mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF3: prevent NaN if RNGFND_GNDCLEAR is zero
This commit is contained in:
parent
5cd403c0b9
commit
e399f57ffa
@ -22,7 +22,8 @@ void NavEKF3_core::readRangeFinder(void)
|
|||||||
uint8_t maxIndex;
|
uint8_t maxIndex;
|
||||||
uint8_t minIndex;
|
uint8_t minIndex;
|
||||||
// get theoretical correct range when the vehicle is on the ground
|
// get theoretical correct range when the vehicle is on the ground
|
||||||
rngOnGnd = frontend->_rng.ground_clearance_cm() * 0.01f;
|
// don't allow range to go below 5cm becasue this can cause problems with optical flow processing
|
||||||
|
rngOnGnd = MAX(frontend->_rng.ground_clearance_cm() * 0.01f, 0.05f);
|
||||||
|
|
||||||
// limit update rate to maximum allowed by data buffers
|
// limit update rate to maximum allowed by data buffers
|
||||||
if ((imuSampleTime_ms - lastRngMeasTime_ms) > frontend->sensorIntervalMin_ms) {
|
if ((imuSampleTime_ms - lastRngMeasTime_ms) > frontend->sensorIntervalMin_ms) {
|
||||||
|
Loading…
Reference in New Issue
Block a user