forked from Archive/PX4-Autopilot
VTOL/Commander: rename transition_failsafe to vtol_fixed_wing_system_failure
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
2d4be68e00
commit
303b879748
|
@ -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
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -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()) {
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue