18 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ 19 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \ 20 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE 24 #include <linux/limits.h> 29 #include <sys/types.h> 37 using namespace Linux;
44 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE 71 error = ((float)*
_target) - current;
83 }
else if (output < 0) {
HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns)
bool set_duty_cycle(uint32_t nsec_duty_cycle)
virtual void write(uint8_t pin, uint8_t value)=0
void set_period(uint32_t nsec_period)
virtual void pinMode(uint8_t pin, uint8_t output)=0
uint32_t _last_temp_update
#define error(fmt, args ...)
void set_imu_target_temp(int8_t *target) override
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void set_imu_temp(float current) override