mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: move mavlink reboot code up to base class
This commit is contained in:
parent
c84b102c1c
commit
320e24af65
@ -753,6 +753,11 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
|
||||
GCS_MAVLINK::packetReceived(status, msg);
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK_Plane::should_disable_overrides_on_reboot() const
|
||||
{
|
||||
return (plane.quadplane.enable != 0);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
switch (msg->msgid) {
|
||||
@ -993,10 +998,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
result = handle_preflight_reboot(packet, plane.quadplane.enable != 0);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
result = MAV_RESULT_FAILED;
|
||||
|
||||
|
@ -27,6 +27,7 @@ protected:
|
||||
uint8_t sysid_my_gcs() const override;
|
||||
|
||||
bool set_mode(uint8_t mode) override;
|
||||
bool should_disable_overrides_on_reboot() const override;
|
||||
|
||||
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
|
Loading…
Reference in New Issue
Block a user