HAL_Linux: removed ESC scaling, moved to AP_HAL

This commit is contained in:
Andrew Tridgell 2023-08-19 16:08:58 +10:00 committed by Peter Barker
parent 49f1e5d1db
commit 51af21f6d9
4 changed files with 0 additions and 14 deletions

View File

@ -427,12 +427,6 @@ void RCOutput_Bebop::read(uint16_t* period_us, uint8_t len)
}
}
void RCOutput_Bebop::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
{
_min_pwm = min_pwm;
_max_pwm = max_pwm;
}
/* Separate thread to handle the Bebop motors controller */
void* RCOutput_Bebop::_control_thread(void *arg) {
RCOutput_Bebop* rcout = (RCOutput_Bebop *) arg;

View File

@ -71,7 +71,6 @@ public:
void push() override;
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);
void play_note(uint8_t pwm, uint16_t period_us, uint16_t duration_ms);

View File

@ -107,10 +107,4 @@ void RCOutput_Disco::push(void)
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

@ -29,7 +29,6 @@ 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