mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_AHRS: Fix DCM gndVelADS on groundspeed_vector() with airspeed_use
This commit is contained in:
parent
5ab000376b
commit
fb311208ab
@ -255,7 +255,7 @@ Vector2f AP_AHRS::groundspeed_vector(void)
|
||||
const Vector3f wind = wind_estimate();
|
||||
const Vector2f wind2d(wind.x, wind.y);
|
||||
const Vector2f airspeed_vector(_cos_yaw * airspeed, _sin_yaw * airspeed);
|
||||
gndVelADS = airspeed_vector - wind2d;
|
||||
gndVelADS = airspeed_vector + wind2d;
|
||||
}
|
||||
|
||||
// Generate estimate of ground speed vector using GPS
|
||||
|
Loading…
Reference in New Issue
Block a user