Skip to content

Commit

Permalink
Plane: Move position update to 50hz loop rather then the 10hz
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell authored and tridge committed Apr 21, 2016
1 parent cf7b612 commit f5749b4
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,6 +411,9 @@ void Plane::airspeed_ratio_update(void)
*/
void Plane::update_GPS_50Hz(void)
{
// get position from AHRS
have_position = ahrs.get_position(current_loc);

static uint32_t last_gps_reading[GPS_MAX_INSTANCES];
gps.update();

Expand All @@ -429,9 +432,6 @@ void Plane::update_GPS_50Hz(void)
*/
void Plane::update_GPS_10Hz(void)
{
// get position from AHRS
have_position = ahrs.get_position(current_loc);

static uint32_t last_gps_msg_ms;
if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
last_gps_msg_ms = gps.last_message_time_ms();
Expand Down

0 comments on commit f5749b4

Please sign in to comment.