mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_GPS: don't consume Heading message if we have RelPosHeading
this avoids 2 conflicting yaw sources
This commit is contained in:
parent
69cb6796f3
commit
761e4a05e2
@ -545,6 +545,14 @@ void AP_GPS_UAVCAN::handle_aux_msg(const AuxCb &cb)
|
||||
|
||||
void AP_GPS_UAVCAN::handle_heading_msg(const HeadingCb &cb)
|
||||
{
|
||||
#if GPS_MOVING_BASELINE
|
||||
if (seen_relposheading && gps.mb_params[interim_state.instance].type.get() != 0) {
|
||||
// we prefer to use the relposheading to get yaw as it allows
|
||||
// the user to more easily control the relative antenna positions
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
WITH_SEMAPHORE(sem);
|
||||
|
||||
if (interim_state.gps_yaw_configured == false) {
|
||||
@ -606,6 +614,7 @@ void AP_GPS_UAVCAN::handle_relposheading_msg(const RelPosHeadingCb &cb, uint8_t
|
||||
WITH_SEMAPHORE(sem);
|
||||
|
||||
interim_state.gps_yaw_configured = true;
|
||||
seen_relposheading = true;
|
||||
// push raw heading data to calculate moving baseline heading states
|
||||
if (calculate_moving_base_yaw(interim_state,
|
||||
cb.msg->reported_heading_deg,
|
||||
|
@ -111,6 +111,7 @@ private:
|
||||
bool seen_fix2;
|
||||
bool seen_aux;
|
||||
bool seen_status;
|
||||
bool seen_relposheading;
|
||||
|
||||
bool healthy;
|
||||
uint32_t status_flags;
|
||||
|
Loading…
Reference in New Issue
Block a user