mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_HAL_Linux: RCOutput_Bebop: group writes
This allows to remove the hard limit of 4 motors in Bebop, allowing to execute the motor test.
This commit is contained in:
parent
24f41538cb
commit
0dad58ae8b
@ -319,14 +319,23 @@ void LinuxRCOutput_Bebop::write(uint8_t ch, uint16_t period_us)
|
|||||||
|
|
||||||
_request_period_us[ch] = period_us;
|
_request_period_us[ch] = period_us;
|
||||||
|
|
||||||
/* write command to motors only when all channels are set */
|
if (!_corking)
|
||||||
if (ch == (BEBOP_BLDC_MOTORS_NUM - 1)) {
|
push();
|
||||||
pthread_mutex_lock(&_mutex);
|
}
|
||||||
memcpy(_period_us, _request_period_us, sizeof(_period_us));
|
|
||||||
pthread_cond_signal(&_cond);
|
void LinuxRCOutput_Bebop::cork()
|
||||||
pthread_mutex_unlock(&_mutex);
|
{
|
||||||
memset(_request_period_us, 0 ,sizeof(_request_period_us));
|
_corking = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void LinuxRCOutput_Bebop::push()
|
||||||
|
{
|
||||||
|
_corking = false;
|
||||||
|
pthread_mutex_lock(&_mutex);
|
||||||
|
memcpy(_period_us, _request_period_us, sizeof(_period_us));
|
||||||
|
pthread_cond_signal(&_cond);
|
||||||
|
pthread_mutex_unlock(&_mutex);
|
||||||
|
memset(_request_period_us, 0 ,sizeof(_request_period_us));
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t LinuxRCOutput_Bebop::read(uint8_t ch)
|
uint16_t LinuxRCOutput_Bebop::read(uint8_t ch)
|
||||||
|
@ -61,6 +61,8 @@ public:
|
|||||||
void enable_ch(uint8_t ch);
|
void enable_ch(uint8_t ch);
|
||||||
void disable_ch(uint8_t ch);
|
void disable_ch(uint8_t ch);
|
||||||
void write(uint8_t ch, uint16_t period_us);
|
void write(uint8_t ch, uint16_t period_us);
|
||||||
|
void cork() override;
|
||||||
|
void push() override;
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
void read(uint16_t* period_us, uint8_t len);
|
void read(uint16_t* period_us, uint8_t len);
|
||||||
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm);
|
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm);
|
||||||
@ -75,6 +77,7 @@ private:
|
|||||||
uint16_t _min_pwm;
|
uint16_t _min_pwm;
|
||||||
uint16_t _max_pwm;
|
uint16_t _max_pwm;
|
||||||
uint8_t _state;
|
uint8_t _state;
|
||||||
|
bool _corking = false;
|
||||||
|
|
||||||
uint8_t _checksum(uint8_t *data, unsigned int len);
|
uint8_t _checksum(uint8_t *data, unsigned int len);
|
||||||
void _start_prop();
|
void _start_prop();
|
||||||
|
Loading…
Reference in New Issue
Block a user