mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
Sub: move base_mode and frame_type into GCS from GCS_MAVLink
This commit is contained in:
parent
e5818308b9
commit
1ce531b921
@ -17,7 +17,7 @@ void Sub::gcs_send_heartbeat()
|
||||
* pattern below when adding any new messages
|
||||
*/
|
||||
|
||||
MAV_TYPE GCS_MAVLINK_Sub::frame_type() const
|
||||
MAV_TYPE GCS_Sub::frame_type() const
|
||||
{
|
||||
return MAV_TYPE_SUBMARINE;
|
||||
}
|
||||
@ -62,7 +62,7 @@ MAV_MODE GCS_MAVLINK_Sub::base_mode() const
|
||||
return (MAV_MODE)_base_mode;
|
||||
}
|
||||
|
||||
uint32_t GCS_MAVLINK_Sub::custom_mode() const
|
||||
uint32_t GCS_Sub::custom_mode() const
|
||||
{
|
||||
return sub.control_mode;
|
||||
}
|
||||
|
@ -50,9 +50,7 @@ private:
|
||||
|
||||
bool send_info(void);
|
||||
|
||||
MAV_TYPE frame_type() const override;
|
||||
MAV_MODE base_mode() const override;
|
||||
uint32_t custom_mode() const override;
|
||||
MAV_STATE system_status() const override;
|
||||
|
||||
int16_t vfr_hud_throttle() const override;
|
||||
|
@ -22,6 +22,9 @@ public:
|
||||
|
||||
void update_sensor_status_flags() override;
|
||||
|
||||
uint32_t custom_mode() const override;
|
||||
MAV_TYPE frame_type() const override;
|
||||
|
||||
private:
|
||||
|
||||
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
Loading…
Reference in New Issue
Block a user