mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_PX4: limit IMU target temperature to 65
This commit is contained in:
parent
c0d21c5730
commit
aafd1512e4
@ -196,8 +196,12 @@ void PX4Util::set_imu_temp(float current)
|
||||
// experimentally tweaked for Pixhawk2
|
||||
const float kI = 0.3f;
|
||||
const float kP = 200.0f;
|
||||
float target = (float)(*_heater.target);
|
||||
|
||||
// limit to 65 degrees to prevent damage
|
||||
target = constrain_float(target, 0, 65);
|
||||
|
||||
float err = ((float)*_heater.target) - current;
|
||||
float err = target - current;
|
||||
|
||||
_heater.integrator += kI * err;
|
||||
_heater.integrator = constrain_float(_heater.integrator, 0, 70);
|
||||
|
Loading…
Reference in New Issue
Block a user