Reverted to current_loc.alt in MSG_VFR_HUD and MSG_Location

This commit is contained in:
Jason Short 2011-09-17 11:16:13 -07:00
parent 0f7b317a8d
commit 0b701f7351
1 changed files with 4 additions and 4 deletions

View File

@ -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;
}