From 9feb46c8346e9104267f732fe358ca7f63f0bba3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 8 May 2013 16:19:26 +1000 Subject: [PATCH] Copter: use new accel cal interact over MAVLink --- ArduCopter/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 680efd60c4..77f0c88e98 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1203,7 +1203,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) if (packet.param5 == 1) { float trim_roll, trim_pitch; // this blocks - AP_InertialSensor_UserInteractStream interact(hal.console); + 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));