mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Rename force_failsafe to termination for clarity
This commit is contained in:
parent
34dacffc4a
commit
7fe78e184e
@ -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 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 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
|
||||
|
||||
@ -800,7 +800,7 @@ PX4IO::io_set_arming_state()
|
||||
_lockdown_override = false;
|
||||
}
|
||||
|
||||
if (armed.force_failsafe) {
|
||||
if (armed.termination) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
|
||||
} else {
|
||||
|
||||
@ -83,7 +83,7 @@ MixingOutput::MixingOutput(const char *param_prefix, uint8_t max_num_outputs, Ou
|
||||
_armed.prearmed = false;
|
||||
_armed.ready_to_arm = false;
|
||||
_armed.lockdown = false;
|
||||
_armed.force_failsafe = false;
|
||||
_armed.termination = false;
|
||||
_armed.in_esc_calibration_mode = false;
|
||||
|
||||
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];
|
||||
}
|
||||
|
||||
} else if (_armed.force_failsafe) {
|
||||
// overwrite outputs in case of force_failsafe with _failsafe_value values
|
||||
} else if (_armed.termination) {
|
||||
// Overwrite outputs with _failsafe_value when terminated
|
||||
for (size_t i = 0; i < _max_num_outputs; i++) {
|
||||
_current_output_value[i] = actualFailsafeValue(i);
|
||||
}
|
||||
|
||||
@ -148,12 +148,12 @@ public:
|
||||
_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.timestamp = hrt_absolute_time();
|
||||
actuator_armed.armed = armed;
|
||||
actuator_armed.force_failsafe = force_failsafe;
|
||||
actuator_armed.termination = termination;
|
||||
actuator_armed.manual_lockdown = manual_lockdown;
|
||||
actuator_armed.prearmed = prearm;
|
||||
_actuator_armed_pub.publish(actuator_armed);
|
||||
|
||||
@ -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.lockdown == b.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);
|
||||
}
|
||||
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)
|
||||
|| _multicopter_throw_launch.isThrowLaunchInProgress());
|
||||
// _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
|
||||
|
||||
// if force_failsafe activated send parachute command
|
||||
if (!actuator_armed_prev.force_failsafe && _actuator_armed.force_failsafe && isArmed()) {
|
||||
// Send parachute command upon termination
|
||||
if (!actuator_armed_prev.termination && _actuator_armed.termination && isArmed()) {
|
||||
send_parachute_command();
|
||||
}
|
||||
|
||||
|
||||
@ -42,7 +42,7 @@ void SystemChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
actuator_armed_s 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
|
||||
*/
|
||||
reporter.armingCheckFailure(NavModes::All, health_component_t::system, events::ID("check_system_flight_term_active"),
|
||||
|
||||
@ -119,9 +119,9 @@ private:
|
||||
}
|
||||
|
||||
// system_status overrides
|
||||
if (actuator_armed.force_failsafe || (actuator_armed.lockdown
|
||||
&& vehicle_status.hil_state == vehicle_status_s::HIL_STATE_OFF) || actuator_armed.manual_lockdown
|
||||
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_TERMINATION) {
|
||||
if (actuator_armed.termination
|
||||
|| (actuator_armed.lockdown && vehicle_status.hil_state == vehicle_status_s::HIL_STATE_OFF)
|
||||
|| actuator_armed.manual_lockdown) {
|
||||
|
||||
system_status = MAV_STATE_FLIGHT_TERMINATION;
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user