From 4dfc9494efc597b11d9287f81a7338775b1f5027 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 28 Jan 2022 22:25:37 +1100 Subject: [PATCH] SITL: correct compilation if INS_TEMPERATURE_CAL_ENABLE is off --- libraries/SITL/SITL.cpp | 4 ++++ libraries/SITL/SITL.h | 2 ++ 2 files changed, 6 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index b7ee26a8e8..66b8f962a6 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -432,10 +432,12 @@ const AP_Param::GroupInfo SIM::var_sfml_joystick[] = { // INS SITL parameters const AP_Param::GroupInfo SIM::var_ins[] = { +#if HAL_INS_TEMPERATURE_CAL_ENABLE AP_GROUPINFO("IMUT_START", 1, SIM, imu_temp_start, 25), AP_GROUPINFO("IMUT_END", 2, SIM, imu_temp_end, 45), AP_GROUPINFO("IMUT_TCONST", 3, SIM, imu_temp_tconst, 300), AP_GROUPINFO("IMUT_FIXED", 4, SIM, imu_temp_fixed, 0), +#endif AP_GROUPINFO("ACC1_BIAS", 5, SIM, accel_bias[0], 0), #if INS_MAX_INSTANCES > 1 AP_GROUPINFO("ACC2_BIAS", 6, SIM, accel_bias[1], 0), @@ -493,6 +495,7 @@ const AP_Param::GroupInfo SIM::var_ins[] = { AP_GROUPINFO("JSON_MASTER", 27, SIM, ride_along_master, 0), // the IMUT parameters must be last due to the enable parameters +#if HAL_INS_TEMPERATURE_CAL_ENABLE AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 61, SIM, AP_InertialSensor::TCal), #if INS_MAX_INSTANCES > 1 AP_SUBGROUPINFO(imu_tcal[1], "IMUT2_", 62, SIM, AP_InertialSensor::TCal), @@ -500,6 +503,7 @@ const AP_Param::GroupInfo SIM::var_ins[] = { #if INS_MAX_INSTANCES > 2 AP_SUBGROUPINFO(imu_tcal[2], "IMUT3_", 63, SIM, AP_InertialSensor::TCal), #endif +#endif // HAL_INS_TEMPERATURE_CAL_ENABLE AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 950ab20830..ec210a99d3 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -451,12 +451,14 @@ public: float get_apparent_wind_dir() const{return state.wind_vane_apparent.direction;} float get_apparent_wind_spd() const{return state.wind_vane_apparent.speed;} +#if HAL_INS_TEMPERATURE_CAL_ENABLE // IMU temperature calibration params AP_Float imu_temp_start; AP_Float imu_temp_end; AP_Float imu_temp_tconst; AP_Float imu_temp_fixed; AP_InertialSensor::TCal imu_tcal[INS_MAX_INSTANCES]; +#endif // IMU control parameters AP_Float gyro_noise[INS_MAX_INSTANCES]; // in degrees/second