Skip to content

Commit

Permalink
AP_GPS: fix GPS headings
Browse files Browse the repository at this point in the history
* If you don't wrap the heading, you can get a flyaway

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed May 12, 2024
1 parent 693151e commit fc105ae
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ class AP_GPS
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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_GSOF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,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;
Expand Down

0 comments on commit fc105ae

Please sign in to comment.