mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
InertialNav: do not reset velocity after glitch clears
This commit is contained in:
parent
7b9fa1ea79
commit
009f42b2e1
@ -185,8 +185,6 @@ void AP_InertialNav::correct_with_gps(uint32_t now, int32_t lon, int32_t lat)
|
||||
// reset the inertial nav position and velocity to gps values
|
||||
if (_flags.gps_glitching) {
|
||||
set_position_xy(x,y);
|
||||
set_velocity_xy(_ahrs.get_gps().velocity().x * 100.0f,
|
||||
_ahrs.get_gps().velocity().y * 100.0f);
|
||||
_position_error.x = 0.0f;
|
||||
_position_error.y = 0.0f;
|
||||
}else{
|
||||
@ -334,7 +332,6 @@ void AP_InertialNav::correct_with_baro(float baro_alt, float dt)
|
||||
// reset the inertial nav alt to baro alt
|
||||
if (_flags.baro_glitching) {
|
||||
set_altitude(baro_alt);
|
||||
set_velocity_z(_baro.get_climb_rate() * 100.0f);
|
||||
_position_error.z = 0.0f;
|
||||
}else{
|
||||
// 3rd order samples (i.e. position from baro) are delayed by 150ms (15 iterations at 100hz)
|
||||
|
Loading…
Reference in New Issue
Block a user