mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
ArduSub: move from MAV_MODE
enum to uint8_t
This commit is contained in:
parent
aef376f1c7
commit
77b8d90226
@ -8,7 +8,7 @@ MAV_TYPE GCS_Sub::frame_type() const
|
||||
return MAV_TYPE_SUBMARINE;
|
||||
}
|
||||
|
||||
MAV_MODE GCS_MAVLINK_Sub::base_mode() const
|
||||
uint8_t GCS_MAVLINK_Sub::base_mode() const
|
||||
{
|
||||
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
|
||||
@ -45,7 +45,7 @@ MAV_MODE GCS_MAVLINK_Sub::base_mode() const
|
||||
// indicate we have set a custom mode
|
||||
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
|
||||
return (MAV_MODE)_base_mode;
|
||||
return _base_mode;
|
||||
}
|
||||
|
||||
uint32_t GCS_Sub::custom_mode() const
|
||||
|
@ -49,7 +49,7 @@ private:
|
||||
|
||||
bool send_info(void);
|
||||
|
||||
MAV_MODE base_mode() const override;
|
||||
uint8_t base_mode() const override;
|
||||
MAV_STATE vehicle_system_status() const override;
|
||||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
Loading…
Reference in New Issue
Block a user