From fe421712683ade62ae9ffbcaf68b7ff8052c64b8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 22 Apr 2024 08:30:46 +1000 Subject: [PATCH] AP_GPS: make get_RelPosHeading boolean --- libraries/AP_GPS/AP_GPS.cpp | 4 +++- libraries/AP_GPS/AP_GPS.h | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 91b7c0dcd1..73829001c8 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -980,7 +980,7 @@ void AP_GPS::update_instance(uint8_t instance) #if GPS_MOVING_BASELINE -void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) +bool AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) { for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) { if (drivers[i] && @@ -991,8 +991,10 @@ void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float relPosD = state[i].relPosD; accHeading = state[i].accHeading; timestamp = state[i].relposheading_ts; + return true; } } + return false; } bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 7087983107..e45aef88c4 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -594,7 +594,7 @@ public: #if GPS_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 get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading); + bool get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED; bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len); void clear_RTCMV3(); #endif // GPS_MOVING_BASELINE