Browse Source

Copter: support pre-flight calibration of gyro

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
a8733ae8a8
  1. 7
      ArduCopter/GCS_Mavlink.pde

7
ArduCopter/GCS_Mavlink.pde

@ -1100,10 +1100,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1100,10 +1100,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…
Cancel
Save