HAL_Linux: fixed set_esc_scaling on Disco

This commit is contained in:
Andrew Tridgell 2016-06-09 10:18:36 +10:00
parent 298f7bffb9
commit 55d692708b
3 changed files with 16 additions and 9 deletions

View File

@ -59,17 +59,17 @@ public:
return static_cast<RCOutput_Bebop*>(rcout);
}
void init();
void set_freq(uint32_t chmask, uint16_t freq_hz);
uint16_t get_freq(uint8_t ch);
void enable_ch(uint8_t ch);
void disable_ch(uint8_t ch);
void write(uint8_t ch, uint16_t period_us);
void init() override;
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us) override;
void cork() override;
void push() override;
uint16_t read(uint8_t ch);
void read(uint16_t* period_us, uint8_t len);
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm);
uint16_t read(uint8_t ch) override;
void read(uint16_t* period_us, uint8_t len) override;
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override;
int read_obs_data(BebopBLDC_ObsData &data);
private:

View File

@ -103,5 +103,11 @@ void RCOutput_Disco::push(void)
sysfs_out.push();
bebop_out.push();
}
void RCOutput_Disco::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
{
sysfs_out.set_esc_scaling(min_pwm, max_pwm);
bebop_out.set_esc_scaling(min_pwm, max_pwm);
}
}

View File

@ -27,6 +27,7 @@ public:
void read(uint16_t *period_us, uint8_t len) override;
void cork() override;
void push() override;
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override;
private:
// Disco RC output combines methods from Sysfs and Bebop