Categories
H-RTK mosaic-H

H-RTK mosaic-H Setup & Getting Started (PX4)

Use as Rover (Aircraft) Station

For PX4 v1.15 and later, the guide below does not apply, please visit the PX4 documentation site for the setup guide:
https://docs.px4.io/main/en/gps_compass/septentrio.html
You only need to set the following parameters:
GPS_1_CONFIG: GPS1 (default to GPS1)
GPS_1_GNSS: 31
GPS_1_PROTOCOL: SBF
SER_GPS1_BAUD: 115200 8N1
EKF2_GPS_CTRL: Bit 3 Dual antenna heading (if the Heading function is not required, this bit does not need to be set)
GPS_PITCH_OFFSET: set according to your setup
GPS_YAW_OFFSET: set according to your setup

To check for heading MAVlink Console :
"listener estimator_status_flags " command, Then check the content displayed by cs_gps_yaw . True means that Heading has been enabled , False means that Heading has not been enabled .

GNSS Data Filtering

Set the following parameters to decrease drifting caused by fluctuation from the GNSS reading
EKF2_GPS_P_NOISE = 1
EKF2_GPS_V_NOISE = 0.6

Use as Base Station

The QGC ground station currently cannot recognize the RTCM data stream of Mosaic-H GPS at this moment, therefore QGC does not support the use of this GPS as Basestation.

Leave a Reply

Your email address will not be published. Required fields are marked *


Other Posts

Categories
H-RTK mosaic-H

H-RTK mosaic-H Supported Firmware

PX4 Supported in Stable 1.14.0 and later Ardupilot Supported in ArdupilotNote: Dual-antenna heading is only supported in Ardupilot latest FW or 4.5.0 and later. Mission Planner Supported as Rover (Aircraft) unit & Base station QGC Support when using as Rover (Aircraft) unitQGC currently does not support mosiac-H to be used as base station because it […]


Categories
H-RTK mosaic-H

H-RTK mosaic-H Download

3D CAD File 1MBHX-CH7603a-3Dasm_mosaic_antenna.stp2MBmosaic-h-3D-simple.stp RXTools GNSS receiver control and analysis software. To download the latest version. Please go to this septentrio official download page. 81MBrxtools_23_0_1_installer.exe12MBrxtools_v23.0.1_user_manual.pdfpdf


Categories
H-RTK mosaic-H

H-RTK mosaic-H Overview & Specification

Overview The Holybro mosaic-H is a cutting-edge RTK GPS module that harnesses the power of Septentrio's elite mosaic-H GNSS receiver. It comes with an IST8310 magnetometer, two high-performance antennas, and an aluminum CNC enclosure. It is packed with versatile features such as effortless configuration, spectrum analysis, data logging, and post-processing for a wide range of […]


Categories
H-RTK mosaic-H

H-RTK mosaic-H Pinout

UART1 PinSignalVoltage1(red)VCCPower +5V2RX(in)TTL 3.3V3TX(out)TTL 3.3V4SCL1TTL 3.3V5SDA1TTL 3.3V6SAFETY_SWITCHTTL 3.3V7SAFETY_SWITCH_LEDTTL 3.3V8VDD_3V3Power +3.3V9BUZZER-Open drain Output 0~5V10GNDGND UART2 PinSignalVoltage1(red)VCCPower +5V2RX2(in)TTL 3.3V3TX2(out)TTL 3.3V4EVENT ATTL 3.3V5PPSTTL 3.3V6GNDGND


Categories
H-RTK mosaic-H

H-RTK mosaic-H Setup & Getting Started (Ardupilot)

Use as a Rover (Aircraft) Unit Ardupilot 4.4.0 stable firmware currently also supports Mosaic GPS, but does not yet support dual-antenna Heading. Dual-antenna heading is supported in 4.5.0 and later.To setup this using GPS1 input, configure these parameters: Using serial3 as exampleGPS_INJECT_TO = 0 (send to first GPS)GPS1_RATE_MS = 100GPS1_TYPE = 10 (SBF)SERIAL3_BAUD = 230SERIAL3_PROTOCOL […]