|
|
|
@ -4,6 +4,7 @@
@@ -4,6 +4,7 @@
|
|
|
|
|
#include "AP_NavEKF2_core.h" |
|
|
|
|
#include <AP_AHRS/AP_AHRS.h> |
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h> |
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h> |
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder_Backend.h> |
|
|
|
|
#include <AP_GPS/AP_GPS.h> |
|
|
|
|
#include <AP_Baro/AP_Baro.h> |
|
|
|
@ -813,8 +814,9 @@ void NavEKF2_core::selectHeightForFusion()
@@ -813,8 +814,9 @@ void NavEKF2_core::selectHeightForFusion()
|
|
|
|
|
// correct range data for the body frame position offset relative to the IMU
|
|
|
|
|
// the corrected reading is the reading that would have been taken if the sensor was
|
|
|
|
|
// co-located with the IMU
|
|
|
|
|
if (rangeDataToFuse) { |
|
|
|
|
AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(rangeDataDelayed.sensor_idx); |
|
|
|
|
const RangeFinder *_rng = AP::rangefinder(); |
|
|
|
|
if (_rng && rangeDataToFuse) { |
|
|
|
|
const AP_RangeFinder_Backend *sensor = _rng->get_backend(rangeDataDelayed.sensor_idx); |
|
|
|
|
if (sensor != nullptr) { |
|
|
|
|
Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset; |
|
|
|
|
if (!posOffsetBody.is_zero()) { |
|
|
|
@ -832,13 +834,13 @@ void NavEKF2_core::selectHeightForFusion()
@@ -832,13 +834,13 @@ void NavEKF2_core::selectHeightForFusion()
|
|
|
|
|
if (extNavUsedForPos) { |
|
|
|
|
// always use external vision as the height source if using for position.
|
|
|
|
|
activeHgtSource = HGT_SOURCE_EV; |
|
|
|
|
} else if (((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) { |
|
|
|
|
} else if (_rng && ((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) { |
|
|
|
|
if (frontend->_altSource == 1) { |
|
|
|
|
// always use range finder
|
|
|
|
|
activeHgtSource = HGT_SOURCE_RNG; |
|
|
|
|
} else { |
|
|
|
|
// determine if we are above or below the height switch region
|
|
|
|
|
float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt; |
|
|
|
|
float rangeMaxUse = 1e-4f * (float)_rng->max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt; |
|
|
|
|
bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse; |
|
|
|
|
bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse; |
|
|
|
|
|
|
|
|
|