32 : bebop_out(
std::move(dev))
40 printf(
"RCOutput_Disco: initialised\n");
46 if (chmask & (1U << i)) {
94 for (
int i = 0; i < len; i++) {
95 period_us[i] =
read(i);
int printf(const char *fmt,...)
uint16_t get_freq(uint8_t ch) override
const output_table_t output_table[7]
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
void write(uint8_t ch, uint16_t period_us) override
RCOutput_Disco(AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override
uint16_t read(uint8_t ch) override
void set_freq(uint32_t chmask, uint16_t freq_hz) override
void enable_ch(uint8_t ch) override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Common definitions and utility routines for the ArduPilot libraries.
void disable_ch(uint8_t ch) override