GCS_MAVLink: move orderly rebooting code from GCS into AP_Vehicle

Several places we reboot the vehicle we should probably do several of
the things done in this code - flushing parameters, forcing safety on
etc.
This commit is contained in:
Peter Barker 2020-09-28 11:21:52 +10:00 committed by Peter Barker
parent 3aabb45059
commit 7cb8cde417
2 changed files with 2 additions and 24 deletions

View File

@ -416,7 +416,6 @@ protected:
void handle_common_message(const mavlink_message_t &msg);
void handle_set_gps_global_origin(const mavlink_message_t &msg);
void handle_setup_signing(const mavlink_message_t &msg);
virtual bool should_zero_rc_outputs_on_reboot() const { return false; }
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet);
// reset a message interval via mavlink:

View File

@ -2656,34 +2656,13 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
return MAV_RESULT_UNSUPPORTED;
}
if (should_zero_rc_outputs_on_reboot()) {
SRV_Channels::zero_rc_outputs();
}
// send ack before we reboot
mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED);
// Notify might want to blink some LEDs:
AP_Notify *notify = AP_Notify::get_singleton();
if (notify) {
AP_Notify::flags.firmware_update = 1;
notify->update();
}
// force safety on
hal.rcout->force_safety_on();
// flush pending parameter writes
AP_Param::flush();
// do not process incoming mavlink messages while we delay:
hal.scheduler->register_delay_callback(nullptr, 5);
// delay to give the ACK a chance to get out, the LEDs to flash,
// the IO board safety to be forced on, the parameters to flush, ...
hal.scheduler->delay(200);
// when packet.param1 == 3 we reboot to hold in bootloader
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
hal.scheduler->reboot(hold_in_bootloader);
AP::vehicle()->reboot(hold_in_bootloader); // not expected to return
return MAV_RESULT_FAILED;
}