diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 28fedcac0c..f64f115cb3 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1075,9 +1075,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else if (is_equal(packet.param5,2.0f)) { // accel trim float trim_roll, trim_pitch; - if(ins.calibrate_trim(trim_roll, trim_pitch)) { + if(plane.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)); + plane.ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); result = MAV_RESULT_ACCEPTED; } else { result = MAV_RESULT_FAILED;