mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed start timer for temperature in SITL
when we are doing an autotest we want the temperature to start climbing when we first set SIM_IMUT_FIXED=0
This commit is contained in:
parent
30e55d8dfc
commit
d5b511f4a0
|
@ -50,8 +50,12 @@ float AP_InertialSensor_SITL::get_temperature(void)
|
|||
// user wants fixed temperature
|
||||
return sitl->imu_temp_fixed;
|
||||
}
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (temp_start_ms == 0) {
|
||||
temp_start_ms = now;
|
||||
}
|
||||
// follow a curve with given start, end and time constant
|
||||
const float tsec = AP_HAL::millis() * 0.001f;
|
||||
const float tsec = (AP_HAL::millis() - temp_start_ms) * 0.001f;
|
||||
const float T0 = sitl->imu_temp_start;
|
||||
const float T1 = sitl->imu_temp_end;
|
||||
const float tconst = sitl->imu_temp_tconst;
|
||||
|
|
|
@ -43,6 +43,7 @@ private:
|
|||
float accel_time;
|
||||
float gyro_motor_phase[12];
|
||||
float accel_motor_phase[12];
|
||||
uint32_t temp_start_ms;
|
||||
|
||||
static uint8_t bus_id;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue