mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
AntennaTracker: move from MAV_MODE
enum to uint8_t
This commit is contained in:
parent
494af643b5
commit
4ea719e017
@ -6,7 +6,7 @@ MAV_TYPE GCS_Tracker::frame_type() const
|
||||
return MAV_TYPE_ANTENNA_TRACKER;
|
||||
}
|
||||
|
||||
MAV_MODE GCS_MAVLINK_Tracker::base_mode() const
|
||||
uint8_t GCS_MAVLINK_Tracker::base_mode() const
|
||||
{
|
||||
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
// work out the base_mode. This value is not very useful
|
||||
@ -47,7 +47,7 @@ MAV_MODE GCS_MAVLINK_Tracker::base_mode() const
|
||||
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||
}
|
||||
|
||||
return (MAV_MODE)_base_mode;
|
||||
return _base_mode;
|
||||
}
|
||||
|
||||
uint32_t GCS_Tracker::custom_mode() const
|
||||
|
@ -48,7 +48,7 @@ private:
|
||||
|
||||
void send_global_position_int() override;
|
||||
|
||||
MAV_MODE base_mode() const override;
|
||||
uint8_t base_mode() const override;
|
||||
MAV_STATE vehicle_system_status() const override;
|
||||
|
||||
bool waypoint_receiving;
|
||||
|
Loading…
Reference in New Issue
Block a user