mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
HAL_Linux: fixed nested cork/push
don't generate extra pulse sets if we nest
This commit is contained in:
parent
2ba6e7af35
commit
9b297ef5a1
@ -132,6 +132,7 @@ void RCOutput_AeroIO::set_freq(uint32_t chmask, uint16_t freq_hz)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (!_corking) {
|
if (!_corking) {
|
||||||
|
_corking = true;
|
||||||
push();
|
push();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -150,6 +151,7 @@ void RCOutput_AeroIO::enable_ch(uint8_t ch)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_pending_duty_write_mask |= (1U << ch);
|
_pending_duty_write_mask |= (1U << ch);
|
||||||
|
_corking = true;
|
||||||
push();
|
push();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -160,6 +162,7 @@ void RCOutput_AeroIO::disable_ch(uint8_t ch)
|
|||||||
}
|
}
|
||||||
_duty_buffer[ch] = 0;
|
_duty_buffer[ch] = 0;
|
||||||
_pending_duty_write_mask |= (1U << ch);
|
_pending_duty_write_mask |= (1U << ch);
|
||||||
|
_corking = true;
|
||||||
push();
|
push();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -169,6 +172,7 @@ void RCOutput_AeroIO::write(uint8_t ch, uint16_t period_us)
|
|||||||
_duty_buffer[ch] = period_us;
|
_duty_buffer[ch] = period_us;
|
||||||
|
|
||||||
if (!_corking) {
|
if (!_corking) {
|
||||||
|
_corking = true;
|
||||||
push();
|
push();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -180,6 +184,9 @@ void RCOutput_AeroIO::cork()
|
|||||||
|
|
||||||
void RCOutput_AeroIO::push()
|
void RCOutput_AeroIO::push()
|
||||||
{
|
{
|
||||||
|
if (!_corking) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
_corking = false;
|
_corking = false;
|
||||||
|
|
||||||
for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
|
for (uint8_t i = 0; i < PWM_CHAN_COUNT; i++) {
|
||||||
|
@ -142,6 +142,9 @@ void RCOutput_AioPRU::cork(void)
|
|||||||
|
|
||||||
void RCOutput_AioPRU::push(void)
|
void RCOutput_AioPRU::push(void)
|
||||||
{
|
{
|
||||||
|
if (!corked) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
corked = false;
|
corked = false;
|
||||||
for (uint8_t i=0; i<PWM_CHAN_COUNT; i++) {
|
for (uint8_t i=0; i<PWM_CHAN_COUNT; i++) {
|
||||||
if (pending_mask & (1U<<i)) {
|
if (pending_mask & (1U<<i)) {
|
||||||
|
@ -418,6 +418,9 @@ void RCOutput_Bebop::cork()
|
|||||||
|
|
||||||
void RCOutput_Bebop::push()
|
void RCOutput_Bebop::push()
|
||||||
{
|
{
|
||||||
|
if (!_corking) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
_corking = false;
|
_corking = false;
|
||||||
pthread_mutex_lock(&_mutex);
|
pthread_mutex_lock(&_mutex);
|
||||||
memcpy(_period_us, _request_period_us, sizeof(_period_us));
|
memcpy(_period_us, _request_period_us, sizeof(_period_us));
|
||||||
|
@ -176,8 +176,10 @@ void RCOutput_PCA9685::write(uint8_t ch, uint16_t period_us)
|
|||||||
_pulses_buffer[ch] = period_us;
|
_pulses_buffer[ch] = period_us;
|
||||||
_pending_write_mask |= (1U << ch);
|
_pending_write_mask |= (1U << ch);
|
||||||
|
|
||||||
if (!_corking)
|
if (!_corking) {
|
||||||
|
_corking = true;
|
||||||
push();
|
push();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void RCOutput_PCA9685::cork()
|
void RCOutput_PCA9685::cork()
|
||||||
@ -187,6 +189,9 @@ void RCOutput_PCA9685::cork()
|
|||||||
|
|
||||||
void RCOutput_PCA9685::push()
|
void RCOutput_PCA9685::push()
|
||||||
{
|
{
|
||||||
|
if (!_corking) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
_corking = false;
|
_corking = false;
|
||||||
|
|
||||||
if (_pending_write_mask == 0)
|
if (_pending_write_mask == 0)
|
||||||
|
@ -99,6 +99,9 @@ void RCOutput_PRU::cork(void)
|
|||||||
|
|
||||||
void RCOutput_PRU::push(void)
|
void RCOutput_PRU::push(void)
|
||||||
{
|
{
|
||||||
|
if (!corked) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
corked = false;
|
corked = false;
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(pending); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(pending); i++) {
|
||||||
if (pending_mask & (1U << i)) {
|
if (pending_mask & (1U << i)) {
|
||||||
|
@ -136,6 +136,9 @@ void RCOutput_Sysfs::cork(void)
|
|||||||
|
|
||||||
void RCOutput_Sysfs::push(void)
|
void RCOutput_Sysfs::push(void)
|
||||||
{
|
{
|
||||||
|
if (!_corked) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
for (uint8_t i=0; i<_channel_count; i++) {
|
for (uint8_t i=0; i<_channel_count; i++) {
|
||||||
if ((1U<<i) & _pending_mask) {
|
if ((1U<<i) & _pending_mask) {
|
||||||
_pwm_channels[i]->set_duty_cycle(usec_to_nsec(_pending[i]));
|
_pwm_channels[i]->set_duty_cycle(usec_to_nsec(_pending[i]));
|
||||||
|
@ -119,6 +119,9 @@ void RCOutput_ZYNQ::cork(void)
|
|||||||
|
|
||||||
void RCOutput_ZYNQ::push(void)
|
void RCOutput_ZYNQ::push(void)
|
||||||
{
|
{
|
||||||
|
if (!corked) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
corked = false;
|
corked = false;
|
||||||
for (uint8_t i=0; i<MAX_ZYNQ_PWMS; i++) {
|
for (uint8_t i=0; i<MAX_ZYNQ_PWMS; i++) {
|
||||||
if (pending_mask & (1U << i)) {
|
if (pending_mask & (1U << i)) {
|
||||||
|
@ -180,8 +180,10 @@ void RCOutput_QFLIGHT::cork(void)
|
|||||||
|
|
||||||
void RCOutput_QFLIGHT::push(void)
|
void RCOutput_QFLIGHT::push(void)
|
||||||
{
|
{
|
||||||
corked = false;
|
if (corked) {
|
||||||
need_write = true;
|
corked = false;
|
||||||
|
need_write = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
||||||
|
Loading…
Reference in New Issue
Block a user