mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
HAL_ChibiOS: support oneshot mode
supports oneshot 125 and oneshot
This commit is contained in:
parent
38a36a070f
commit
880a84294e
@ -243,6 +243,9 @@ void RCOutput::push_local(void)
|
|||||||
}
|
}
|
||||||
uint16_t outmask = (1U<<num_channels)-1;
|
uint16_t outmask = (1U<<num_channels)-1;
|
||||||
outmask &= en_mask;
|
outmask &= en_mask;
|
||||||
|
|
||||||
|
uint16_t widest_pulse = 0;
|
||||||
|
uint8_t need_trigger = 0;
|
||||||
|
|
||||||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||||
for (uint8_t j = 0; j < 4; j++) {
|
for (uint8_t j = 0; j < 4; j++) {
|
||||||
@ -269,9 +272,37 @@ void RCOutput::push_local(void)
|
|||||||
uint32_t width = (pwm_group_list[i].pwm_cfg.frequency/1000000) * period_us;
|
uint32_t width = (pwm_group_list[i].pwm_cfg.frequency/1000000) * period_us;
|
||||||
pwmEnableChannel(pwm_group_list[i].pwm_drv, j, width);
|
pwmEnableChannel(pwm_group_list[i].pwm_drv, j, width);
|
||||||
}
|
}
|
||||||
|
if (period_us > widest_pulse) {
|
||||||
|
widest_pulse = period_us;
|
||||||
|
}
|
||||||
|
need_trigger |= (1U<<i);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (need_trigger && _output_mode == MODE_PWM_ONESHOT) {
|
||||||
|
uint64_t now = AP_HAL::micros64();
|
||||||
|
if (now < min_pulse_trigger_us) {
|
||||||
|
// guarantee minimum pulse separation
|
||||||
|
hal.scheduler->delay_microseconds(min_pulse_trigger_us - now);
|
||||||
|
}
|
||||||
|
osalSysLock();
|
||||||
|
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||||
|
if (need_trigger & (1U<<i)) {
|
||||||
|
// this triggers pulse output for a channel group
|
||||||
|
pwm_group_list[i].pwm_drv->tim->EGR = STM32_TIM_EGR_UG;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
osalSysUnlock();
|
||||||
|
if (widest_pulse > 2300) {
|
||||||
|
widest_pulse = 2300;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
calculate time that we are allowed to trigger next pulse
|
||||||
|
to guarantee at least a 50us gap between pulses
|
||||||
|
*/
|
||||||
|
min_pulse_trigger_us = AP_HAL::micros64() + widest_pulse + 50;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t RCOutput::read(uint8_t chan)
|
uint16_t RCOutput::read(uint8_t chan)
|
||||||
@ -336,6 +367,17 @@ void RCOutput::set_output_mode(enum output_mode mode)
|
|||||||
write(i, 0);
|
write(i, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (_output_mode == MODE_PWM_ONESHOT) {
|
||||||
|
// for oneshot we force 1Hz output and then trigger on each loop
|
||||||
|
for (uint8_t i=0; i< NUM_GROUPS; i++) {
|
||||||
|
pwmChangePeriod(pwm_group_list[i].pwm_drv, pwm_group_list[i].pwm_cfg.frequency);
|
||||||
|
}
|
||||||
|
#if HAL_WITH_IO_MCU
|
||||||
|
if (AP_BoardConfig::io_enabled()) {
|
||||||
|
return iomcu.set_oneshot_mode();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -89,6 +89,9 @@ private:
|
|||||||
// mask of channels that are running in high speed
|
// mask of channels that are running in high speed
|
||||||
uint16_t fast_channel_mask;
|
uint16_t fast_channel_mask;
|
||||||
|
|
||||||
|
// min time to trigger next pulse to prevent overlap
|
||||||
|
uint64_t min_pulse_trigger_us;
|
||||||
|
|
||||||
// push out values to local PWM
|
// push out values to local PWM
|
||||||
void push_local(void);
|
void push_local(void);
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user