From 123800ccd2c4f83f25e1ed061b1c40ee57828acc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 31 Jul 2019 09:01:44 +1000 Subject: [PATCH] AP_InertialSensor: default INS_USE3 to 1 --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 1683f97ec8..8531976222 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -291,7 +291,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Description: Use third IMU for attitude, velocity and position estimates // @Values: 0:Disabled,1:Enabled // @User: Advanced - AP_GROUPINFO("USE3", 22, AP_InertialSensor, _use[2], 0), + AP_GROUPINFO("USE3", 22, AP_InertialSensor, _use[2], 1), // @Param: STILL_THRESH // @DisplayName: Stillness threshold for detecting if we are moving