mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: avoid using struct Location
clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
parent
c871aaefb7
commit
c49c638d41
|
@ -490,7 +490,7 @@ void GCS_MAVLINK_Tracker::handleMessage(const mavlink_message_t &msg)
|
|||
|
||||
mavlink_msg_mission_item_decode(&msg, &packet);
|
||||
|
||||
struct Location tell_command;
|
||||
Location tell_command;
|
||||
|
||||
switch (packet.frame)
|
||||
{
|
||||
|
|
|
@ -102,7 +102,7 @@ private:
|
|||
AP_BattMonitor battery{MASK_LOG_CURRENT,
|
||||
FUNCTOR_BIND_MEMBER(&Tracker::handle_battery_failsafe, void, const char*, const int8_t),
|
||||
nullptr};
|
||||
struct Location current_loc;
|
||||
Location current_loc;
|
||||
|
||||
Mode *mode_from_mode_num(enum Mode::Number num);
|
||||
|
||||
|
@ -202,7 +202,7 @@ private:
|
|||
|
||||
// system.cpp
|
||||
void init_ardupilot() override;
|
||||
bool get_home_eeprom(struct Location &loc) const;
|
||||
bool get_home_eeprom(Location &loc) const;
|
||||
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
|
||||
bool set_home(const Location &temp) WARN_IF_UNUSED;
|
||||
void prepare_servos();
|
||||
|
|
|
@ -102,7 +102,7 @@ void Tracker::init_ardupilot()
|
|||
/*
|
||||
fetch HOME from EEPROM
|
||||
*/
|
||||
bool Tracker::get_home_eeprom(struct Location &loc) const
|
||||
bool Tracker::get_home_eeprom(Location &loc) const
|
||||
{
|
||||
// Find out proper location in memory by using the start_byte position + the index
|
||||
// --------------------------------------------------------------------------------
|
||||
|
|
Loading…
Reference in New Issue