Copter: support pre-flight calibration of gyro
This commit is contained in:
parent
9a0a83f404
commit
a8733ae8a8
@ -1100,10 +1100,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||||
if (packet.param1 == 1 ||
|
if (packet.param1 == 1) {
|
||||||
packet.param2 == 1) {
|
// gyro offset calibration
|
||||||
ins.init_accel();
|
ins.init_gyro();
|
||||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
if (packet.param3 == 1) {
|
if (packet.param3 == 1) {
|
||||||
|
Loading…
Reference in New Issue
Block a user