mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: move mavlink reboot code up to base class
This commit is contained in:
parent
11df6debd0
commit
e1408696dc
@ -676,14 +676,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
|
||||||
if (is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f)) {
|
|
||||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
|
||||||
hal.scheduler->reboot(is_equal(packet.param1, 3.0f));
|
|
||||||
result = MAV_RESULT_ACCEPTED;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||||
if (is_equal(packet.param1, 1.0f)) {
|
if (is_equal(packet.param1, 1.0f)) {
|
||||||
// run pre_arm_checks and arm_checks and display failures
|
// run pre_arm_checks and arm_checks and display failures
|
||||||
|
Loading…
Reference in New Issue
Block a user