mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
Rover: move from MAV_MODE
enum to uint8_t
This commit is contained in:
parent
c07863f6cd
commit
2730777785
@ -15,7 +15,7 @@ MAV_TYPE GCS_Rover::frame_type() const
|
|||||||
return MAV_TYPE_GROUND_ROVER;
|
return MAV_TYPE_GROUND_ROVER;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_MODE GCS_MAVLINK_Rover::base_mode() const
|
uint8_t GCS_MAVLINK_Rover::base_mode() const
|
||||||
{
|
{
|
||||||
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||||
|
|
||||||
@ -49,7 +49,7 @@ MAV_MODE GCS_MAVLINK_Rover::base_mode() const
|
|||||||
// indicate we have set a custom mode
|
// indicate we have set a custom mode
|
||||||
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||||
|
|
||||||
return (MAV_MODE)_base_mode;
|
return _base_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t GCS_Rover::custom_mode() const
|
uint32_t GCS_Rover::custom_mode() const
|
||||||
|
@ -59,7 +59,7 @@ private:
|
|||||||
|
|
||||||
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
MAV_MODE base_mode() const override;
|
uint8_t base_mode() const override;
|
||||||
MAV_STATE vehicle_system_status() const override;
|
MAV_STATE vehicle_system_status() const override;
|
||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
Loading…
Reference in New Issue
Block a user