AntennaTracker: use new interactive accelcal

This commit is contained in:
Andrew Tridgell 2015-03-07 21:32:06 +11:00
parent 9b9aa3dc33
commit e6b291f270

View File

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