AP_GPS: make get_RelPosHeading boolean

This commit is contained in:
Andrew Tridgell 2024-04-22 08:30:46 +10:00
parent 4e29e1e6b0
commit fe42171268
2 changed files with 4 additions and 2 deletions

View File

@ -980,7 +980,7 @@ void AP_GPS::update_instance(uint8_t instance)
#if GPS_MOVING_BASELINE #if GPS_MOVING_BASELINE
void AP_GPS::get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) bool AP_GPS::get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading)
{ {
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) { for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
if (drivers[i] && if (drivers[i] &&
@ -991,8 +991,10 @@ void AP_GPS::get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float
relPosD = state[i].relPosD; relPosD = state[i].relPosD;
accHeading = state[i].accHeading; accHeading = state[i].accHeading;
timestamp = state[i].relposheading_ts; timestamp = state[i].relposheading_ts;
return true;
} }
} }
return false;
} }
bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)

View File

@ -594,7 +594,7 @@ public:
#if GPS_MOVING_BASELINE #if GPS_MOVING_BASELINE
// methods used by UAVCAN GPS driver and AP_Periph for moving baseline // methods used by UAVCAN GPS driver and AP_Periph for moving baseline
void inject_MBL_data(uint8_t* data, uint16_t length); void inject_MBL_data(uint8_t* data, uint16_t length);
void get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading); bool get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED;
bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len); bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len);
void clear_RTCMV3(); void clear_RTCMV3();
#endif // GPS_MOVING_BASELINE #endif // GPS_MOVING_BASELINE