Skip to content

Commit

Permalink
AP_DAL: remove tmp_location from global namespace
Browse files Browse the repository at this point in the history
removes this from the global namespace and means it isn't included when DAL isn't

update the location where we update the fields.
  • Loading branch information
peterbarker committed Dec 10, 2023
1 parent 273e079 commit 258ef75
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 13 deletions.
16 changes: 4 additions & 12 deletions libraries/AP_DAL/AP_DAL_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,6 @@
#include <AP_Logger/AP_Logger.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()
{
for (uint8_t i=0; i<ARRAY_SIZE(_RGPI); i++) {
Expand All @@ -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()
{
const auto &gps = AP::gps();
Expand Down Expand Up @@ -61,5 +49,9 @@ void AP_DAL_GPS::start_frame()

WRITE_REPLAY_BLOCK_IFCHANGED(RGPI, RGPI, old_RGPI);
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;
}
}
10 changes: 9 additions & 1 deletion libraries/AP_DAL/AP_DAL_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,9 @@ class AP_DAL_GPS {
GPS_Status status() const {
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 {
return _RGPI[instance].have_vertical_velocity;
}
Expand Down Expand Up @@ -125,11 +127,17 @@ class AP_DAL_GPS {
}
void handle_message(const log_RGPJ &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:

struct log_RGPH _RGPH;
struct log_RGPI _RGPI[GPS_MAX_INSTANCES];
struct log_RGPJ _RGPJ[GPS_MAX_INSTANCES];

Location tmp_location[GPS_MAX_INSTANCES];
};

0 comments on commit 258ef75

Please sign in to comment.