AP_OADatabase: remove unnecessary const on arguments

also swap order of angle and distance arguments to be consistent with proximity library
This commit is contained in:
Randy Mackay 2019-11-27 16:52:32 +09:00 committed by Andrew Tridgell
parent 5462aeae01
commit 717cd707dc
2 changed files with 3 additions and 3 deletions

View File

@ -106,7 +106,7 @@ void AP_OADatabase::update()
} }
// push a location into the database // 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()) { if (!healthy()) {
return; return;

View File

@ -37,7 +37,7 @@ public:
void update(); void update();
// push a location into the database // 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 // returns true if database is healthy
bool healthy() const { return (_queue.items != nullptr) && (_database.items != nullptr); } bool healthy() const { return (_queue.items != nullptr) && (_database.items != nullptr); }
@ -131,7 +131,7 @@ class AP_OADatabase {
public: public:
static AP_OADatabase *get_singleton() { return nullptr; } static AP_OADatabase *get_singleton() { return nullptr; }
void init() {}; 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; } bool healthy() const { return false; }
void send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms) {}; void send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms) {};
}; };