Skip to content

Commit

Permalink
Commander: always allow to switch to LAND mode (PX4#23580)
Browse files Browse the repository at this point in the history
Special handling for LAND mode: always allow to switch into it such that if used
as emergency mode it is always available. When triggering it the user generally wants
the vehicle to descend immediately, and if that means to switch to DESCEND it is fine.

Signed-off-by: Silvan Fuhrer <[email protected]>
  • Loading branch information
sfuhrer authored Sep 3, 2024
1 parent 80d4fad commit 6fa6360
Showing 1 changed file with 15 additions and 2 deletions.
17 changes: 15 additions & 2 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -887,7 +887,14 @@ Commander::handle_command(const vehicle_command_s &cmd)
}

if (desired_nav_state != vehicle_status_s::NAVIGATION_STATE_MAX) {
if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd))) {

// Special handling for LAND mode: always allow to switch into it such that if used
// as emergency mode it is always available. When triggering it the user generally wants
// the vehicle to descend immediately, and if that means to switch to DESCEND it is fine.

const bool force = desired_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND;

if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd), false, force)) {
main_ret = TRANSITION_CHANGED;

} else {
Expand Down Expand Up @@ -1062,7 +1069,13 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;

case vehicle_command_s::VEHICLE_CMD_NAV_LAND: {
if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, getSourceFromCommand(cmd))) {
// Special handling for LAND mode: always allow to switch into it such that if used
// as emergency mode it is always available. When triggering it the user generally wants
// the vehicle to descend immediately, and if that means to switch to DESCEND it is fine.
const bool force = true;

if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, getSourceFromCommand(cmd), false,
force)) {
mavlink_log_info(&_mavlink_log_pub, "Landing at current position\t");
events::send(events::ID("commander_landing_current_pos"), events::Log::Info,
"Landing at current position");
Expand Down

0 comments on commit 6fa6360

Please sign in to comment.