mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Copter: support pre-flight calibration of gyro
This commit is contained in:
parent
661755e05a
commit
7f8a68d44a
@ -1104,10 +1104,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1) {
|
||||
ins.init_accel();
|
||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
||||
if (packet.param1 == 1) {
|
||||
// gyro offset calibration
|
||||
ins.init_gyro();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
if (packet.param3 == 1) {
|
||||
|
Loading…
Reference in New Issue
Block a user