From 3ff71c78144918b6730ed47639e08e44178b004e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Jan 2021 15:07:15 +1100 Subject: [PATCH] AP_InertialSensor: changes from review feedback --- .../AP_InertialSensor/AP_InertialSensor.cpp | 20 +++++++++---------- .../AP_InertialSensor_Backend.cpp | 2 +- .../AP_InertialSensor_tempcal.cpp | 2 +- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 64f583271d..4aa5eca1ac 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -576,7 +576,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("ACC1_CALTEMP", 46, AP_InertialSensor, caltemp_accel[0], -100), + AP_GROUPINFO("ACC1_CALTEMP", 46, AP_InertialSensor, caltemp_accel[0], -300), // @Param: GYR1_CALTEMP // @DisplayName: Calibration temperature for 1st gyroscope @@ -584,7 +584,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("GYR1_CALTEMP", 47, AP_InertialSensor, caltemp_gyro[0], -100), + AP_GROUPINFO("GYR1_CALTEMP", 47, AP_InertialSensor, caltemp_gyro[0], -300), #if INS_MAX_INSTANCES > 1 // @Param: ACC2_CALTEMP @@ -593,7 +593,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("ACC2_CALTEMP", 48, AP_InertialSensor, caltemp_accel[1], -100), + AP_GROUPINFO("ACC2_CALTEMP", 48, AP_InertialSensor, caltemp_accel[1], -300), // @Param: GYR2_CALTEMP // @DisplayName: Calibration temperature for 2nd gyroscope @@ -601,7 +601,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("GYR2_CALTEMP", 49, AP_InertialSensor, caltemp_gyro[1], -100), + AP_GROUPINFO("GYR2_CALTEMP", 49, AP_InertialSensor, caltemp_gyro[1], -300), #endif #if INS_MAX_INSTANCES > 2 @@ -611,7 +611,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("ACC3_CALTEMP", 50, AP_InertialSensor, caltemp_accel[2], -100), + AP_GROUPINFO("ACC3_CALTEMP", 50, AP_InertialSensor, caltemp_accel[2], -300), // @Param: GYR3_CALTEMP // @DisplayName: Calibration temperature for 3rd gyroscope @@ -619,7 +619,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @User: Advanced // @Units: degC // @Calibration: 1 - AP_GROUPINFO("GYR3_CALTEMP", 51, AP_InertialSensor, caltemp_gyro[2], -100), + AP_GROUPINFO("GYR3_CALTEMP", 51, AP_InertialSensor, caltemp_gyro[2], -300), #endif // @Param: TCAL_OPTIONS @@ -1482,7 +1482,7 @@ void AP_InertialSensor::_save_gyro_calibration() _gyro_offset[i].set_and_save(Vector3f()); _gyro_id[i].set_and_save(0); #if HAL_INS_TEMPERATURE_CAL_ENABLE - caltemp_gyro[i].set_and_save_ifchanged(-100); + caltemp_gyro[i].set_and_save_ifchanged(-300); #endif } } @@ -1968,7 +1968,7 @@ bool AP_InertialSensor::is_still() // return true if we are in a calibration bool AP_InertialSensor::calibrating() const { - return _calibrating_accel || _calibrating_gyro || (_acal && _acal->active()); + return _calibrating_accel || _calibrating_gyro || (_acal && _acal->running()); } /// calibrating - returns true if a temperature calibration is running @@ -2053,7 +2053,7 @@ void AP_InertialSensor::_acal_save_calibrations() _accel_offset[i].set_and_save(Vector3f()); _accel_scale[i].set_and_save(Vector3f()); #if HAL_INS_TEMPERATURE_CAL_ENABLE - caltemp_accel[i].set_and_save(-100); + caltemp_accel[i].set_and_save(-300); #endif } } @@ -2064,7 +2064,7 @@ void AP_InertialSensor::_acal_save_calibrations() _accel_offset[i].set_and_save(Vector3f()); _accel_scale[i].set_and_save(Vector3f()); #if HAL_INS_TEMPERATURE_CAL_ENABLE - caltemp_accel[i].set_and_save_ifchanged(-100); + caltemp_accel[i].set_and_save_ifchanged(-300); #endif } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index ff2ee0786f..8da87960d3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -101,7 +101,7 @@ void AP_InertialSensor_Backend::_rotate_and_correct_accel(uint8_t instance, Vect } #endif - if (!_imu._calibrating_accel && (_imu._acal == nullptr || !_imu._acal->active())) { + if (!_imu._calibrating_accel && (_imu._acal == nullptr || !_imu._acal->running())) { #if HAL_INS_TEMPERATURE_CAL_ENABLE // apply temperature corrections diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index 53051ad4cc..b8cc10802f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -378,7 +378,7 @@ void AP_InertialSensor::TCal::Learn::reset(float temperature) memset(state, 0, sizeof(state)); start_tmax = tcal.temp_max; accel_start.zero(); - for (uint8_t i=0; i<2; i++) { + for (uint8_t i=0; i