mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Rename VtolAttitudeControl::abort_front_transition(const char *reason) to VtolAttitudeControl::quadchute(const char *reason)
This commit is contained in:
parent
40fbfdc054
commit
38e46ff341
@ -277,7 +277,7 @@ void Standard::update_transition_state()
|
||||
if (_params->front_trans_timeout > FLT_EPSILON) {
|
||||
if (time_since_trans_start > _params->front_trans_timeout) {
|
||||
// transition timeout occured, abort transition
|
||||
_attc->abort_front_transition("Transition timeout");
|
||||
_attc->quadchute("Transition timeout");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -211,7 +211,7 @@ VtolAttitudeControl::is_fixed_wing_requested()
|
||||
}
|
||||
|
||||
void
|
||||
VtolAttitudeControl::abort_front_transition(const char *reason)
|
||||
VtolAttitudeControl::quadchute(const char *reason)
|
||||
{
|
||||
if (!_vtol_vehicle_status.vtol_transition_failsafe) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Abort: %s", reason);
|
||||
|
||||
@ -107,7 +107,7 @@ public:
|
||||
bool init();
|
||||
|
||||
bool is_fixed_wing_requested();
|
||||
void abort_front_transition(const char *reason);
|
||||
void quadchute(const char *reason);
|
||||
|
||||
struct actuator_controls_s *get_actuators_fw_in() {return &_actuators_fw_in;}
|
||||
struct actuator_controls_s *get_actuators_mc_in() {return &_actuators_mc_in;}
|
||||
|
||||
@ -245,7 +245,7 @@ void VtolType::check_quadchute_condition()
|
||||
if (_params->fw_min_alt > FLT_EPSILON) {
|
||||
|
||||
if (-(_local_pos->z) < _params->fw_min_alt) {
|
||||
_attc->abort_front_transition("QuadChute: Minimum altitude breached");
|
||||
_attc->quadchute("QuadChute: Minimum altitude breached");
|
||||
}
|
||||
}
|
||||
|
||||
@ -263,7 +263,7 @@ void VtolType::check_quadchute_condition()
|
||||
(_ra_hrate < -1.0f) &&
|
||||
(_ra_hrate_sp > 1.0f)) {
|
||||
|
||||
_attc->abort_front_transition("QuadChute: loss of altitude");
|
||||
_attc->quadchute("QuadChute: loss of altitude");
|
||||
}
|
||||
|
||||
} else {
|
||||
@ -271,7 +271,7 @@ void VtolType::check_quadchute_condition()
|
||||
const bool height_rate_error = _local_pos->v_z_valid && (_local_pos->vz > 1.0f) && (_local_pos->z_deriv > 1.0f);
|
||||
|
||||
if (height_error && height_rate_error) {
|
||||
_attc->abort_front_transition("QuadChute: large altitude error");
|
||||
_attc->quadchute("QuadChute: large altitude error");
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -280,7 +280,7 @@ void VtolType::check_quadchute_condition()
|
||||
if (_params->fw_qc_max_pitch > 0) {
|
||||
|
||||
if (fabsf(euler.theta()) > fabsf(math::radians(_params->fw_qc_max_pitch))) {
|
||||
_attc->abort_front_transition("Maximum pitch angle exceeded");
|
||||
_attc->quadchute("Maximum pitch angle exceeded");
|
||||
}
|
||||
}
|
||||
|
||||
@ -288,7 +288,7 @@ void VtolType::check_quadchute_condition()
|
||||
if (_params->fw_qc_max_roll > 0) {
|
||||
|
||||
if (fabsf(euler.phi()) > fabsf(math::radians(_params->fw_qc_max_roll))) {
|
||||
_attc->abort_front_transition("Maximum roll angle exceeded");
|
||||
_attc->quadchute("Maximum roll angle exceeded");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user