Copter: use new accel cal interact over MAVLink

This commit is contained in:
Andrew Tridgell 2013-05-08 16:19:26 +10:00
parent 2ddeaa7f4d
commit 9feb46c834
1 changed files with 1 additions and 1 deletions

View File

@ -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));