From 6c2f623df2d0b2958ae82143b2c35c07623f0dad Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 26 Aug 2013 08:46:22 +1000 Subject: [PATCH] Rover: send y accel in m/s/s as nav_pitch this allows for easier tuning in MissionPlanner --- APMrover2/GCS_Mavlink.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index a2aa37a5e7..d62bcd99ed 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -239,8 +239,8 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) { mavlink_msg_nav_controller_output_send( chan, - lateral_acceleration, - 0, + lateral_acceleration, // use nav_roll to hold demanded Y accel + ins.get_accel().y, // use nav_pitch to hold actual Y accel nav_controller->nav_bearing_cd() * 0.01f, nav_controller->target_bearing_cd() * 0.01f, wp_distance,