-
Notifications
You must be signed in to change notification settings - Fork 13.5k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
EKF2: Zero gyro update #21691
EKF2: Zero gyro update #21691
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,96 @@ | ||
/**************************************************************************** | ||
* | ||
* Copyright (c) 2023 PX4 Development Team. 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 PX4 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 zero_gyro_update.cpp | ||
* Control function for ekf zero gyro update | ||
*/ | ||
|
||
#include "ekf.h" | ||
|
||
void Ekf::controlZeroGyroUpdate(const imuSample &imu_delayed) | ||
{ | ||
if (!(_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GyroBias))) { | ||
return; | ||
} | ||
|
||
// When at rest, fuse the gyro data as a direct observation of the gyro bias | ||
if (_control_status.flags.vehicle_at_rest) { | ||
// Downsample gyro data to run the fusion at a lower rate | ||
_zgup_delta_ang += imu_delayed.delta_ang; | ||
_zgup_delta_ang_dt += imu_delayed.delta_ang_dt; | ||
|
||
static constexpr float zgup_dt = 0.2f; | ||
const bool zero_gyro_update_data_ready = _zgup_delta_ang_dt >= zgup_dt; | ||
|
||
if (zero_gyro_update_data_ready) { | ||
Vector3f delta_ang_scaled = _zgup_delta_ang / _zgup_delta_ang_dt * _dt_ekf_avg; | ||
Vector3f innovation = _state.delta_ang_bias - delta_ang_scaled; | ||
|
||
const float d_ang_sig = _dt_ekf_avg * math::constrain(_params.gyro_noise, 0.0f, 1.0f); | ||
//const float obs_var = sq(d_ang_sig) * (_dt_ekf_avg / _zgup_delta_ang_dt); // This is correct but too small for single precision | ||
const float obs_var = sq(d_ang_sig); | ||
|
||
Vector3f innov_var{ | ||
P(10, 10) + obs_var, | ||
P(11, 11) + obs_var, | ||
P(12, 12) + obs_var}; | ||
|
||
for (int i = 0; i < 3; i++) { | ||
fuseDeltaAngBias(innovation(i), innov_var(i), i); | ||
} | ||
|
||
// Reset the integrators | ||
_zgup_delta_ang.setZero(); | ||
_zgup_delta_ang_dt = 0.f; | ||
} | ||
|
||
} else if (_control_status_prev.flags.vehicle_at_rest) { | ||
// Reset the integrators | ||
_zgup_delta_ang.setZero(); | ||
_zgup_delta_ang_dt = 0.f; | ||
} | ||
} | ||
|
||
void Ekf::fuseDeltaAngBias(const float innov, const float innov_var, const int obs_index) | ||
{ | ||
Vector24f K; // Kalman gain vector for any single observation - sequential fusion is used. | ||
const unsigned state_index = obs_index + 10; | ||
|
||
// calculate kalman gain K = PHS, where S = 1/innovation variance | ||
for (int row = 0; row < _k_num_states; row++) { | ||
K(row) = P(row, state_index) / innov_var; | ||
} | ||
|
||
measurementUpdate(K, innov_var, innov); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Just for my own understanding, why no innovation check? We'd be screwed anyway with that bad gyro? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yes, an innovation filter means more parameters and we anyway want to always force fuse the data here because we know that if we're at rest, the gyro value is the bias, no matter if the rest of the filter agrees with that or not. We could argue that the innovation filter will be useful to reject outliers, but I don't think it'll be a real problem here. |
||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -43,52 +43,23 @@ void Ekf::controlZeroInnovationHeadingUpdate() | |
const bool yaw_aiding = _control_status.flags.mag_hdg || _control_status.flags.mag_3D | ||
|| _control_status.flags.ev_yaw || _control_status.flags.gps_yaw; | ||
|
||
if (!_control_status.flags.tilt_align) { | ||
// fuse zero heading innovation during the leveling fine alignment step to keep the yaw variance low | ||
float innovation = 0.f; | ||
float obs_var = _control_status.flags.vehicle_at_rest ? 0.001f : 0.1f; | ||
estimator_aid_source1d_s unused; | ||
fuseYaw(innovation, obs_var, unused); | ||
_time_last_heading_fuse = 0; | ||
_last_static_yaw = NAN; | ||
// fuse zero innovation at a limited rate if the yaw variance is too large | ||
if (_control_status.flags.tilt_align | ||
&& !yaw_aiding | ||
&& isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) { | ||
|
||
} else if (_control_status.flags.vehicle_at_rest) { | ||
// When at rest or no source of yaw aiding is active yaw fusion is run selectively to enable yaw gyro | ||
// bias learning when stationary on ground and to prevent uncontrolled yaw variance growth | ||
const float euler_yaw = getEulerYaw(_R_to_earth); | ||
// Use an observation variance larger than usual but small enough | ||
// to constrain the yaw variance just below the threshold | ||
float obs_var = 0.25f; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I know it was already like this, but any little comment we could add to justify this particular magic number? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. sure There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. done |
||
estimator_aid_source1d_s aid_src_status; | ||
Vector24f H_YAW; | ||
|
||
if (PX4_ISFINITE(_last_static_yaw)) { | ||
// fuse last static yaw at a limited rate (every 200 milliseconds) | ||
if (!yaw_aiding && isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) { | ||
float innovation = wrap_pi(euler_yaw - _last_static_yaw); | ||
float obs_var = 0.01f; | ||
estimator_aid_source1d_s unused; | ||
fuseYaw(innovation, obs_var, unused); | ||
} | ||
computeYawInnovVarAndH(obs_var, aid_src_status.innovation_variance, H_YAW); | ||
|
||
} else { | ||
// record static yaw when transitioning to at rest | ||
_last_static_yaw = euler_yaw; | ||
if ((aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { | ||
// The yaw variance is too large, fuse fake measurement | ||
float innovation = 0.f; | ||
fuseYaw(innovation, obs_var, aid_src_status, H_YAW); | ||
} | ||
|
||
} else { | ||
// vehicle moving and tilt alignment completed | ||
|
||
// fuse zero innovation at a limited rate if the yaw variance is too large | ||
if (!yaw_aiding && isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) { | ||
float obs_var = 0.25f; | ||
estimator_aid_source1d_s aid_src_status; | ||
Vector24f H_YAW; | ||
|
||
computeYawInnovVarAndH(obs_var, aid_src_status.innovation_variance, H_YAW); | ||
|
||
if ((aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { | ||
// The yaw variance is too large, fuse fake measurement | ||
float innovation = 0.f; | ||
fuseYaw(innovation, obs_var, aid_src_status, H_YAW); | ||
} | ||
} | ||
|
||
_last_static_yaw = NAN; | ||
} | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm wondering if we should start using the specific dt everywhere appropriate? Maybe something to discuss later after accel/gyro bias states.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The filter estimates the delta angle based on
_dt_ekf_avg
, this is why we need to scale it with that value here. But yes, I generally agree that using angular rate values will reduce complexity.