mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: fixed baro-only preflight cal
this was causing a full level, which mucked up the INS calibration
This commit is contained in:
parent
5800c2a2c8
commit
a44e3191df
@ -1210,10 +1210,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1 ||
|
||||
packet.param3 == 1) {
|
||||
packet.param2 == 1) {
|
||||
ins.init_accel();
|
||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
||||
}
|
||||
if (packet.param3 == 1) {
|
||||
init_barometer();
|
||||
}
|
||||
if (packet.param4 == 1) {
|
||||
trim_radio();
|
||||
|
Loading…
Reference in New Issue
Block a user