From aac652a1b40916612e6895e3e61b0e38d0abd879 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 May 2015 07:28:55 +1000 Subject: [PATCH] Copter: support setting just accel trim with preflight-cal use param5==2 --- ArduCopter/GCS_Mavlink.pde | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 08cc4fa437..550f1c7868 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1188,6 +1188,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else { result = MAV_RESULT_FAILED; } + } else if (is_equal(packet.param5,2.0f)) { + // accel trim + float trim_roll, trim_pitch; + if(ins.calibrate_trim(trim_roll, trim_pitch)) { + // reset ahrs's trim to suggested values from calibration routine + ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; + } } else if (is_equal(packet.param6,1.0f)) { // compassmot calibration result = mavlink_compassmot(chan);