Skip to content
Snippets Groups Projects
Commit c33f5437 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Plane: changed preflight calibration to prevent accel cal from MP

MissionPlanner sends param1=1 and param3=1 for preflight
calibration. This was having the effect of redoing the accel
calibration as 1D cal on every flight!
parent 4f44a63b
No related branches found
No related tags found
No related merge requests found
......@@ -1008,22 +1008,21 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1) {
startup_INS_ground(true);
} else if (packet.param3 == 1) {
if (packet.param3 == 1) {
in_calibration = true;
init_barometer();
if (airspeed.enabled()) {
zero_airspeed(false);
}
in_calibration = false;
}
if (packet.param4 == 1) {
} else if (packet.param1 == 1 ||
packet.param2 == 1) {
startup_INS_ground(true);
} else if (packet.param4 == 1) {
trim_radio();
}
}
#if !defined( __AVR_ATmega1280__ )
if (packet.param5 == 1) {
else if (packet.param5 == 1) {
float trim_roll, trim_pitch;
AP_InertialSensor_UserInteract_MAVLink interact(chan);
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
......@@ -1032,6 +1031,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
}
#endif
else {
send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration"));
}
result = MAV_RESULT_ACCEPTED;
break;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment