forked from Archive/PX4-Autopilot
VTOL: only run front transition alt loss QC if altitude is controlled
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
c1d94c7f05
commit
06713cb655
|
@ -301,9 +301,9 @@ bool VtolType::isFrontTransitionAltitudeLoss()
|
|||
{
|
||||
bool result = false;
|
||||
|
||||
// only run if param set, altitude estimate valid and in transition to FW or within 5s of finishing it.
|
||||
if (_param_vt_qc_t_alt_loss.get() > FLT_EPSILON && _local_pos->z_valid && (_common_vtol_mode == mode::TRANSITION_TO_FW
|
||||
|| hrt_elapsed_time(&_trans_finished_ts) < 5_s)) {
|
||||
// only run if param set, altitude valid and controlled, and in transition to FW or within 5s of finishing it.
|
||||
if (_param_vt_qc_t_alt_loss.get() > FLT_EPSILON && _local_pos->z_valid && _v_control_mode->flag_control_altitude_enabled
|
||||
&& (_common_vtol_mode == mode::TRANSITION_TO_FW || hrt_elapsed_time(&_trans_finished_ts) < 5_s)) {
|
||||
|
||||
result = _local_pos->z - _local_position_z_start_of_transition > _param_vt_qc_t_alt_loss.get();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue