mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fix GPS headings
* If you don't wrap the heading, you can get a flyaway Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
c110b180fd
commit
a8222265f1
|
@ -192,7 +192,7 @@ public:
|
|||
uint16_t time_week; ///< GPS week number
|
||||
Location location; ///< last fix location
|
||||
float ground_speed; ///< ground speed in m/s
|
||||
float ground_course; ///< ground course in degrees
|
||||
float ground_course; ///< ground course in degrees, wrapped 0-360
|
||||
float gps_yaw; ///< GPS derived yaw information, if available (degrees)
|
||||
uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading
|
||||
bool gps_yaw_configured; ///< GPS is configured to provide yaw
|
||||
|
|
|
@ -324,7 +324,7 @@ AP_GPS_GSOF::process_message(void)
|
|||
if ((vflag & 1) == 1)
|
||||
{
|
||||
state.ground_speed = SwapFloat(msg.data, a + 1);
|
||||
state.ground_course = degrees(SwapFloat(msg.data, a + 5));
|
||||
state.ground_course = wrap_360(degrees(SwapFloat(msg.data, a + 5)));
|
||||
fill_3d_velocity();
|
||||
state.velocity.z = -SwapFloat(msg.data, a + 9);
|
||||
state.have_vertical_velocity = true;
|
||||
|
|
Loading…
Reference in New Issue