Plane: support 3D accel calibration over MAVLink

This commit is contained in:
Andrew Tridgell 2013-05-08 16:25:35 +10:00
parent 9feb46c834
commit 81c1fd5fc4
1 changed files with 8 additions and 0 deletions

View File

@ -1146,6 +1146,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.param4 == 1) { if (packet.param4 == 1) {
trim_radio(); trim_radio();
} }
if (packet.param5 == 1) {
float trim_roll, trim_pitch;
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));
}
}
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
break; break;