Browse Source

AP_OADatabase: remove unnecessary const on arguments

also swap order of angle and distance arguments to be consistent with proximity library
c415-sdk
Randy Mackay 5 years ago
parent
commit
1ba5f4626d
  1. 2
      libraries/AC_Avoidance/AP_OADatabase.cpp
  2. 4
      libraries/AC_Avoidance/AP_OADatabase.h

2
libraries/AC_Avoidance/AP_OADatabase.cpp

@ -106,7 +106,7 @@ void AP_OADatabase::update() @@ -106,7 +106,7 @@ void AP_OADatabase::update()
}
// push a location into the database
void AP_OADatabase::queue_push(const Location &loc, const uint32_t timestamp_ms, const float distance, const float angle)
void AP_OADatabase::queue_push(const Location &loc, uint32_t timestamp_ms, float angle, float distance)
{
if (!healthy()) {
return;

4
libraries/AC_Avoidance/AP_OADatabase.h

@ -37,7 +37,7 @@ public: @@ -37,7 +37,7 @@ public:
void update();
// push a location into the database
void queue_push(const Location &loc, const uint32_t timestamp_ms, const float distance, const float angle);
void queue_push(const Location &loc, uint32_t timestamp_ms, float angle, float distance);
// returns true if database is healthy
bool healthy() const { return (_queue.items != nullptr) && (_database.items != nullptr); }
@ -131,7 +131,7 @@ class AP_OADatabase { @@ -131,7 +131,7 @@ class AP_OADatabase {
public:
static AP_OADatabase *get_singleton() { return nullptr; }
void init() {};
void queue_push(const Location &loc, const uint32_t timestamp_ms, const float distance, const float angle) {};
void queue_push(const Location &loc, uint32_t timestamp_ms, float angle, float distance) {};
bool healthy() const { return false; }
void send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms) {};
};

Loading…
Cancel
Save