From 27d3564eabb15c8a167ef37f2be4b01edbe35385 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 30 Dec 2011 23:37:24 -0800 Subject: [PATCH] Sync with Arduplane --- ArduCopter/GCS_Mavlink.pde | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 06397209f9..ad02ff3c3e 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -73,11 +73,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack } uint8_t status = MAV_STATE_ACTIVE; - + if (!motor_armed) { status = MAV_STATE_STANDBY; } - + uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 mavlink_msg_sys_status_send( @@ -116,12 +116,12 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) chan, nav_roll / 1.0e2, nav_pitch / 1.0e2, + nav_bearing / 1.0e2, target_bearing / 1.0e2, - dcm.yaw_sensor / 1.0e2, // was target_bearing wp_distance, altitude_error / 1.0e2, - nav_lon, // was 0 - nav_lat); // was 0 + 0, + crosstrack_error); // was 0 } static void NOINLINE send_gps_raw(mavlink_channel_t chan)