Browse Source

AP_NavEKF3: CorrectGPSForAntennaOffset always corrects vel

c415-sdk
Randy Mackay 4 years ago
parent
commit
3d4e1cd5c5
  1. 4
      libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp

4
libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp

@ -327,13 +327,13 @@ void NavEKF3_core::CorrectGPSForAntennaOffset(gps_elements &gps_data) const @@ -327,13 +327,13 @@ void NavEKF3_core::CorrectGPSForAntennaOffset(gps_elements &gps_data) const
if (posOffsetBody.is_zero()) {
return;
}
if (fuseVelData) {
// TODO use a filtered angular rate with a group delay that matches the GPS delay
Vector3f angRate = imuDataDelayed.delAng * (1.0f/imuDataDelayed.delAngDT);
Vector3f velOffsetBody = angRate % posOffsetBody;
Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
gps_data.vel -= velOffsetEarth;
}
Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
gps_data.pos.x -= posOffsetEarth.x;
gps_data.pos.y -= posOffsetEarth.y;

Loading…
Cancel
Save