mirror of https://github.com/ArduPilot/ardupilot
Sub: move mavlink reboot code up to base class
This commit is contained in:
parent
320e24af65
commit
e0eb3424ec
|
@ -941,29 +941,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
||||
// Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short
|
||||
// For that matter, send an invalid signal to all channels to prevent undesired/unexpected behavior
|
||||
SRV_Channels::cork();
|
||||
for (int i=0; i<NUM_RC_CHANNELS; i++) {
|
||||
// Set to 1 because 0 is interpreted as flag to ignore update
|
||||
hal.rcout->write(i, 1);
|
||||
}
|
||||
SRV_Channels::push();
|
||||
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
// send ack before we reboot
|
||||
mavlink_msg_command_ack_send_buf(msg, chan, packet.command, result);
|
||||
|
||||
AP_Notify::flags.firmware_update = 1;
|
||||
sub.notify.update();
|
||||
hal.scheduler->delay(200);
|
||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
||||
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
#if AC_FENCE == ENABLED
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
|
|
|
@ -22,6 +22,7 @@ protected:
|
|||
uint8_t sysid_my_gcs() const override;
|
||||
|
||||
bool set_mode(uint8_t mode) override;
|
||||
bool should_zero_rc_outputs_on_reboot() const override { return true; }
|
||||
|
||||
MAV_RESULT _handle_command_preflight_calibration_baro() override;
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
|
|
Loading…
Reference in New Issue