px4-firmware/EKF/terrain_estimator.cpp

318 lines
12 KiB
C++
Raw Normal View History

/****************************************************************************
*
* Copyright (c) 2015 Estimation and Control Library (ECL). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name ECL nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file terrain_estimator.cpp
* Function for fusing rangefinder measurements to estimate terrain vertical position/
*
* @author Paul Riseborough <p_riseborough@live.com.au>
*
*/
#include "ekf.h"
#include <ecl.h>
#include <mathlib/mathlib.h>
bool Ekf::initHagl()
{
bool initialized = false;
if (!_control_status.flags.in_air) {
// if on ground, do not trust the range sensor, but assume a ground clearance
_terrain_vpos = _state.pos(2) + _params.rng_gnd_clearance;
// use the ground clearance value as our uncertainty
_terrain_var = sq(_params.rng_gnd_clearance);
_time_last_fake_hagl_fuse = _time_last_imu;
initialized = true;
} else if (shouldUseRangeFinderForHagl()
&& _range_sensor.isDataHealthy()) {
// if we have a fresh measurement, use it to initialise the terrain estimator
_terrain_vpos = _state.pos(2) + _range_sensor.getDistBottom();
// initialise state variance to variance of measurement
_terrain_var = sq(_params.range_noise);
// success
initialized = true;
} else if (shouldUseOpticalFlowForHagl()
&& _flow_for_terrain_data_ready) {
2019-05-12 13:33:03 -03:00
// initialise terrain vertical position to origin as this is the best guess we have
_terrain_vpos = fmaxf(0.0f, _state.pos(2));
_terrain_var = 100.0f;
initialized = true;
} else {
// no information - cannot initialise
}
if (initialized) {
// has initialized with valid data
_time_last_hagl_fuse = _time_last_imu;
}
return initialized;
}
bool Ekf::shouldUseRangeFinderForHagl() const
{
return (_params.terrain_fusion_mode & TerrainFusionMask::TerrainFuseRangeFinder);
}
bool Ekf::shouldUseOpticalFlowForHagl() const
{
return (_params.terrain_fusion_mode & TerrainFusionMask::TerrainFuseOpticalFlow);
}
void Ekf::runTerrainEstimator()
{
// If we are on ground, store the local position and time to use as a reference
if (!_control_status.flags.in_air) {
_last_on_ground_posD = _state.pos(2);
}
// Perform initialisation check and
// on ground, continuously reset the terrain estimator
if (!_terrain_initialised || !_control_status.flags.in_air) {
_terrain_initialised = initHagl();
} else {
// predict the state variance growth where the state is the vertical position of the terrain underneath the vehicle
// process noise due to errors in vehicle height estimate
_terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_p_noise);
// process noise due to terrain gradient
_terrain_var += sq(_imu_sample_delayed.delta_vel_dt * _params.terrain_gradient)
* (sq(_state.vel(0)) + sq(_state.vel(1)));
// limit the variance to prevent it becoming badly conditioned
_terrain_var = math::constrain(_terrain_var, 0.0f, 1e4f);
// Fuse range finder data if available
if (shouldUseRangeFinderForHagl()
&& _range_sensor.isDataHealthy()) {
fuseHagl();
}
if (shouldUseOpticalFlowForHagl()
&& _flow_for_terrain_data_ready) {
fuseFlowForTerrain();
_flow_for_terrain_data_ready = false;
}
// constrain _terrain_vpos to be a minimum of _params.rng_gnd_clearance larger than _state.pos(2)
if (_terrain_vpos - _state.pos(2) < _params.rng_gnd_clearance) {
_terrain_vpos = _params.rng_gnd_clearance + _state.pos(2);
}
}
EKF: Fix non GPS aiding data reset logic (#418) * EKF: Move optical flow specific state reset to helper functions * EKF: Ensure loss of optical flow aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using flow data as a velocity reference. If flow data is unavailable for too long - declare optical flow use stopped. Use consistent time periods for all resets * EKF: Ensure loss of external vision aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using data as a position. Don't reset velocity if there is another source of aiding constraining it. If data is unavailable for too long, declare external vision use stopped. Use consistent time periods for all resets. * EKF: Update parameter documentation Make the distinction between the no_gps_timeout_max and no_aid_timeout_max parameters clearer * EKF: make class variable units consistent with documentation * EKF: Don't reset states when optical flow use commences if using external vision * EKF: Stop optical flow fusion when on ground if excessive movement is detected. * EKF: fix terrain estimator vulnerabilities Reset estimate to sensor value if rejected for 10 seconds Protect against user motion when on ground. Fix unnecessary duplication of terrain validity check and separate validity update and reporting. * EKF: remove unnecessary Info console prints Optical flow use information can be obtained from the estimator_status.control_mode_flags message * EKF: fix inaccurate comment * EKF: remove duplicate calculation from terrain validity accessor function
2018-04-09 05:35:15 -03:00
updateTerrainValidity();
}
void Ekf::fuseHagl()
{
Range check cleanup (#782) * EKF: centralize range finder tilt check * Ekf-control: do not double check for terrain estimate validity isRangeAidSuitable can only return true if the terrain estimate is valid so there is no need for an additional check * range_finder_checks: restructure the checks to avoid early returns There is now only one clear path that can lead to the validity being true. Furthermore, if the _rng_hgt_valid is true, we can trust it and we don't need for additional checks such as tilt. The case where we need to provide fake measurements because the drone is on the ground and the range finder data is bad is already handled in "controlHeightFusion" so there is no need to hack the range finder checks with that. * Add Sensor and SensorRangeFinder classes The purpose is to encapsulate the checks for each sensor in a dedicated class with the same interface * SensorRangeFinder: encapsulate in estimator::sensor namespace * EKF: rename _sensor_rng to _range_sensor * Range checks: include limits in valid range * RangeChecks: update comment in the continuity checks * RangeChecks: move more low-level checks in functions Also move setTilt out of the terrain estimator, this is anyway protected internally to not compute cos/sin if the parameter did not change. * Sensor: remove unused virtual functions Those are not required yet but can still be added later * SensorRangeFinder: re-organise member variables Also rename getRangeToEarth to getCosTilt * SensorRangeFinder: split setSensorTilt and setCosMaxTilt functions * SensorRangeFinder: Add a few unit tests - good data - tilt exceeded - max range exceeded * SensorRangeFinder: set hysteresis in us instead of ms * SensorRangeFinder: Add more tests * SensorRangeFinder: update continuity, hysteresis and stuck tests * SensorRangeFinder: rename variables * SensorRangeFinder: get rid of "delayed" specification From the SensorRangeFinder class point of view, it's not relevant to know if the data is delayed or not * SensorRangeFinder: move time_last_valid out of stuck check * SensorRangeFinder: rename file names to sensor_range_finder * SensorRangeFinder: address Kamil's comments * SensorRangeFinder: Add more tilt tests * SensorRangeFinder: store current tilt offset This is to avoid recomputing cos/sin functions at each loop
2020-04-03 03:28:07 -03:00
// get a height above ground measurement from the range finder assuming a flat earth
const float meas_hagl = _range_sensor.getDistBottom();
Range check cleanup (#782) * EKF: centralize range finder tilt check * Ekf-control: do not double check for terrain estimate validity isRangeAidSuitable can only return true if the terrain estimate is valid so there is no need for an additional check * range_finder_checks: restructure the checks to avoid early returns There is now only one clear path that can lead to the validity being true. Furthermore, if the _rng_hgt_valid is true, we can trust it and we don't need for additional checks such as tilt. The case where we need to provide fake measurements because the drone is on the ground and the range finder data is bad is already handled in "controlHeightFusion" so there is no need to hack the range finder checks with that. * Add Sensor and SensorRangeFinder classes The purpose is to encapsulate the checks for each sensor in a dedicated class with the same interface * SensorRangeFinder: encapsulate in estimator::sensor namespace * EKF: rename _sensor_rng to _range_sensor * Range checks: include limits in valid range * RangeChecks: update comment in the continuity checks * RangeChecks: move more low-level checks in functions Also move setTilt out of the terrain estimator, this is anyway protected internally to not compute cos/sin if the parameter did not change. * Sensor: remove unused virtual functions Those are not required yet but can still be added later * SensorRangeFinder: re-organise member variables Also rename getRangeToEarth to getCosTilt * SensorRangeFinder: split setSensorTilt and setCosMaxTilt functions * SensorRangeFinder: Add a few unit tests - good data - tilt exceeded - max range exceeded * SensorRangeFinder: set hysteresis in us instead of ms * SensorRangeFinder: Add more tests * SensorRangeFinder: update continuity, hysteresis and stuck tests * SensorRangeFinder: rename variables * SensorRangeFinder: get rid of "delayed" specification From the SensorRangeFinder class point of view, it's not relevant to know if the data is delayed or not * SensorRangeFinder: move time_last_valid out of stuck check * SensorRangeFinder: rename file names to sensor_range_finder * SensorRangeFinder: address Kamil's comments * SensorRangeFinder: Add more tilt tests * SensorRangeFinder: store current tilt offset This is to avoid recomputing cos/sin functions at each loop
2020-04-03 03:28:07 -03:00
// predict the hagl from the vehicle position and terrain height
const float pred_hagl = _terrain_vpos - _state.pos(2);
// calculate the innovation
_hagl_innov = pred_hagl - meas_hagl;
// calculate the observation variance adding the variance of the vehicles own height uncertainty
const float obs_variance = fmaxf(P(9,9) * _params.vehicle_variance_scaler, 0.0f)
+ sq(_params.range_noise)
+ sq(_params.range_noise_scaler * _range_sensor.getRange());
// calculate the innovation variance - limiting it to prevent a badly conditioned fusion
_hagl_innov_var = fmaxf(_terrain_var + obs_variance, obs_variance);
// perform an innovation consistency check and only fuse data if it passes
const float gate_size = fmaxf(_params.range_innov_gate, 1.0f);
_hagl_test_ratio = sq(_hagl_innov) / (sq(gate_size) * _hagl_innov_var);
if (_hagl_test_ratio <= 1.0f) {
// calculate the Kalman gain
float gain = _terrain_var / _hagl_innov_var;
// correct the state
_terrain_vpos -= gain * _hagl_innov;
// correct the variance
_terrain_var = fmaxf(_terrain_var * (1.0f - gain), 0.0f);
// record last successful fusion event
_time_last_hagl_fuse = _time_last_imu;
_innov_check_fail_status.flags.reject_hagl = false;
} else {
// If we have been rejecting range data for too long, reset to measurement
if (isTimedOut(_time_last_hagl_fuse, (uint64_t)10E6)) {
_terrain_vpos = _state.pos(2) + meas_hagl;
_terrain_var = obs_variance;
} else {
Range check cleanup (#782) * EKF: centralize range finder tilt check * Ekf-control: do not double check for terrain estimate validity isRangeAidSuitable can only return true if the terrain estimate is valid so there is no need for an additional check * range_finder_checks: restructure the checks to avoid early returns There is now only one clear path that can lead to the validity being true. Furthermore, if the _rng_hgt_valid is true, we can trust it and we don't need for additional checks such as tilt. The case where we need to provide fake measurements because the drone is on the ground and the range finder data is bad is already handled in "controlHeightFusion" so there is no need to hack the range finder checks with that. * Add Sensor and SensorRangeFinder classes The purpose is to encapsulate the checks for each sensor in a dedicated class with the same interface * SensorRangeFinder: encapsulate in estimator::sensor namespace * EKF: rename _sensor_rng to _range_sensor * Range checks: include limits in valid range * RangeChecks: update comment in the continuity checks * RangeChecks: move more low-level checks in functions Also move setTilt out of the terrain estimator, this is anyway protected internally to not compute cos/sin if the parameter did not change. * Sensor: remove unused virtual functions Those are not required yet but can still be added later * SensorRangeFinder: re-organise member variables Also rename getRangeToEarth to getCosTilt * SensorRangeFinder: split setSensorTilt and setCosMaxTilt functions * SensorRangeFinder: Add a few unit tests - good data - tilt exceeded - max range exceeded * SensorRangeFinder: set hysteresis in us instead of ms * SensorRangeFinder: Add more tests * SensorRangeFinder: update continuity, hysteresis and stuck tests * SensorRangeFinder: rename variables * SensorRangeFinder: get rid of "delayed" specification From the SensorRangeFinder class point of view, it's not relevant to know if the data is delayed or not * SensorRangeFinder: move time_last_valid out of stuck check * SensorRangeFinder: rename file names to sensor_range_finder * SensorRangeFinder: address Kamil's comments * SensorRangeFinder: Add more tilt tests * SensorRangeFinder: store current tilt offset This is to avoid recomputing cos/sin functions at each loop
2020-04-03 03:28:07 -03:00
_innov_check_fail_status.flags.reject_hagl = true;
}
}
}
void Ekf::fuseFlowForTerrain()
{
// calculate optical LOS rates using optical flow rates that have had the body angular rate contribution removed
// correct for gyro bias errors in the data used to do the motion compensation
// Note the sign convention used: A positive LOS rate is a RH rotation of the scene about that axis.
2020-06-03 06:25:03 -03:00
const Vector2f opt_flow_rate = Vector2f(_flow_compensated_XY_rad) / _flow_sample_delayed.dt + Vector2f(_flow_gyro_bias);
// get latest estimated orientation
2019-12-25 12:13:05 -04:00
const float q0 = _state.quat_nominal(0);
const float q1 = _state.quat_nominal(1);
const float q2 = _state.quat_nominal(2);
const float q3 = _state.quat_nominal(3);
// calculate the optical flow observation variance
2019-12-25 12:13:05 -04:00
const float R_LOS = calcOptFlowMeasVar();
// get rotation matrix from earth to body
2020-06-21 10:28:10 -03:00
const Dcmf earth_to_body = quatToInverseRotMat(_state.quat_nominal);
// calculate the sensor position relative to the IMU
2019-12-25 12:13:05 -04:00
const Vector3f pos_offset_body = _params.flow_pos_body - _params.imu_pos_body;
// calculate the velocity of the sensor relative to the imu in body frame
2020-01-23 12:46:21 -04:00
// Note: _flow_sample_delayed.gyro_xyz is the negative of the body angular velocity, thus use minus sign
const Vector3f vel_rel_imu_body = Vector3f(-_flow_sample_delayed.gyro_xyz / _flow_sample_delayed.dt) % pos_offset_body;
// calculate the velocity of the sensor in the earth frame
2019-12-25 12:13:05 -04:00
const Vector3f vel_rel_earth = _state.vel + _R_to_earth * vel_rel_imu_body;
// rotate into body frame
2019-12-25 12:13:05 -04:00
const Vector3f vel_body = earth_to_body * vel_rel_earth;
2019-12-25 12:13:05 -04:00
const float t0 = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3;
// constrain terrain to minimum allowed value and predict height above ground
_terrain_vpos = fmaxf(_terrain_vpos, _params.rng_gnd_clearance + _state.pos(2));
2019-12-25 12:13:05 -04:00
const float pred_hagl = _terrain_vpos - _state.pos(2);
// Calculate observation matrix for flow around the vehicle x axis
2019-12-25 12:13:05 -04:00
const float Hx = vel_body(1) * t0 / (pred_hagl * pred_hagl);
2019-05-12 13:33:03 -03:00
// Constrain terrain variance to be non-negative
_terrain_var = fmaxf(_terrain_var, 0.0f);
// Cacluate innovation variance
_flow_innov_var[0] = Hx * Hx * _terrain_var + R_LOS;
// calculate the kalman gain for the flow x measurement
2019-12-25 12:13:05 -04:00
const float Kx = _terrain_var * Hx / _flow_innov_var[0];
// calculate prediced optical flow about x axis
2019-12-25 12:13:05 -04:00
const float pred_flow_x = vel_body(1) * earth_to_body(2, 2) / pred_hagl;
// calculate flow innovation (x axis)
_flow_innov[0] = pred_flow_x - opt_flow_rate(0);
// calculate correction term for terrain variance
2019-12-25 12:13:05 -04:00
const float KxHxP = Kx * Hx * _terrain_var;
// innovation consistency check
2019-12-25 12:13:05 -04:00
const float gate_size = fmaxf(_params.flow_innov_gate, 1.0f);
float flow_test_ratio = sq(_flow_innov[0]) / (sq(gate_size) * _flow_innov_var[0]);
// do not perform measurement update if badly conditioned
if (flow_test_ratio <= 1.0f) {
_terrain_vpos += Kx * _flow_innov[0];
// guard against negative variance
_terrain_var = fmaxf(_terrain_var - KxHxP, 0.0f);
_time_last_of_fuse = _time_last_imu;
}
// Calculate observation matrix for flow around the vehicle y axis
2019-12-25 12:13:05 -04:00
const float Hy = -vel_body(0) * t0 / (pred_hagl * pred_hagl);
// Calculuate innovation variance
_flow_innov_var[1] = Hy * Hy * _terrain_var + R_LOS;
// calculate the kalman gain for the flow y measurement
2019-12-25 12:13:05 -04:00
const float Ky = _terrain_var * Hy / _flow_innov_var[1];
// calculate prediced optical flow about y axis
2019-12-25 12:13:05 -04:00
const float pred_flow_y = -vel_body(0) * earth_to_body(2, 2) / pred_hagl;
// calculate flow innovation (y axis)
_flow_innov[1] = pred_flow_y - opt_flow_rate(1);
// calculate correction term for terrain variance
2019-12-25 12:13:05 -04:00
const float KyHyP = Ky * Hy * _terrain_var;
// innovation consistency check
flow_test_ratio = sq(_flow_innov[1]) / (sq(gate_size) * _flow_innov_var[1]);
if (flow_test_ratio <= 1.0f) {
_terrain_vpos += Ky * _flow_innov[1];
// guard against negative variance
_terrain_var = fmaxf(_terrain_var - KyHyP, 0.0f);
_time_last_of_fuse = _time_last_imu;
}
}
[ekf] controlMagFusion refactor and mag field strength check (#662) * ekf_control: Inhibit mag fusion when field magnitude is large Move mag inhibition check in separate function * ekf_control: pull out of functionalities out of controlMagFusion - yaw abd mag bias observability checks - mag 3D conditions - load mag covariances - set and clear mag control modes * ekf_control: refactor mag heading/3D start/stop. Move mag declination, mag 3d and mag heading fusion out of the main function * ekf_control: extract mag yaw reset and mag declination fusion requirements * ekf_control: use WMM in isStronMagneticField for mag fusion inhibition - Correct units of WMM strength table * ekf_control: extract mag_state_only functionality of AUTOFW (VTOL custom) Also split inAirYawReset from onGroundYawReset * ekf_control: extract mag automatic selection - transform if-else into switch-case for parameter fusion type selection * ekf_control: extract run3DMagAndDeclFusion, reorganize functions, fix flag naming in Test script * ekf_control: do not run mag fusion if tilt is not aligned. Reset some variables on ground even if mag fusion is not running yet. It could be that it runs later so we need to make sure that those variables are properly set. * ekf_control: move controlMagFusion and related functions to mag_control.cpp * ekf control: check for validity of mag strength from WMM and falls back to average earth mag field with larger gate if not valid * ekf control: remove evyaw check for mag inhibition * ekf control: change nested ternary operator into if-else if * Ekf: create AlphaFilter template class for simple low-pass filtering 0.1/0.9 type low-pass filters are commonly used to smooth data, this class is meant to abstract the computation of this filter * ekf control: reset heading using mag_lpf data to avoid resetting on an outlier fixes ecl issue #525 * ekf control: replace mag_states_only flag with mag_field_disturbed and add parameter to enable or disable mag field strength check * ekf control: remove AUTOFW mag fusion type as not needed This was implemented for VTOL but did not solve the problem and should not be used anymore * ekf control: use start/stop mag functions everywhere instead of setting the flag * ekf control: Run mag fusion depending on yaw_align instead of tilt_align as there is no reason to fuse mag when the ekf isn't aligned * AlphaFilter: add test for float and Vector3f
2019-11-08 11:02:59 -04:00
bool Ekf::isTerrainEstimateValid() const
EKF: Fix non GPS aiding data reset logic (#418) * EKF: Move optical flow specific state reset to helper functions * EKF: Ensure loss of optical flow aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using flow data as a velocity reference. If flow data is unavailable for too long - declare optical flow use stopped. Use consistent time periods for all resets * EKF: Ensure loss of external vision aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using data as a position. Don't reset velocity if there is another source of aiding constraining it. If data is unavailable for too long, declare external vision use stopped. Use consistent time periods for all resets. * EKF: Update parameter documentation Make the distinction between the no_gps_timeout_max and no_aid_timeout_max parameters clearer * EKF: make class variable units consistent with documentation * EKF: Don't reset states when optical flow use commences if using external vision * EKF: Stop optical flow fusion when on ground if excessive movement is detected. * EKF: fix terrain estimator vulnerabilities Reset estimate to sensor value if rejected for 10 seconds Protect against user motion when on ground. Fix unnecessary duplication of terrain validity check and separate validity update and reporting. * EKF: remove unnecessary Info console prints Optical flow use information can be obtained from the estimator_status.control_mode_flags message * EKF: fix inaccurate comment * EKF: remove duplicate calculation from terrain validity accessor function
2018-04-09 05:35:15 -03:00
{
return _hagl_valid;
EKF: Fix non GPS aiding data reset logic (#418) * EKF: Move optical flow specific state reset to helper functions * EKF: Ensure loss of optical flow aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using flow data as a velocity reference. If flow data is unavailable for too long - declare optical flow use stopped. Use consistent time periods for all resets * EKF: Ensure loss of external vision aiding is handled correctly If data is only source of aiding and has been rejected for too long - reset using data as a position. Don't reset velocity if there is another source of aiding constraining it. If data is unavailable for too long, declare external vision use stopped. Use consistent time periods for all resets. * EKF: Update parameter documentation Make the distinction between the no_gps_timeout_max and no_aid_timeout_max parameters clearer * EKF: make class variable units consistent with documentation * EKF: Don't reset states when optical flow use commences if using external vision * EKF: Stop optical flow fusion when on ground if excessive movement is detected. * EKF: fix terrain estimator vulnerabilities Reset estimate to sensor value if rejected for 10 seconds Protect against user motion when on ground. Fix unnecessary duplication of terrain validity check and separate validity update and reporting. * EKF: remove unnecessary Info console prints Optical flow use information can be obtained from the estimator_status.control_mode_flags message * EKF: fix inaccurate comment * EKF: remove duplicate calculation from terrain validity accessor function
2018-04-09 05:35:15 -03:00
}
void Ekf::updateTerrainValidity()
{
// we have been fusing range finder measurements in the last 5 seconds
const bool recent_range_fusion = isRecent(_time_last_hagl_fuse, (uint64_t)5e6);
// we have been fusing optical flow measurements for terrain estimation within the last 5 seconds
// this can only be the case if the main filter does not fuse optical flow
const bool recent_flow_for_terrain_fusion = isRecent(_time_last_of_fuse, (uint64_t)5e6)
&& !_control_status.flags.opt_flow;
_hagl_valid = (_terrain_initialised && (recent_range_fusion || recent_flow_for_terrain_fusion));
_hagl_sensor_status.flags.range_finder = shouldUseRangeFinderForHagl()
&& recent_range_fusion
&& (_time_last_fake_hagl_fuse != _time_last_hagl_fuse);
_hagl_sensor_status.flags.flow = shouldUseOpticalFlowForHagl()
&& recent_flow_for_terrain_fusion;
}
// get the estimated vertical position of the terrain relative to the NED origin
float Ekf::getTerrainVertPos() const
{
return _terrain_vpos;
}