AP_DAL: remove tmp_location from global namespace

removes this from the global namespace and means it isn't included when DAL isn't

update the location where we update the fields.
This commit is contained in:
Peter Barker 2023-12-10 08:55:59 +11:00 committed by Andrew Tridgell
parent 5642d2449a
commit 58d4871177
2 changed files with 13 additions and 13 deletions

View File

@ -3,9 +3,6 @@
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include "AP_DAL.h" #include "AP_DAL.h"
// we use a static here as the "location" accessor wants to be const
static Location tmp_location[GPS_MAX_INSTANCES];
AP_DAL_GPS::AP_DAL_GPS() AP_DAL_GPS::AP_DAL_GPS()
{ {
for (uint8_t i=0; i<ARRAY_SIZE(_RGPI); i++) { for (uint8_t i=0; i<ARRAY_SIZE(_RGPI); i++) {
@ -14,15 +11,6 @@ AP_DAL_GPS::AP_DAL_GPS()
} }
} }
const Location &AP_DAL_GPS::location(uint8_t instance) const
{
Location &loc = tmp_location[instance];
loc.lat = _RGPJ[instance].lat;
loc.lng = _RGPJ[instance].lng;
loc.alt = _RGPJ[instance].alt;
return loc;
}
void AP_DAL_GPS::start_frame() void AP_DAL_GPS::start_frame()
{ {
const auto &gps = AP::gps(); const auto &gps = AP::gps();
@ -61,5 +49,9 @@ void AP_DAL_GPS::start_frame()
WRITE_REPLAY_BLOCK_IFCHANGED(RGPI, RGPI, old_RGPI); WRITE_REPLAY_BLOCK_IFCHANGED(RGPI, RGPI, old_RGPI);
WRITE_REPLAY_BLOCK_IFCHANGED(RGPJ, RGPJ, old_RGPJ); WRITE_REPLAY_BLOCK_IFCHANGED(RGPJ, RGPJ, old_RGPJ);
tmp_location[i].lat = RGPJ.lat;
tmp_location[i].lng = RGPJ.lng;
tmp_location[i].alt = RGPJ.alt;
} }
} }

View File

@ -26,7 +26,9 @@ public:
GPS_Status status() const { GPS_Status status() const {
return status(primary_sensor()); return status(primary_sensor());
} }
const Location &location(uint8_t instance) const; const Location &location(uint8_t instance) const {
return tmp_location[instance];
}
bool have_vertical_velocity(uint8_t instance) const { bool have_vertical_velocity(uint8_t instance) const {
return _RGPI[instance].have_vertical_velocity; return _RGPI[instance].have_vertical_velocity;
} }
@ -125,6 +127,10 @@ public:
} }
void handle_message(const log_RGPJ &msg) { void handle_message(const log_RGPJ &msg) {
_RGPJ[msg.instance] = msg; _RGPJ[msg.instance] = msg;
tmp_location[msg.instance].lat = msg.lat;
tmp_location[msg.instance].lng = msg.lng;
tmp_location[msg.instance].alt = msg.alt;
} }
private: private:
@ -132,4 +138,6 @@ private:
struct log_RGPH _RGPH; struct log_RGPH _RGPH;
struct log_RGPI _RGPI[GPS_MAX_INSTANCES]; struct log_RGPI _RGPI[GPS_MAX_INSTANCES];
struct log_RGPJ _RGPJ[GPS_MAX_INSTANCES]; struct log_RGPJ _RGPJ[GPS_MAX_INSTANCES];
Location tmp_location[GPS_MAX_INSTANCES];
}; };