|
|
|
@ -256,7 +256,7 @@ void Ekf::resetHeightToGps()
@@ -256,7 +256,7 @@ void Ekf::resetHeightToGps()
|
|
|
|
|
_information_events.flags.reset_hgt_to_gps = true; |
|
|
|
|
|
|
|
|
|
const float z_pos_before_reset = _state.pos(2); |
|
|
|
|
resetVerticalPositionTo(-_gps_sample_delayed.hgt + _gps_alt_ref); |
|
|
|
|
resetVerticalPositionTo(-_gps_sample_delayed.hgt + getEkfGlobalOriginAltitude()); |
|
|
|
|
|
|
|
|
|
// the state variance is the same as the observation
|
|
|
|
|
P.uncorrelateCovarianceSetVariance<1>(9, getGpsHeightVariance()); |
|
|
|
@ -695,40 +695,62 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo
@@ -695,40 +695,62 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo
|
|
|
|
|
origin_time = _last_gps_origin_time_us; |
|
|
|
|
latitude = _pos_ref.getProjectionReferenceLat(); |
|
|
|
|
longitude = _pos_ref.getProjectionReferenceLon(); |
|
|
|
|
origin_alt = _gps_alt_ref; |
|
|
|
|
origin_alt = getEkfGlobalOriginAltitude(); |
|
|
|
|
return _NED_origin_initialised; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude) |
|
|
|
|
bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude) |
|
|
|
|
{ |
|
|
|
|
bool current_pos_available = false; |
|
|
|
|
double current_lat = static_cast<double>(NAN); |
|
|
|
|
double current_lon = static_cast<double>(NAN); |
|
|
|
|
float current_alt = 0.f; |
|
|
|
|
// sanity check valid latitude/longitude and altitude anywhere between the Mariana Trench and edge of Space
|
|
|
|
|
if (PX4_ISFINITE(latitude) && (abs(latitude) <= 90) |
|
|
|
|
&& PX4_ISFINITE(longitude) && (abs(longitude) <= 180) |
|
|
|
|
&& PX4_ISFINITE(altitude) && (altitude > -12'000.f) && (altitude < 100'000.f) |
|
|
|
|
) { |
|
|
|
|
bool current_pos_available = false; |
|
|
|
|
double current_lat = static_cast<double>(NAN); |
|
|
|
|
double current_lon = static_cast<double>(NAN); |
|
|
|
|
|
|
|
|
|
// if we are already doing aiding, correct for the change in position since the EKF started navigating
|
|
|
|
|
if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { |
|
|
|
|
_pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); |
|
|
|
|
current_alt = -_state.pos(2) + _gps_alt_ref; |
|
|
|
|
current_pos_available = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// reinitialize map projection to latitude, longitude, altitude, and reset position
|
|
|
|
|
_pos_ref.initReference(latitude, longitude, _time_last_imu); |
|
|
|
|
// if we are already doing aiding, correct for the change in position since the EKF started navigating
|
|
|
|
|
if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { |
|
|
|
|
_pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); |
|
|
|
|
current_pos_available = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (current_pos_available) { |
|
|
|
|
// reset horizontal position
|
|
|
|
|
Vector2f position = _pos_ref.project(current_lat, current_lon); |
|
|
|
|
resetHorizontalPositionTo(position); |
|
|
|
|
const float gps_alt_ref_prev = getEkfGlobalOriginAltitude(); |
|
|
|
|
|
|
|
|
|
// reset altitude
|
|
|
|
|
// reinitialize map projection to latitude, longitude, altitude, and reset position
|
|
|
|
|
_pos_ref.initReference(latitude, longitude, _time_last_imu); |
|
|
|
|
_gps_alt_ref = altitude; |
|
|
|
|
resetVerticalPositionTo(_gps_alt_ref - current_alt); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
// reset altitude
|
|
|
|
|
_gps_alt_ref = altitude; |
|
|
|
|
// minimum change in position or height that triggers a reset
|
|
|
|
|
static constexpr float MIN_RESET_DIST_M = 0.01f; |
|
|
|
|
|
|
|
|
|
if (current_pos_available) { |
|
|
|
|
// reset horizontal position
|
|
|
|
|
Vector2f position = _pos_ref.project(current_lat, current_lon); |
|
|
|
|
|
|
|
|
|
if (Vector2f(position - Vector2f(_state.pos)).longerThan(MIN_RESET_DIST_M)) { |
|
|
|
|
resetHorizontalPositionTo(position); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// reset vertical position (if there's any change)
|
|
|
|
|
if (fabsf(altitude - gps_alt_ref_prev) > MIN_RESET_DIST_M) { |
|
|
|
|
// determine current z
|
|
|
|
|
float current_alt = -_state.pos(2) + gps_alt_ref_prev; |
|
|
|
|
|
|
|
|
|
resetVerticalPositionTo(_gps_alt_ref - current_alt); |
|
|
|
|
|
|
|
|
|
_baro_hgt_offset -= _state_reset_status.posD_change; |
|
|
|
|
|
|
|
|
|
_rng_hgt_offset -= _state_reset_status.posD_change; |
|
|
|
|
_ev_hgt_offset -= _state_reset_status.posD_change; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position
|
|
|
|
@ -1283,7 +1305,7 @@ void Ekf::startGpsHgtFusion()
@@ -1283,7 +1305,7 @@ void Ekf::startGpsHgtFusion()
|
|
|
|
|
// switch out of range aid
|
|
|
|
|
// calculate height sensor offset such that current
|
|
|
|
|
// measurement matches our current height estimate
|
|
|
|
|
_gps_hgt_offset = (_gps_sample_delayed.hgt - _gps_alt_ref) + _state.pos(2); |
|
|
|
|
_gps_hgt_offset = _gps_sample_delayed.hgt - getEkfGlobalOriginAltitude() + _state.pos(2); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
_gps_hgt_offset = 0.f; |
|
|
|
@ -1381,7 +1403,7 @@ void Ekf::updateBaroHgtBias()
@@ -1381,7 +1403,7 @@ void Ekf::updateBaroHgtBias()
|
|
|
|
|
&& !_baro_hgt_faulty) { |
|
|
|
|
// Use GPS altitude as a reference to compute the baro bias measurement
|
|
|
|
|
const float baro_bias = (_baro_sample_delayed.hgt - _baro_hgt_offset) |
|
|
|
|
- (_gps_sample_delayed.hgt - _gps_alt_ref); |
|
|
|
|
- (_gps_sample_delayed.hgt - getEkfGlobalOriginAltitude()); |
|
|
|
|
const float baro_bias_var = getGpsHeightVariance() + sq(_params.baro_noise); |
|
|
|
|
_baro_b_est.fuseBias(baro_bias, baro_bias_var); |
|
|
|
|
} |
|
|
|
|