mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_GPS: fix blended ground course
Thanks to jyl58 for finding this
This commit is contained in:
parent
3e628f30ff
commit
b82098ca44
@ -1383,7 +1383,7 @@ void AP_GPS::calc_blended_state(void)
|
||||
|
||||
// Calculate ground speed and course from blended velocity vector
|
||||
state[GPS_BLENDED_INSTANCE].ground_speed = norm(state[GPS_BLENDED_INSTANCE].velocity.x, state[GPS_BLENDED_INSTANCE].velocity.y);
|
||||
state[GPS_BLENDED_INSTANCE].ground_course = wrap_360(degrees(atan2f(state[GPS_BLENDED_INSTANCE].velocity.x, state[GPS_BLENDED_INSTANCE].velocity.x)));
|
||||
state[GPS_BLENDED_INSTANCE].ground_course = wrap_360(degrees(atan2f(state[GPS_BLENDED_INSTANCE].velocity.y, state[GPS_BLENDED_INSTANCE].velocity.x)));
|
||||
|
||||
/*
|
||||
* The blended location in _output_state.location is not stable enough to be used by the autopilot
|
||||
|
Loading…
Reference in New Issue
Block a user