PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.2k stars 13.37k forks source link

Dual RTK Heading Problem #21675

Open mrclwtsn opened 1 year ago

mrclwtsn commented 1 year ago

I tried to use Dual RTK Heading function with 2 Holybro H-RTK F9P but failed.

Here is details about my comfiguration: Autopilot: Cube Orange PX4 Version: 1.13.3 Stable GPS_1_CONFIG: 201 GPS_2_CONFIG:202 GPS_UBX_MODE: Heading EKF2_AID_MASK:1

In documantion [(https://docs.px4.io/main/en/gps_compass/u-blox_f9p_heading.html)] its written that for GPS heading we should set EKF2_GPS_CTRL to 3 which is dual antenna heading. The problem is there is no parameters appers in QGC like that. Maybe the parameter name has changed? I think that the documentation is not enough clear. Beside that should we disabled CAL_MAGX_PRIO parameters to use RTK heading function or not needed?

bresch commented 1 year ago

Hi, EKF2_GPS_CTRL is a new parameter that got introduced in version 1.14. In 1.13, the GPS heading was activated using EKF2_AID_MASK (now deprecated). It's not the only thing that changes, we also improved the failure handling logic and I would highly encourage you to try the 1.14 beta version.

Beside that should we disabled CAL_MAGX_PRIO parameters to use RTK heading function or not needed?

You can disable it if you don't want to fallback into mag heading if the GNSS heading data stops. Otherwise, when there is valid GNSS heading data, the mag is not used at all. You can also disable the mag fusion in EKF2_MAG_TYPE instead of disabling it at the driver level.

slgrobotics commented 1 year ago

I was able to make dual-GPS Heading work (dual F9P), but had to tweak code a bit, here is related PR: https://github.com/PX4/PX4-GPSDrivers/pull/131 Also, my settings are: EKF2_GPS_CTRL 15 EKF2_MAG_TYPE 5 SENS_GPS_MASK 0 (Disable GPS blending) SENS_GPS_PRIME 0 (always use Main GPS) GPS_YAW_OFFSET 180 (Moving Base antenna in front of the Rover) I set other parameters to disable IMU etc, but that's not so relevant.

slgrobotics commented 1 year ago

Just in case, there's a related HPPOSLLH pull request:

https://github.com/PX4/PX4-GPSDrivers/pull/136

https://github.com/PX4/PX4-Autopilot/pull/21678

PepperOnioio commented 1 year ago

@slgrobotics, I tried using 1.14 beta with the suggested GPS Parameters. But I can't achieve GPS heading, The UAV is only using Estimation and only achieving Fix type 5. Current HW is the following: FC: mRo H7 Zero GPS: 2x mRo u-Blox ZED-F9 RTK L1/L2 GPS

The GPS' are connected to each other and each is connected to the FC(Main on GPS1 and Secondary on Serial 3). Maybe I'm missing something. GPS heading worked on 1.12.3, but the error handling was bad. Parameter File: GPS_test_071323.txt

slgrobotics commented 1 year ago

@PepperOnioio - please make sure that you pulled the latest from https://github.com/PX4/PX4-Autopilot/tree/main -as the important changes to GPSDriver submodule and converting lat/lon/alt to "double" were merged in just hours ago (https://github.com/PX4/PX4-Autopilot/pull/21678)

Try "gps status" - it should show both GPS in fix_type "6" for "heading" to become valid and show up there under main gps. Secondary GPS should be your Moving Base, main - your Rover. Look at coordinates for both antennas - does the position shift agree with your antennas location?

Your Moving Base GPS must be connected to the RTCM feed from the Land base station. Same for your Rover GPS. And only then you'll have exact coordinates on both.

It would be helpful to see a diagram of your connections, like in https://github.com/PX4/PX4-GPSDrivers/pull/131 - all ports, feeds etc.

And see if anything in ubx.cpp / ubx.h looks not applicable to your setup (specifically look for RELPOSNED).

My startup file is here, maybe you find some useful settings there:

https://github.com/slgrobotics/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/airframes/50003_lawnMower1_config

PepperOnioio commented 1 year ago

Thanks for getting back to me. For context, we just want to achieve GPS Yaw, so we don't have a Land Base station. GPS1 UART1 - Main is connected to the flight controller on UART4 GPS2 UART1 - Secondary is connected to the flight controller on UART8 GPS1 UART2 is connected to GPS2 UART2 And the GPS' are 70cm apart and the Main GPS is at 270 degree, whilst Secondary GPS is at 90 degrees.

Untitled Diagram (1)

As previously mentioned, we used this setup successfully with 1.12.3 Stable and even 1.13.3 Stable, but every time we jammed the GPS, the estimated yaw started rotating CCW and would stop, even after regaining GPS. Only after a restart, it would work correctly again.

I'll try again today with the newest firmware, and post the result.

slgrobotics commented 1 year ago

@PepperOnioio - Thanks, that makes things a bit more clear. I would be specifically interested if "gps status" shows Main GPS in _fixtype 6, and heading showing up as a number, not nan.

I am pretty sure that PX4 sends all necessary setup commands to F9P, but just in case I reset my two units (SparkFun F9P's) to factory settings.

I ran my lawnmower yesterday with freshly compiled code from the "main" branch, and everything worked fine. I run on Raspberry Pi 3B, so I can put tracing printf's in the code and see, for example, if certain UBX messages arrive and are being processed by PX4 in ubx.cpp. Not sure if you have that option with your FC.

PepperOnioio commented 1 year ago

@slgrobotics - I haven't been able to make it work yet. I did check the status on the GPS1 - and the heading is 0. I don't think I can read the UBX messages through the flight controller. mavdlink

slgrobotics commented 1 year ago

@PepperOnioio - I see fix-type being 5 in your screen shot, which means "float". F9P would only deliver heading when _fixtype is 6 ("fixed"). Basically, until your Rover GPS is in "fixed" mode, you cannot expect heading to show up.

It's a rainy day here, and my lawnmower is parked. When I run it I will tale a look at MAVLINK messages and see what they show. So far I haven't done that, as I was looking at console messages - one of the advantages of having a Raspberry Pi as a controller.

It might be useful to connect a PC with u-Center app to your Rover GPS and see what exactly is happening there. If RTCM flow from Moving Base is unaffected, and Rover GPS catches "fixed" mode - u-Center will show RELPOSNED and all.

slgrobotics commented 1 year ago

@PepperOnioio - I did two experiments with my setup.

In my case, same as yours, UART2 of both devices are connected together, TX->RX, RX<-TX - to allow RTCM corrections to flow from Moving Base to Rover.

  1. With the Land Station ON, both Moving Base and Rover GPS'es have _fixtype 6. Heading ("yaw") appears on the main GPS. I have RTK precision (1.4 cm) on my Main GPS, and can see the same on the Moving Base.
pxh> gps status
INFO  [gps] Main GPS
INFO  [gps] protocol: UBX
INFO  [gps] status: OK, port: /dev/ttyACM1, baudrate: 460800
INFO  [gps] sat info: disabled
INFO  [gps] rate reading:         2173 B/s
INFO  [gps] rate position:        4.75 Hz
INFO  [gps] rate velocity:        4.75 Hz
INFO  [gps] rate publication:         4.75 Hz
INFO  [gps] rate RTCM injection:      0.00 Hz
 sensor_gps
    timestamp: 1327926743 (0.003507 seconds ago)
    timestamp_sample: 0
    altitude_ellipsoid_m: 116.155800
    time_utc_usec: 1690140718874546
        ...
    heading: -0.69779
    heading_offset: -3.14159
    heading_accuracy: 0.00988
    rtcm_injection_rate: 0.00000
    automatic_gain_control: 0
    fix_type: 6
    jamming_state: 2
    spoofing_state: 1
    vel_ned_valid: True
    satellites_used: 29
    selected_rtcm_instance: 0
    rtcm_crc_failed: False
    rtcm_msg_used: 2

INFO  [gps] 
INFO  [gps] Secondary GPS
INFO  [gps] protocol: UBX
INFO  [gps] status: OK, port: /dev/ttyACM0, baudrate: 460800
INFO  [gps] sat info: disabled
INFO  [gps] rate reading:         1878 B/s
INFO  [gps] rate position:        8.72 Hz
INFO  [gps] rate velocity:        8.72 Hz
INFO  [gps] rate publication:         8.72 Hz
INFO  [gps] rate RTCM injection:      0.00 Hz
 sensor_gps
      ...
    heading: nan
    heading_offset: -3.14159
    heading_accuracy: 0.00000
    rtcm_injection_rate: 0.00000
    automatic_gain_control: 0
    fix_type: 6
    jamming_state: 1
    spoofing_state: 1
    vel_ned_valid: True
    satellites_used: 28
    selected_rtcm_instance: 0
    rtcm_crc_failed: False
    rtcm_msg_used: 2

pxh> 
  1. With the Land Station OFF, Moving Base has _fixtype 4 and Rover GPS'es have _fixtype 6. Heading ("yaw") appears on the main GPS.
pxh> gps status
INFO  [gps] Main GPS
INFO  [gps] protocol: UBX
INFO  [gps] status: OK, port: /dev/ttyACM1, baudrate: 460800
INFO  [gps] sat info: disabled
INFO  [gps] rate reading:         2150 B/s
INFO  [gps] rate position:        4.76 Hz
INFO  [gps] rate velocity:        4.76 Hz
INFO  [gps] rate publication:         4.76 Hz
INFO  [gps] rate RTCM injection:      0.00 Hz
 sensor_gps
      ...
    heading: -0.70024
    heading_offset: -3.14159
    heading_accuracy: 0.00989
    rtcm_injection_rate: 0.00000
    automatic_gain_control: 0
    fix_type: 6
    jamming_state: 2
    spoofing_state: 1
    vel_ned_valid: True
    satellites_used: 27
    selected_rtcm_instance: 0
    rtcm_crc_failed: False
    rtcm_msg_used: 2

INFO  [gps] 
INFO  [gps] Secondary GPS
INFO  [gps] protocol: UBX
INFO  [gps] status: OK, port: /dev/ttyACM0, baudrate: 460800
INFO  [gps] sat info: disabled
INFO  [gps] rate reading:         1752 B/s
INFO  [gps] rate position:        8.72 Hz
INFO  [gps] rate velocity:        8.72 Hz
INFO  [gps] rate publication:         8.72 Hz
INFO  [gps] rate RTCM injection:      0.00 Hz
 sensor_gps
        ...
    heading: nan
    heading_offset: -3.14159
    heading_accuracy: 0.00000
    rtcm_injection_rate: 0.00000
    automatic_gain_control: 0
    fix_type: 4
    jamming_state: 1
    spoofing_state: 1
    vel_ned_valid: True
    satellites_used: 28
    selected_rtcm_instance: 0
    rtcm_crc_failed: False
    rtcm_msg_used: 2
main_gps secondary_gps
slgrobotics commented 1 year ago

@PepperOnioio - BTW, fix_type 5 (float) in your case means that the Main GPS is receiving RTCMs from the Secondary, so the UART2's in both devices are initialized properly by GPSDriver code. But your GPSes don't seem to get to the state when they computed all necessary corrections and can deliver RTK precision (mode 6).

Takayama75 commented 10 months ago

I was able to make dual-GPS Heading work (dual F9P), but had to tweak code a bit, here is related PR: PX4/PX4-GPSDrivers#131 Also, my settings are: EKF2_GPS_CTRL 15 EKF2_MAG_TYPE 5 SENS_GPS_MASK 0 (Disable GPS blending) SENS_GPS_PRIME 0 (always use Main GPS) GPS_YAW_OFFSET 180 (Moving Base antenna in front of the Rover) I set other parameters to disable IMU etc, but that's not so relevant.

Could you share the other parameters you set? I tried to disable compass and/or IMU. However, the arm was rejected by 0 Compass error etc. Even if dual antenna GPS installed and EKF2_MAG_TYPE is set to 5, is compass still required for arm?

slgrobotics commented 10 months ago

@Takayama75 - my guess is that EKF2 and arming checks are independent. There may be a flag/bit in a parameter that disables compass check when arming. My robot has magnetometer(s), but I make EKF2 ignore them. Arming check still sees them though. My parameters setup file is here: https://github.com/slgrobotics/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/airframes/50005_lawnMower1_config

darshankt commented 9 months ago

Hi, I'm working with 1.13.0 & trying setup C-RTK dual antennas device as heading system. Based on my version of firmware i don't have EKF2_GPS_CTRL param and I have to EKF2_AID_MASK param for heading. Even though i have set EKF2_AID_Mask param for heading, my system still using compass magnetometers as heading. I don't know I need to setup any other parameters to along with EKF2_AID_MASK to enable heading system. Also how can I verify heading system using Dual antenna for Yaw estimation.

saengphet commented 9 months ago

Hi @darshankt I am interested in using the C-RTK duak antenna (CUAV?) too. Is the device now supported by PX4? The parameter you mentioned appears in firmware v1.14. Do you plan to test it?

As it has the same function as the H-RTK Unicore UM982 (Dual Antenna), it is interesting to read these posts too. https://github.com/PX4/PX4-Autopilot/issues/22163 https://discuss.px4.io/t/um982-isnt-providing-heading-data/35195

darshankt commented 9 months ago

I'm still figuring it out, I have tested in v1.13.0 but no luck and now planning move to v1.14.0. If you have PX4 with 1.14.0 please test with parameters and let me know.

Thank you Darshan

On Sun, Dec 10, 2023, 6:08 PM saengphet @.***> wrote:

Hi @darshankt https://github.com/darshankt I am interested in using the C-RTK duak antenna (CUAV?) too. Is the device now supported by PX4? The parameter you mentioned appears in firmware v1.14. Do you plan to test it?

As it has the same function as the H-RTK Unicore UM982 (Dual Antenna), it is interesting to read these posts too.

22163 https://github.com/PX4/PX4-Autopilot/issues/22163

https://discuss.px4.io/t/um982-isnt-providing-heading-data/35195

— Reply to this email directly, view it on GitHub https://github.com/PX4/PX4-Autopilot/issues/21675#issuecomment-1849022973, or unsubscribe https://github.com/notifications/unsubscribe-auth/AKLQEB6KCXIJSBVEL4SITATYIXT7VAVCNFSM6AAAAAAYZ6655KVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMYTQNBZGAZDEOJXGM . You are receiving this because you were mentioned.Message ID: @.***>

slgrobotics commented 3 months ago

I filed a new issue related to EKF2 handling of RTK GPS data - https://github.com/PX4/PX4-Autopilot/issues/23157

This cured my rover of weaving around straight lines.

Also, just for anybody who may be guessing how to properly run GPS driver with dual F9P devices (it isn't that obvious ;-)):

gps start -d /dev/ttyACM1 -b 460800 -e /dev/ttyACM0 -g 460800