Rover: move from MAV_MODE enum to uint8_t

This commit is contained in:
Iampete1 2025-02-10 12:29:57 +00:00 committed by Peter Barker
parent c07863f6cd
commit 2730777785
2 changed files with 3 additions and 3 deletions

View File

@ -15,7 +15,7 @@ MAV_TYPE GCS_Rover::frame_type() const
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;
@ -49,7 +49,7 @@ MAV_MODE GCS_MAVLINK_Rover::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_Rover::custom_mode() const

View File

@ -59,7 +59,7 @@ private:
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;
int16_t vfr_hud_throttle() const override;