diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 56fddd7f3d..1827a2100a 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1082,6 +1082,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 { send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration"));