mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-20 09:29:07 +08:00
Add check for stuck range finder measurements
This commit is contained in:
parent
41f4b62cdb
commit
7252284628
@ -105,6 +105,8 @@ void Ekf::controlFusionModes()
|
||||
_range_data_ready = _range_buffer.pop_first_older_than(_imu_sample_delayed.time_us, &_range_sample_delayed)
|
||||
&& (_R_rng_to_earth_2_2 > 0.7071f);
|
||||
|
||||
checkForStuckRange();
|
||||
|
||||
_flow_data_ready = _flow_buffer.pop_first_older_than(_imu_sample_delayed.time_us, &_flow_sample_delayed)
|
||||
&& (_R_to_earth(2, 2) > 0.7071f);
|
||||
_ev_data_ready = _ext_vision_buffer.pop_first_older_than(_imu_sample_delayed.time_us, &_ev_sample_delayed);
|
||||
@ -947,6 +949,34 @@ bool Ekf::rangeAidConditionsMet(bool in_range_aid_mode)
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::checkForStuckRange()
|
||||
{
|
||||
if (_range_data_ready && _range_sample_delayed.time_us - _time_last_rng_ready > 10e6 &&
|
||||
_control_status.flags.in_air) {
|
||||
_rng_stuck = true;
|
||||
|
||||
//require a variance of rangefinder values to check for "stuck" measurements
|
||||
if (_rng_check_max_val - _rng_check_min_val > 1.0f) {
|
||||
_time_last_rng_ready = _range_sample_delayed.time_us;
|
||||
_rng_check_min_val = 0.0f;
|
||||
_rng_check_max_val = 0.0f;
|
||||
_rng_stuck = false;
|
||||
|
||||
} else {
|
||||
if (_range_sample_delayed.rng > _rng_check_max_val)
|
||||
_rng_check_max_val = _range_sample_delayed.rng;
|
||||
|
||||
if (_rng_check_min_val < 0.1f || _range_sample_delayed.rng < _rng_check_min_val)
|
||||
_rng_check_min_val = _range_sample_delayed.rng;
|
||||
|
||||
_range_data_ready = false;
|
||||
}
|
||||
|
||||
} else if (_range_data_ready) {
|
||||
_time_last_rng_ready = _range_sample_delayed.time_us;
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::controlAirDataFusion()
|
||||
{
|
||||
// control activation and initialisation/reset of wind states required for airspeed fusion
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user