diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index e45aef88c44c95..e21bf665246316 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -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 diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 4fbfef5833a2d5..4327c9f4d4bbba 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -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;