AP_InertialSensor: changes from review feedback

thanks Sid!
This commit is contained in:
Andrew Tridgell 2021-01-17 09:26:09 +11:00 committed by Peter Barker
parent 9561f24c0e
commit dc58b0b950
2 changed files with 19 additions and 18 deletions

View File

@ -570,56 +570,56 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
AP_SUBGROUPINFO(tcal[2], "TCAL3_", 45, AP_InertialSensor, AP_InertialSensor::TCal), AP_SUBGROUPINFO(tcal[2], "TCAL3_", 45, AP_InertialSensor, AP_InertialSensor::TCal),
#endif #endif
// @Param: ACC_CALTEMP1 // @Param: ACC1_CALTEMP
// @DisplayName: Calibration temperature for 1st accelerometer // @DisplayName: Calibration temperature for 1st accelerometer
// @Description: Temperature that the 1st accelerometer was calibrated at // @Description: Temperature that the 1st accelerometer was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("ACC_CALTEMP1", 46, AP_InertialSensor, caltemp_accel[0], -100), AP_GROUPINFO("ACC1_CALTEMP", 46, AP_InertialSensor, caltemp_accel[0], -100),
// @Param: GYR_CALTEMP1 // @Param: GYR1_CALTEMP
// @DisplayName: Calibration temperature for 1st gyroscope // @DisplayName: Calibration temperature for 1st gyroscope
// @Description: Temperature that the 1st gyroscope was calibrated at // @Description: Temperature that the 1st gyroscope was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("GYR_CALTEMP1", 47, AP_InertialSensor, caltemp_gyro[0], -100), AP_GROUPINFO("GYR1_CALTEMP", 47, AP_InertialSensor, caltemp_gyro[0], -100),
#if INS_MAX_INSTANCES > 1 #if INS_MAX_INSTANCES > 1
// @Param: ACC_CALTEMP2 // @Param: ACC2_CALTEMP
// @DisplayName: Calibration temperature for 2nd accelerometer // @DisplayName: Calibration temperature for 2nd accelerometer
// @Description: Temperature that the 2nd accelerometer was calibrated at // @Description: Temperature that the 2nd accelerometer was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("ACC_CALTEMP2", 48, AP_InertialSensor, caltemp_accel[1], -100), AP_GROUPINFO("ACC2_CALTEMP", 48, AP_InertialSensor, caltemp_accel[1], -100),
// @Param: GYR_CALTEMP2 // @Param: GYR2_CALTEMP
// @DisplayName: Calibration temperature for 2nd gyroscope // @DisplayName: Calibration temperature for 2nd gyroscope
// @Description: Temperature that the 2nd gyroscope was calibrated at // @Description: Temperature that the 2nd gyroscope was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("GYR_CALTEMP2", 49, AP_InertialSensor, caltemp_gyro[1], -100), AP_GROUPINFO("GYR2_CALTEMP", 49, AP_InertialSensor, caltemp_gyro[1], -100),
#endif #endif
#if INS_MAX_INSTANCES > 2 #if INS_MAX_INSTANCES > 2
// @Param: ACC_CALTEMP3 // @Param: ACC3_CALTEMP
// @DisplayName: Calibration temperature for 3rd accelerometer // @DisplayName: Calibration temperature for 3rd accelerometer
// @Description: Temperature that the 3rd accelerometer was calibrated at // @Description: Temperature that the 3rd accelerometer was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("ACC_CALTEMP3", 50, AP_InertialSensor, caltemp_accel[2], -100), AP_GROUPINFO("ACC3_CALTEMP", 50, AP_InertialSensor, caltemp_accel[2], -100),
// @Param: GYR_CALTEMP3 // @Param: GYR3_CALTEMP
// @DisplayName: Calibration temperature for 3rd gyroscope // @DisplayName: Calibration temperature for 3rd gyroscope
// @Description: Temperature that the 3rd gyroscope was calibrated at // @Description: Temperature that the 3rd gyroscope was calibrated at
// @User: Advanced // @User: Advanced
// @Units: degC // @Units: degC
// @Calibration: 1 // @Calibration: 1
AP_GROUPINFO("GYR_CALTEMP3", 51, AP_InertialSensor, caltemp_gyro[2], -100), AP_GROUPINFO("GYR3_CALTEMP", 51, AP_InertialSensor, caltemp_gyro[2], -100),
#endif #endif
// @Param: TCAL_OPTIONS // @Param: TCAL_OPTIONS

View File

@ -286,16 +286,17 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te
const float tmid = 0.5 * (tcal.temp_max + start_temp); const float tmid = 0.5 * (tcal.temp_max + start_temp);
const float tdiff = T - tmid; const float tdiff = T - tmid;
AP::logger().Write("TCLR", "TimeUS,I,Si,Temp,TDiff,X,Y,Z", AP::logger().Write("TCLR", "TimeUS,I,SType,Temp,TDiff,X,Y,Z,NSamp",
"s#------", "s#-------",
"F0000000", "F0000000-",
"QBBfffff", "QBBfffffI",
AP_HAL::micros64(), AP_HAL::micros64(),
instance(), instance(),
si, si,
T, T,
tdiff, tdiff,
st.sum.x, st.sum.y, st.sum.z); st.sum.x, st.sum.y, st.sum.z,
st.sum_count);
st.pfit[0].update(tdiff, st.sum.x); st.pfit[0].update(tdiff, st.sum.x);
@ -469,7 +470,7 @@ void AP_InertialSensor::get_persistent_params(ExpandingString &str) const
str.printf("INS_ACC%sSCAL_X=%f\n", id, ascl.x); str.printf("INS_ACC%sSCAL_X=%f\n", id, ascl.x);
str.printf("INS_ACC%sSCAL_Y=%f\n", id, ascl.y); str.printf("INS_ACC%sSCAL_Y=%f\n", id, ascl.y);
str.printf("INS_ACC%sSCAL_Z=%f\n", id, ascl.z); str.printf("INS_ACC%sSCAL_Z=%f\n", id, ascl.z);
str.printf("INS_ACC_CALTEMP%u=%.2f\n", imu, caltemp_accel[i].get()); str.printf("INS_ACC%u_CALTEMP=%.2f\n", imu, caltemp_accel[i].get());
} }
} }
if (uint32_t(tcal_options.get()) & uint32_t(TCalOptions::PERSIST_TEMP_CAL)) { if (uint32_t(tcal_options.get()) & uint32_t(TCalOptions::PERSIST_TEMP_CAL)) {