mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
SITL: correct compilation if INS_TEMPERATURE_CAL_ENABLE is off
This commit is contained in:
parent
558f6babc4
commit
4dfc9494ef
@ -432,10 +432,12 @@ const AP_Param::GroupInfo SIM::var_sfml_joystick[] = {
|
|||||||
|
|
||||||
// INS SITL parameters
|
// INS SITL parameters
|
||||||
const AP_Param::GroupInfo SIM::var_ins[] = {
|
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_START", 1, SIM, imu_temp_start, 25),
|
||||||
AP_GROUPINFO("IMUT_END", 2, SIM, imu_temp_end, 45),
|
AP_GROUPINFO("IMUT_END", 2, SIM, imu_temp_end, 45),
|
||||||
AP_GROUPINFO("IMUT_TCONST", 3, SIM, imu_temp_tconst, 300),
|
AP_GROUPINFO("IMUT_TCONST", 3, SIM, imu_temp_tconst, 300),
|
||||||
AP_GROUPINFO("IMUT_FIXED", 4, SIM, imu_temp_fixed, 0),
|
AP_GROUPINFO("IMUT_FIXED", 4, SIM, imu_temp_fixed, 0),
|
||||||
|
#endif
|
||||||
AP_GROUPINFO("ACC1_BIAS", 5, SIM, accel_bias[0], 0),
|
AP_GROUPINFO("ACC1_BIAS", 5, SIM, accel_bias[0], 0),
|
||||||
#if INS_MAX_INSTANCES > 1
|
#if INS_MAX_INSTANCES > 1
|
||||||
AP_GROUPINFO("ACC2_BIAS", 6, SIM, accel_bias[1], 0),
|
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),
|
AP_GROUPINFO("JSON_MASTER", 27, SIM, ride_along_master, 0),
|
||||||
|
|
||||||
// the IMUT parameters must be last due to the enable parameters
|
// 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),
|
AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 61, SIM, AP_InertialSensor::TCal),
|
||||||
#if INS_MAX_INSTANCES > 1
|
#if INS_MAX_INSTANCES > 1
|
||||||
AP_SUBGROUPINFO(imu_tcal[1], "IMUT2_", 62, SIM, AP_InertialSensor::TCal),
|
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
|
#if INS_MAX_INSTANCES > 2
|
||||||
AP_SUBGROUPINFO(imu_tcal[2], "IMUT3_", 63, SIM, AP_InertialSensor::TCal),
|
AP_SUBGROUPINFO(imu_tcal[2], "IMUT3_", 63, SIM, AP_InertialSensor::TCal),
|
||||||
#endif
|
#endif
|
||||||
|
#endif // HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -451,12 +451,14 @@ public:
|
|||||||
float get_apparent_wind_dir() const{return state.wind_vane_apparent.direction;}
|
float get_apparent_wind_dir() const{return state.wind_vane_apparent.direction;}
|
||||||
float get_apparent_wind_spd() const{return state.wind_vane_apparent.speed;}
|
float get_apparent_wind_spd() const{return state.wind_vane_apparent.speed;}
|
||||||
|
|
||||||
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||||
// IMU temperature calibration params
|
// IMU temperature calibration params
|
||||||
AP_Float imu_temp_start;
|
AP_Float imu_temp_start;
|
||||||
AP_Float imu_temp_end;
|
AP_Float imu_temp_end;
|
||||||
AP_Float imu_temp_tconst;
|
AP_Float imu_temp_tconst;
|
||||||
AP_Float imu_temp_fixed;
|
AP_Float imu_temp_fixed;
|
||||||
AP_InertialSensor::TCal imu_tcal[INS_MAX_INSTANCES];
|
AP_InertialSensor::TCal imu_tcal[INS_MAX_INSTANCES];
|
||||||
|
#endif
|
||||||
|
|
||||||
// IMU control parameters
|
// IMU control parameters
|
||||||
AP_Float gyro_noise[INS_MAX_INSTANCES]; // in degrees/second
|
AP_Float gyro_noise[INS_MAX_INSTANCES]; // in degrees/second
|
||||||
|
Loading…
Reference in New Issue
Block a user