diff --git a/AntennaTracker/GCS_Mavlink.pde b/AntennaTracker/GCS_Mavlink.pde index 3ffd887744..70082d6a1b 100644 --- a/AntennaTracker/GCS_Mavlink.pde +++ b/AntennaTracker/GCS_Mavlink.pde @@ -533,7 +533,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) #if !defined( __AVR_ATmega1280__ ) if (packet.param5 == 1) { float trim_roll, trim_pitch; - AP_InertialSensor_UserInteract_MAVLink interact(chan); + AP_InertialSensor_UserInteract_MAVLink interact(this); if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) { // reset ahrs's trim to suggested values from calibration routine ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));