diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index c646cf6348..ec33e9992d 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -790,7 +790,7 @@ static void update_GPS(void) if(ground_start_count > 1){ ground_start_count--; - ground_start_avg += g_gps->ground_speed; + ground_start_avg += g_gps->ground_speed_cm; } else if (ground_start_count == 1) { // We countdown N number of good GPS fixes @@ -808,7 +808,7 @@ static void update_GPS(void) ground_start_count = 0; } } - ground_speed = g_gps->ground_speed * 0.01; + ground_speed = g_gps->ground_speed_cm * 0.01; } } diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index d29af7e3c6..8589911b0b 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -227,7 +227,7 @@ static void NOINLINE send_location(mavlink_channel_t chan) fix_time, current_loc.lat, // in 1E7 degrees current_loc.lng, // in 1E7 degrees - g_gps->altitude * 10, // millimeters above sea level + g_gps->altitude_cm * 10, // millimeters above sea level (current_loc.alt - home.alt) * 10, // millimeters above ground g_gps->velocity_north() * 100, // X speed cm/s (+ve North) g_gps->velocity_east() * 100, // Y speed cm/s (+ve East) @@ -258,11 +258,11 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) g_gps->status(), g_gps->latitude, // in 1E7 degrees g_gps->longitude, // in 1E7 degrees - g_gps->altitude * 10, // in mm + g_gps->altitude_cm * 10, // in mm g_gps->hdop, 65535, - g_gps->ground_speed, // cm/s - g_gps->ground_course, // 1/100 degrees, + g_gps->ground_speed_cm, // cm/s + g_gps->ground_course_cd, // 1/100 degrees, g_gps->num_sats); } @@ -338,8 +338,8 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) { mavlink_msg_vfr_hud_send( chan, - (float)g_gps->ground_speed / 100.0, - (float)g_gps->ground_speed / 100.0, + (float)g_gps->ground_speed_cm / 100.0, + (float)g_gps->ground_speed_cm / 100.0, (ahrs.yaw_sensor / 100) % 360, (uint16_t)(100 * channel_throttle->norm_output()), current_loc.alt / 100.0, diff --git a/APMrover2/commands.pde b/APMrover2/commands.pde index 47582f5926..c1e39135d8 100644 --- a/APMrover2/commands.pde +++ b/APMrover2/commands.pde @@ -166,8 +166,8 @@ void init_home() home.lng = g_gps->longitude; // Lon * 10**7 home.lat = g_gps->latitude; // Lat * 10**7 - gps_base_alt = max(g_gps->altitude, 0); - home.alt = g_gps->altitude; + gps_base_alt = max(g_gps->altitude_cm, 0); + home.alt = g_gps->altitude_cm; home_is_set = true; // Save Home to EEPROM - Command 0 diff --git a/APMrover2/test.pde b/APMrover2/test.pde index 25f0d12ffc..60001a784e 100644 --- a/APMrover2/test.pde +++ b/APMrover2/test.pde @@ -357,7 +357,7 @@ test_gps(uint8_t argc, const Menu::arg *argv) cliSerial->printf_P(PSTR("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n"), g_gps->latitude, g_gps->longitude, - g_gps->altitude/100, + g_gps->altitude_cm/100, g_gps->num_sats); }else{ cliSerial->printf_P(PSTR("."));