From 0535c4f5929bb312ac3459b0d44ad268cdc12ec0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 23 Jan 2021 10:11:14 +1100 Subject: [PATCH] AP_InertialSensor: default TMAX to 70 if user forgets to set this then better to just timeout rather than calibrating over a small range --- libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index 3fb8d24ceb..cefe84f6f4 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -68,7 +68,7 @@ const AP_Param::GroupInfo AP_InertialSensor::TCal::var_info[] = { // @Units: degC // @User: Advanced // @Calibration: 1 - AP_GROUPINFO("TMAX", 3, AP_InertialSensor::TCal, temp_max, 0), + AP_GROUPINFO("TMAX", 3, AP_InertialSensor::TCal, temp_max, 70), // @Param: ACC1_X // @DisplayName: Accelerometer 1st order temperature coefficient X axis