28 extern AP_IOMCU iomcu;
    35 #if CH_CFG_USE_HEAP == TRUE    82 #endif // CH_CFG_USE_HEAP    89 #if HAL_USE_PWM == TRUE    98 #if HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER   105     heater.sum += current;
   109     if (now - heater.last_update_ms < 1000) {
   112     heater.last_update_ms = now;
   114     current = heater.sum / heater.count;
   119     const float kI = 0.3f;
   120     const float kP = 200.0f;
   121     float target = (float)(*heater.target);
   126     float err = target - current;
   128     heater.integrator += kI * err;
   135     iomcu.set_heater_duty_cycle(output);
   136 #endif // HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER   141 #if HAL_WITH_IO_MCU && HAL_HAVE_IMU_HEATER   142     heater.target = target;
   148 ToneAlarm Util::_toneAlarm;
   152     return _toneAlarm.init();
   157     _toneAlarm.set_tune(tone);
   168     } 
else if (
state == 1) {
   173     } 
else if (
state == 3) {
   177     if (_toneAlarm.is_tune_comp()) {
   182 #endif // HAL_PWM_ALARM void * malloc_ccm(size_t size)
virtual void _toneAlarm_timer_tick()
enum safety_state safety_switch_state(void) override
void * try_alloc_from_ccm_ram(size_t size)
void * malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
void * calloc(size_t nmemb, size_t size)
static bool io_enabled(void)
virtual void toneAlarm_set_tune(uint8_t tune)
size_t mem_available(void)
float constrain_float(const float amt, const float low, const float high)
void set_imu_target_temp(int8_t *target)
void set_imu_temp(float current)
void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
uint32_t available_memory() override
virtual bool toneAlarm_init()