mirror of https://github.com/ArduPilot/ardupilot
APM: reboot only works on the APM2
This commit is contained in:
parent
d08bd4214b
commit
29344e688d
|
@ -1112,8 +1112,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
if (packet.param1 == 1) {
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
reboot_apm();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
|
@ -571,6 +571,7 @@ uint16_t board_voltage(void)
|
|||
}
|
||||
|
||||
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
/*
|
||||
force a software reset of the APM
|
||||
*/
|
||||
|
@ -584,3 +585,4 @@ static void reboot_apm(void)
|
|||
wdt_enable(WDTO_15MS);
|
||||
while (1);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue