Rename force_failsafe to termination for clarity

This commit is contained in:
Matthias Grob 2025-07-25 16:34:41 +02:00 committed by Alex Klimaj
parent 34dacffc4a
commit 7fe78e184e
7 changed files with 15 additions and 15 deletions

View File

@ -5,5 +5,5 @@ bool prearmed # Set to true if the actuator safety is disabled but motors are n
bool ready_to_arm # Set to true if system is ready to be armed bool ready_to_arm # Set to true if system is ready to be armed
bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL) bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL)
bool manual_lockdown # Set to true if manual throttle kill switch is engaged bool manual_lockdown # Set to true if manual throttle kill switch is engaged
bool force_failsafe # Set to true if the actuators are forced to the failsafe position bool termination # Send out failsafe (by default same as disarmed) output
bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics

View File

@ -800,7 +800,7 @@ PX4IO::io_set_arming_state()
_lockdown_override = false; _lockdown_override = false;
} }
if (armed.force_failsafe) { if (armed.termination) {
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE; set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
} else { } else {

View File

@ -83,7 +83,7 @@ MixingOutput::MixingOutput(const char *param_prefix, uint8_t max_num_outputs, Ou
_armed.prearmed = false; _armed.prearmed = false;
_armed.ready_to_arm = false; _armed.ready_to_arm = false;
_armed.lockdown = false; _armed.lockdown = false;
_armed.force_failsafe = false; _armed.termination = false;
_armed.in_esc_calibration_mode = false; _armed.in_esc_calibration_mode = false;
px4_sem_init(&_lock, 0, 1); px4_sem_init(&_lock, 0, 1);
@ -479,8 +479,8 @@ MixingOutput::limitAndUpdateOutputs(float outputs[MAX_ACTUATORS], bool has_updat
_current_output_value[i] = _disarmed_value[i]; _current_output_value[i] = _disarmed_value[i];
} }
} else if (_armed.force_failsafe) { } else if (_armed.termination) {
// overwrite outputs in case of force_failsafe with _failsafe_value values // Overwrite outputs with _failsafe_value when terminated
for (size_t i = 0; i < _max_num_outputs; i++) { for (size_t i = 0; i < _max_num_outputs; i++) {
_current_output_value[i] = actualFailsafeValue(i); _current_output_value[i] = actualFailsafeValue(i);
} }

View File

@ -148,12 +148,12 @@ public:
_actuator_test_pub.publish(actuator_test); _actuator_test_pub.publish(actuator_test);
} }
void sendActuatorArmed(bool armed, bool force_failsafe = false, bool manual_lockdown = false, bool prearm = false) void sendActuatorArmed(bool armed, bool termination = false, bool manual_lockdown = false, bool prearm = false)
{ {
actuator_armed_s actuator_armed{}; actuator_armed_s actuator_armed{};
actuator_armed.timestamp = hrt_absolute_time(); actuator_armed.timestamp = hrt_absolute_time();
actuator_armed.armed = armed; actuator_armed.armed = armed;
actuator_armed.force_failsafe = force_failsafe; actuator_armed.termination = termination;
actuator_armed.manual_lockdown = manual_lockdown; actuator_armed.manual_lockdown = manual_lockdown;
actuator_armed.prearmed = prearm; actuator_armed.prearmed = prearm;
_actuator_armed_pub.publish(actuator_armed); _actuator_armed_pub.publish(actuator_armed);

View File

@ -94,7 +94,7 @@ static constexpr bool operator ==(const actuator_armed_s &a, const actuator_arme
a.ready_to_arm == b.ready_to_arm && a.ready_to_arm == b.ready_to_arm &&
a.lockdown == b.lockdown && a.lockdown == b.lockdown &&
a.manual_lockdown == b.manual_lockdown && a.manual_lockdown == b.manual_lockdown &&
a.force_failsafe == b.force_failsafe && a.termination == b.termination &&
a.in_esc_calibration_mode == b.in_esc_calibration_mode); a.in_esc_calibration_mode == b.in_esc_calibration_mode);
} }
static_assert(sizeof(actuator_armed_s) == 16, "actuator_armed equality operator review"); static_assert(sizeof(actuator_armed_s) == 16, "actuator_armed equality operator review");
@ -1898,11 +1898,11 @@ void Commander::run()
_actuator_armed.lockdown = ((_vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON) _actuator_armed.lockdown = ((_vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON)
|| _multicopter_throw_launch.isThrowLaunchInProgress()); || _multicopter_throw_launch.isThrowLaunchInProgress());
// _actuator_armed.manual_lockdown // action_request_s::ACTION_KILL // _actuator_armed.manual_lockdown // action_request_s::ACTION_KILL
_actuator_armed.force_failsafe = (_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION); _actuator_armed.termination = (_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION);
// _actuator_armed.in_esc_calibration_mode // VEHICLE_CMD_PREFLIGHT_CALIBRATION // _actuator_armed.in_esc_calibration_mode // VEHICLE_CMD_PREFLIGHT_CALIBRATION
// if force_failsafe activated send parachute command // Send parachute command upon termination
if (!actuator_armed_prev.force_failsafe && _actuator_armed.force_failsafe && isArmed()) { if (!actuator_armed_prev.termination && _actuator_armed.termination && isArmed()) {
send_parachute_command(); send_parachute_command();
} }

View File

@ -42,7 +42,7 @@ void SystemChecks::checkAndReport(const Context &context, Report &reporter)
actuator_armed_s actuator_armed; actuator_armed_s actuator_armed;
if (_actuator_armed_sub.copy(&actuator_armed)) { if (_actuator_armed_sub.copy(&actuator_armed)) {
if (actuator_armed.force_failsafe || actuator_armed.manual_lockdown) { if (actuator_armed.termination || actuator_armed.manual_lockdown) {
/* EVENT /* EVENT
*/ */
reporter.armingCheckFailure(NavModes::All, health_component_t::system, events::ID("check_system_flight_term_active"), reporter.armingCheckFailure(NavModes::All, health_component_t::system, events::ID("check_system_flight_term_active"),

View File

@ -119,9 +119,9 @@ private:
} }
// system_status overrides // system_status overrides
if (actuator_armed.force_failsafe || (actuator_armed.lockdown if (actuator_armed.termination
&& vehicle_status.hil_state == vehicle_status_s::HIL_STATE_OFF) || actuator_armed.manual_lockdown || (actuator_armed.lockdown && vehicle_status.hil_state == vehicle_status_s::HIL_STATE_OFF)
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_TERMINATION) { || actuator_armed.manual_lockdown) {
system_status = MAV_STATE_FLIGHT_TERMINATION; system_status = MAV_STATE_FLIGHT_TERMINATION;
} }