From 8e8049009864c946145534a1c8ef81243e6f7a77 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 8 Dec 2017 10:21:44 +0900 Subject: [PATCH] Rover: reporting gets lat accel from attitude control --- APMrover2/GCS_Mavlink.cpp | 2 +- APMrover2/Log.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 085fa322ce..83236b04e3 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -131,7 +131,7 @@ void Rover::send_nav_controller_output(mavlink_channel_t chan) { mavlink_msg_nav_controller_output_send( chan, - control_mode->lateral_acceleration, // use nav_roll to hold demanded Y accel + g2.attitude_control.get_desired_lat_accel(), ahrs.groundspeed() * ins.get_gyro().z, // use nav_pitch to hold actual Y accel nav_controller->nav_bearing_cd() * 0.01f, nav_controller->target_bearing_cd() * 0.01f, diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 109954386c..0745ec822c 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -180,7 +180,7 @@ void Rover::Log_Write_Rangefinder() struct log_Rangefinder pkt = { LOG_PACKET_HEADER_INIT(LOG_RANGEFINDER_MSG), time_us : AP_HAL::micros64(), - lateral_accel : control_mode->lateral_acceleration, + lateral_accel : g2.attitude_control.get_desired_lat_accel(), rangefinder1_distance : s0 ? s0->distance_cm() : (uint16_t)0, rangefinder2_distance : s1 ? s1->distance_cm() : (uint16_t)0, detected_count : obstacle.detected_count,