Browse Source

commander: Support enabling and disabling lockdown

sbg
Lorenz Meier 9 years ago
parent
commit
c8492454e9
  1. 21
      src/modules/commander/commander.cpp

21
src/modules/commander/commander.cpp

@ -471,6 +471,12 @@ int commander_main(int argc, char *argv[]) @@ -471,6 +471,12 @@ int commander_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "lockdown")) {
if (argc < 3) {
usage("not enough arguments, missing [on, off]");
return 1;
}
int mavlink_fd_local = px4_open(MAVLINK_LOG_DEVICE, 0);
vehicle_command_s cmd = {};
@ -478,7 +484,8 @@ int commander_main(int argc, char *argv[]) @@ -478,7 +484,8 @@ int commander_main(int argc, char *argv[])
cmd.target_component = status.component_id;
cmd.command = vehicle_command_s::VEHICLE_CMD_DO_FLIGHTTERMINATION;
cmd.param1 = 2.0f; /* lockdown */
/* if the comparison matches for off (== 0) set 0.0f, 2.0f (on) else */
cmd.param1 = strcmp(argv[2], "off") ? 2.0f : 0.0f; /* lockdown */
// XXX inspect use of publication handle
(void)orb_advertise(ORB_ID(vehicle_command), &cmd);
@ -809,12 +816,6 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -809,12 +816,6 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
armed_local->force_failsafe = true;
warnx("forcing failsafe (termination)");
} else {
armed_local->force_failsafe = false;
armed_local->lockdown = false;
warnx("disabling failsafe (termination)");
}
/* param2 is currently used for other failsafe modes */
status_local->engine_failure_cmd = false;
status_local->data_link_lost_cmd = false;
@ -852,7 +853,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s @@ -852,7 +853,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
warnx("vtol transition failure mode commanded");
}
} else {
armed_local->force_failsafe = false;
armed_local->lockdown = false;
warnx("disabling failsafe and lockdown");
}
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
}

Loading…
Cancel
Save