diff --git a/ArduCopter/Mavlink_Common.h b/ArduCopter/Mavlink_Common.h index a04ffecd4c..6ecb79761f 100644 --- a/ArduCopter/Mavlink_Common.h +++ b/ArduCopter/Mavlink_Common.h @@ -126,8 +126,8 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_ chan, current_loc.lat, current_loc.lng, - /*current_loc.alt * 10,*/ // changed to absolute altitude - g_gps->altitude, + current_loc.alt * 10, // reverted to relative altitude + /*g_gps->altitude,*/ g_gps->ground_speed * rot.a.x, g_gps->ground_speed * rot.b.x, g_gps->ground_speed * rot.c.x); @@ -248,8 +248,8 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_ (float)g_gps->ground_speed / 100.0, (dcm.yaw_sensor / 100) % 360, g.rc_3.servo_out/10, - /*current_loc.alt / 100.0,*/ // changed to absolute altitude - g_gps->altitude/100.0, + current_loc.alt / 100.0, + /*g_gps->altitude/100.0,*/ // reverted to relative altitude climb_rate); break; }