mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_InertialSensor_MPU6000: Add heat support
Send current tempertaure to the Heater so the control loop sets the correct temperature to the imu
This commit is contained in:
parent
f231182cd9
commit
b37c52f7a3
@ -679,6 +679,8 @@ bool AP_InertialSensor_MPU6000::update( void )
|
||||
_publish_accel(_accel_instance, accel);
|
||||
_publish_gyro(_gyro_instance, gyro);
|
||||
_publish_temperature(_accel_instance, temp);
|
||||
/* give the temperature to the control loop in order to keep it constant*/
|
||||
hal.util->set_imu_temp(temp);
|
||||
|
||||
#if MPU6000_FAST_SAMPLING
|
||||
if (_last_accel_filter_hz != _accel_filter_cutoff()) {
|
||||
|
Loading…
Reference in New Issue
Block a user