diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 79ddd071f0..4640650aeb 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1146,6 +1146,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) if (packet.param4 == 1) { trim_radio(); } + if (packet.param5 == 1) { + float trim_roll, trim_pitch; + AP_InertialSensor_UserInteract_MAVLink interact(chan); + if(ins.calibrate_accel(flash_leds, &interact, 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; break;