AP_InertialSensor: default TMAX to 70

if user forgets to set this then better to just timeout rather than
calibrating over a small range
This commit is contained in:
Andrew Tridgell 2021-01-23 10:11:14 +11:00
parent 9861a02c60
commit 0535c4f592
1 changed files with 1 additions and 1 deletions

View File

@ -68,7 +68,7 @@ const AP_Param::GroupInfo AP_InertialSensor::TCal::var_info[] = {
// @Units: degC // @Units: degC
// @User: Advanced // @User: Advanced
// @Calibration: 1 // @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 // @Param: ACC1_X
// @DisplayName: Accelerometer 1st order temperature coefficient X axis // @DisplayName: Accelerometer 1st order temperature coefficient X axis