forked from Archive/PX4-Autopilot
commander: CMD_NAV_LAND/CMD_NAV_PRECLAND reply RESULT_ACCEPTED unless transition is denied
This commit is contained in:
parent
80068093d6
commit
49d4cc7d5b
|
@ -893,7 +893,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
|||
break;
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_NAV_LAND: {
|
||||
if (TRANSITION_CHANGED == main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_LAND, _status_flags,
|
||||
if (TRANSITION_DENIED != main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_LAND, _status_flags,
|
||||
&_internal_state)) {
|
||||
mavlink_log_info(&_mavlink_log_pub, "Landing at current position");
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
@ -906,8 +906,8 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
|||
break;
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_NAV_PRECLAND: {
|
||||
if (TRANSITION_CHANGED == main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_PRECLAND,
|
||||
_status_flags, &_internal_state)) {
|
||||
if (TRANSITION_DENIED != main_state_transition(_status, commander_state_s::MAIN_STATE_AUTO_PRECLAND, _status_flags,
|
||||
&_internal_state)) {
|
||||
mavlink_log_info(&_mavlink_log_pub, "Precision landing");
|
||||
cmd_result = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
|
|
Loading…
Reference in New Issue