mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
commander delete unused vtol_transition_failure_cmd
This commit is contained in:
committed by
Lorenz Meier
parent
d0fba8bf8b
commit
17e17d79dd
@@ -45,7 +45,6 @@ uint16 OFFBOARD_CONTROL_LOSS_TIMEOUT_MASK = 32
|
||||
uint16 RC_SIGNAL_FOUND_ONCE_MASK = 64
|
||||
uint16 RC_INPUT_BLOCKED_MASK = 256
|
||||
uint16 VTOL_TRANSITION_FAILURE_MASK = 1024
|
||||
uint16 VTOL_TRANSITION_FAILURE_CMD_MASK = 2048
|
||||
uint16 GPS_FAILURE_MASK = 4096
|
||||
|
||||
# 0x0001 usb_connected: status of the USB power supply
|
||||
@@ -57,7 +56,6 @@ uint16 GPS_FAILURE_MASK = 4096
|
||||
# 0x0040 rc_signal_found_once
|
||||
# 0x0100 rc_input_blocked: set if RC input should be ignored temporarily
|
||||
# 0x0400 vtol_transition_failure: Set to true if vtol transition failed
|
||||
# 0x0800 vtol_transition_failure_cmd: Set to true if vtol transition failure mode is commanded
|
||||
# 0x1000 gps_failure: Set to true if a gps failure is detected
|
||||
|
||||
uint16 other_flags
|
||||
|
||||
@@ -959,7 +959,6 @@ Commander::handle_command(vehicle_status_s *status_local, const safety_s *safety
|
||||
|
||||
/* param2 is currently used for other failsafe modes */
|
||||
status_local->engine_failure_cmd = false;
|
||||
status_flags.vtol_transition_failure_cmd = false;
|
||||
|
||||
if ((int)cmd->param2 <= 0) {
|
||||
/* reset all commanded failure modes */
|
||||
@@ -969,11 +968,6 @@ Commander::handle_command(vehicle_status_s *status_local, const safety_s *safety
|
||||
/* trigger engine failure mode */
|
||||
status_local->engine_failure_cmd = true;
|
||||
warnx("engine failure mode commanded");
|
||||
|
||||
} else if ((int)cmd->param2 == 5) {
|
||||
/* trigger vtol transition failure mode */
|
||||
status_flags.vtol_transition_failure_cmd = true;
|
||||
warnx("vtol transition failure mode commanded");
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -2041,7 +2035,6 @@ Commander::run()
|
||||
status.in_transition_mode = vtol_status.vtol_in_trans_mode;
|
||||
status.in_transition_to_fw = vtol_status.in_transition_to_fw;
|
||||
status_flags.vtol_transition_failure = vtol_status.vtol_transition_failsafe;
|
||||
status_flags.vtol_transition_failure_cmd = vtol_status.vtol_transition_failsafe;
|
||||
|
||||
armed.soft_stop = !status.is_rotary_wing;
|
||||
}
|
||||
@@ -4501,9 +4494,6 @@ void publish_status_flags(orb_advert_t &vehicle_status_flags_pub, vehicle_status
|
||||
if (status_flags.vtol_transition_failure) {
|
||||
v_flags.other_flags |= vehicle_status_flags_s::VTOL_TRANSITION_FAILURE_MASK;
|
||||
}
|
||||
if (status_flags.vtol_transition_failure_cmd) {
|
||||
v_flags.other_flags |= vehicle_status_flags_s::VTOL_TRANSITION_FAILURE_CMD_MASK;
|
||||
}
|
||||
if (status_flags.gps_failure) {
|
||||
v_flags.other_flags |= vehicle_status_flags_s::GPS_FAILURE_MASK;
|
||||
}
|
||||
|
||||
@@ -672,9 +672,6 @@ bool set_nav_state(struct vehicle_status_s *status,
|
||||
if (status->engine_failure_cmd) {
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
|
||||
} else if (status_flags->vtol_transition_failure_cmd) {
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_RTL;
|
||||
|
||||
} else if (status_flags->gps_failure) {
|
||||
if (status->is_rotary_wing) {
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
||||
|
||||
@@ -105,7 +105,6 @@ struct status_flags_s {
|
||||
bool rc_signal_found_once;
|
||||
bool rc_input_blocked; // set if RC input should be ignored temporarily
|
||||
bool vtol_transition_failure; // Set to true if vtol transition failed
|
||||
bool vtol_transition_failure_cmd; // Set to true if vtol transition failure mode is commanded
|
||||
bool gps_failure; // Set to true if a gps failure is detected
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user