diff --git a/msg/FailsafeFlags.msg b/msg/FailsafeFlags.msg index dc173ddd96..7455313732 100644 --- a/msg/FailsafeFlags.msg +++ b/msg/FailsafeFlags.msg @@ -44,7 +44,7 @@ bool battery_unhealthy # Battery unhealthy # Other bool primary_geofence_breached # Primary Geofence breached bool mission_failure # Mission failure -bool vtol_transition_failure # VTOL transition failed (quadchute) +bool vtol_fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) bool wind_limit_exceeded # Wind limit exceeded bool flight_time_limit_exceeded # Maximum flight time exceeded diff --git a/msg/VtolVehicleStatus.msg b/msg/VtolVehicleStatus.msg index 80c424e7a4..61a8246796 100644 --- a/msg/VtolVehicleStatus.msg +++ b/msg/VtolVehicleStatus.msg @@ -9,4 +9,4 @@ uint64 timestamp # time since system start (microseconds) uint8 vehicle_vtol_state # current state of the vtol, see VEHICLE_VTOL_STATE -bool vtol_transition_failsafe # vtol in transition failsafe mode +bool fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/vtolCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/vtolCheck.cpp index c953c4281e..7e0224e26f 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/vtolCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/vtolCheck.cpp @@ -40,12 +40,13 @@ void VtolChecks::checkAndReport(const Context &context, Report &reporter) vtol_vehicle_status_s vtol_vehicle_status; if (_vtol_vehicle_status_sub.copy(&vtol_vehicle_status)) { - reporter.failsafeFlags().vtol_transition_failure = vtol_vehicle_status.vtol_transition_failsafe; + reporter.failsafeFlags().vtol_fixed_wing_system_failure = vtol_vehicle_status.fixed_wing_system_failure; - if (reporter.failsafeFlags().vtol_transition_failure) { + if (reporter.failsafeFlags().vtol_fixed_wing_system_failure) { /* EVENT */ - reporter.armingCheckFailure(NavModes::All, health_component_t::system, events::ID("check_vtol_transition_failure"), + reporter.armingCheckFailure(NavModes::All, health_component_t::system, + events::ID("check_vtol_fixed_wing_system_failure"), events::Log::Error, "VTOL transition failure"); if (reporter.mavlink_log_pub()) { diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index 6d53cf0cfd..dfc571d039 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -373,7 +373,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER || state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF) { - CHECK_FAILSAFE(status_flags, vtol_transition_failure, fromQuadchuteActParam(_param_com_qc_act.get())); + CHECK_FAILSAFE(status_flags, vtol_fixed_wing_system_failure, fromQuadchuteActParam(_param_com_qc_act.get())); } // Mission diff --git a/src/modules/vtol_att_control/standard.cpp b/src/modules/vtol_att_control/standard.cpp index a210b8ef27..effb4c5f56 100644 --- a/src/modules/vtol_att_control/standard.cpp +++ b/src/modules/vtol_att_control/standard.cpp @@ -72,7 +72,7 @@ void Standard::update_vtol_state() float mc_weight = _mc_roll_weight; - if (_vtol_vehicle_status->vtol_transition_failsafe) { + if (_vtol_vehicle_status->fixed_wing_system_failure) { // Failsafe event, engage mc motors immediately _vtol_mode = vtol_mode::MC_MODE; _pusher_throttle = 0.0f; diff --git a/src/modules/vtol_att_control/tailsitter.cpp b/src/modules/vtol_att_control/tailsitter.cpp index 74e7810fbf..acfd4941e0 100644 --- a/src/modules/vtol_att_control/tailsitter.cpp +++ b/src/modules/vtol_att_control/tailsitter.cpp @@ -71,7 +71,7 @@ void Tailsitter::update_vtol_state() float pitch = Eulerf(Quatf(_v_att->q)).theta(); - if (_vtol_vehicle_status->vtol_transition_failsafe) { + if (_vtol_vehicle_status->fixed_wing_system_failure) { // Failsafe event, switch to MC mode immediately _vtol_mode = vtol_mode::MC_MODE; diff --git a/src/modules/vtol_att_control/tiltrotor.cpp b/src/modules/vtol_att_control/tiltrotor.cpp index a00c52860a..e62fed0cb1 100644 --- a/src/modules/vtol_att_control/tiltrotor.cpp +++ b/src/modules/vtol_att_control/tiltrotor.cpp @@ -71,7 +71,7 @@ void Tiltrotor::update_vtol_state() * forward completely. For the backtransition the motors simply rotate back. */ - if (_vtol_vehicle_status->vtol_transition_failsafe) { + if (_vtol_vehicle_status->fixed_wing_system_failure) { // Failsafe event, switch to MC mode immediately _vtol_mode = vtol_mode::MC_MODE; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index dfcf60af43..ed567183ae 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -134,9 +134,9 @@ void VtolAttitudeControl::action_request_poll() _transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW; _immediate_transition = false; - // reset vtol_transition_failsafe flag when a new transition to FW is triggered + // reset fixed_wing_system_failure flag when a new transition to FW is triggered if (_transition_command == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW) { - _vtol_vehicle_status.vtol_transition_failsafe = false; + _vtol_vehicle_status.fixed_wing_system_failure = false; } break; @@ -169,9 +169,9 @@ void VtolAttitudeControl::vehicle_cmd_poll() _transition_command = transition_command_param1; _immediate_transition = (PX4_ISFINITE(vehicle_command.param2)) ? int(vehicle_command.param2 + 0.5f) : false; - // reset vtol_transition_failsafe flag when a new transition to FW is triggered + // reset fixed_wing_system_failure flag when a new transition to FW is triggered if (_transition_command == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW) { - _vtol_vehicle_status.vtol_transition_failsafe = false; + _vtol_vehicle_status.fixed_wing_system_failure = false; } } @@ -193,7 +193,7 @@ void VtolAttitudeControl::vehicle_cmd_poll() void VtolAttitudeControl::quadchute(QuadchuteReason reason) { - if (!_vtol_vehicle_status.vtol_transition_failsafe) { + if (!_vtol_vehicle_status.fixed_wing_system_failure) { switch (reason) { case QuadchuteReason::TransitionTimeout: mavlink_log_critical(&_mavlink_log_pub, "Quadchute: transition timeout\t"); @@ -242,7 +242,7 @@ VtolAttitudeControl::quadchute(QuadchuteReason reason) return; } - _vtol_vehicle_status.vtol_transition_failsafe = true; + _vtol_vehicle_status.fixed_wing_system_failure = true; } } diff --git a/src/modules/vtol_att_control/vtol_type.cpp b/src/modules/vtol_att_control/vtol_type.cpp index 508a01e1c8..6fb7e3482c 100644 --- a/src/modules/vtol_att_control/vtol_type.cpp +++ b/src/modules/vtol_att_control/vtol_type.cpp @@ -471,7 +471,7 @@ float VtolType::pusher_assist() } // Do not engage pusher assist during a failsafe event (could be a problem with the fixed wing drive) - if (_attc->get_vtol_vehicle_status()->vtol_transition_failsafe) { + if (_attc->get_vtol_vehicle_status()->fixed_wing_system_failure) { return 0.0f; }