Handle MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN 'Do nothing for autopilot'

This commit is contained in:
Nick Steele 2019-10-18 09:37:22 -04:00 committed by Daniel Agar
parent 08ec6a28f0
commit 070d75496d
1 changed files with 6 additions and 0 deletions

View File

@ -3405,6 +3405,12 @@ void *commander_low_prio_loop(void *arg)
switch (cmd.command) {
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (((int)(cmd.param1)) == 0) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
/* do nothing for autopilot */
break;
}
if (is_safe(safety, armed)) {
if (((int)(cmd.param1)) == 1) {