|
|
|
@ -75,6 +75,14 @@ void AP_BoardConfig::set_imu_temp(float current)
@@ -75,6 +75,14 @@ void AP_BoardConfig::set_imu_temp(float current)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (now - heater.last_log_ms >= 1000) { |
|
|
|
|
// @LoggerMessage: HEAT
|
|
|
|
|
// @Description: IMU Heater data
|
|
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
|
// @Field: Temp: Current IMU temperature
|
|
|
|
|
// @Field: Targ: Target IMU temperature
|
|
|
|
|
// @Field: P: Proportional portion of response
|
|
|
|
|
// @Field: I: Integral portion of response
|
|
|
|
|
// @Field: Out: Controller output to heating element
|
|
|
|
|
AP::logger().Write("HEAT", "TimeUS,Temp,Targ,P,I,Out", "Qfbfff", |
|
|
|
|
AP_HAL::micros64(), |
|
|
|
|
avg, target, |
|
|
|
|