23 #if HAL_USE_PWM == TRUE 31 extern AP_IOMCU iomcu;
34 #define RCOU_SERIAL_TIMING_DEBUG 0 36 struct RCOutput::pwm_group
RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
39 #define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list) 42 #define CHAN_DISABLED 255 56 for (uint8_t j = 0; j < 4; j++ ) {
58 if (chan >= pwm_count) {
84 #ifdef HAL_GPIO_PIN_SAFETY_IN 100 uint32_t old_clock = group.
pwm_cfg.frequency;
101 uint32_t old_period = group.
pwm_cfg.period;
107 group.
pwm_cfg.frequency = 8000000;
108 }
else if (freq_set <= 400) {
110 group.
pwm_cfg.frequency = 1000000;
117 PWMDriver *pwmp = group.
pwm_drv;
118 uint32_t psc = (pwmp->clock / pwmp->config->frequency) - 1;
119 while ((psc > 0xFFFF || ((psc + 1) * pwmp->config->frequency) != pwmp->clock) &&
120 group.
pwm_cfg.frequency > 1000000) {
122 psc = (pwmp->clock / pwmp->config->frequency) - 1;
133 bool force_reconfig =
false;
134 for (uint8_t j=0; j<4; j++) {
135 if (group.
pwm_cfg.channels[j].mode == PWM_OUTPUT_ACTIVE_LOW) {
136 group.
pwm_cfg.channels[j].mode = PWM_OUTPUT_ACTIVE_HIGH;
137 force_reconfig =
true;
139 if (group.
pwm_cfg.channels[j].mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW) {
140 group.
pwm_cfg.channels[j].mode = PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH;
141 force_reconfig =
true;
146 if (old_clock != group.
pwm_cfg.frequency ||
147 old_period != group.
pwm_cfg.period ||
166 uint8_t update_mask = 0;
174 iomcu.set_freq(chmask, freq_hz);
195 uint16_t group_freq = freq_hz;
199 if ((group.
ch_mask & chmask) != 0) {
204 if (group_freq > 50) {
208 if (chmask != update_mask) {
209 hal.
console->
printf(
"RCOutput: Failed to set PWM frequency req %x set %x\n", (
unsigned)chmask, (
unsigned)update_mask);
220 iomcu.set_default_rate(freq_hz);
243 return iomcu.get_freq(chan);
250 for (uint8_t j = 0; j < 4; j++) {
251 if (group.
chan[j] == chan) {
272 for (uint8_t j = 0; j < 4; j++) {
273 if ((group.
chan[j] == chan) && !(
en_mask & 1<<chan)) {
292 for (uint8_t j = 0; j < 4; j++) {
293 if (group.
chan[j] == chan) {
294 pwmDisableChannel(group.
pwm_drv, j);
311 uint16_t io_period_us = period_us;
317 iomcu.write_channel(chan, io_period_us);
352 uint16_t widest_pulse = 0;
353 uint8_t need_trigger = 0;
364 for (uint8_t j = 0; j < 4; j++) {
369 if (outmask & (1UL<<chan)) {
381 period_us = PWM_FRACTION_TO_WIDTH(group.
pwm_drv, 1, 1);
383 period_us = PWM_FRACTION_TO_WIDTH(group.
pwm_drv,\
386 pwmEnableChannel(group.
pwm_drv, j, period_us);
389 uint32_t width = ((group.
pwm_cfg.frequency/1000000U) * period_us) / 8U;
390 pwmEnableChannel(group.
pwm_drv, j, width);
392 uint32_t width = (group.
pwm_cfg.frequency/1000000U) * period_us;
393 pwmEnableChannel(group.
pwm_drv, j, width);
398 if (period_us > widest_pulse) {
399 widest_pulse = period_us;
405 need_trigger |= (1U<<i);
411 if (widest_pulse > 2300) {
430 return iomcu.read_channel(chan);
444 period_us[i] = iomcu.read_channel(i);
453 memcpy(period_us,
period, len*
sizeof(uint16_t));
469 for (uint8_t i=0; i<len; i++) {
527 uint32_t clock_hz = group.
pwm_drv->clock;
528 uint32_t target_frequency = bitrate * bit_width;
529 uint32_t prescaler = clock_hz / target_frequency;
530 while ((clock_hz / prescaler) * prescaler != clock_hz && prescaler <= 0x8000) {
533 uint32_t freq = clock_hz / prescaler;
534 if (prescaler > 0x8000) {
539 group.
pwm_cfg.frequency = freq;
540 group.
pwm_cfg.period = bit_width;
541 group.
pwm_cfg.dier = TIM_DIER_UDE;
543 group.
bit_width_mul = (freq + (target_frequency/2)) / target_frequency;
545 for (uint8_t j=0; j<4; j++) {
546 pwmmode_t mode = group.
pwm_cfg.channels[j].mode;
547 if (mode != PWM_OUTPUT_DISABLED) {
548 if(mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW || mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH) {
549 group.
pwm_cfg.channels[j].mode = active_high?PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH:PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW;
551 group.
pwm_cfg.channels[j].mode = active_high?PWM_OUTPUT_ACTIVE_HIGH:PWM_OUTPUT_ACTIVE_LOW;
559 for (uint8_t j=0; j<4; j++) {
561 pwmEnableChannel(group.
pwm_drv, j, 0);
583 for (uint8_t i=0; i<4; i++) {
595 const uint32_t bit_period = 19;
630 for (uint8_t j=0; j<4; j++) {
632 pwmEnableChannel(group.
pwm_drv, j, 0);
669 return iomcu.set_oneshot_mode();
708 return iomcu.enable_sbus_out(rate_hz);
739 group.
pwm_drv->tim->EGR = STM32_TIM_EGR_UG;
818 dmaStreamRelease(group.
dma);
828 uint16_t packet = (value << 1);
836 uint16_t csum_data = packet;
837 for (uint8_t i = 0; i < 3; i++) {
843 packet = (packet << 4) | csum;
853 const uint32_t DSHOT_MOTOR_BIT_0 = 7 * clockmul;
854 const uint32_t DSHOT_MOTOR_BIT_1 = 14 * clockmul;
855 for (uint16_t i = 0; i < 16; i++) {
856 buffer[i * stride] = (packet & 0x8000) ? DSHOT_MOTOR_BIT_1 : DSHOT_MOTOR_BIT_0;
883 for (uint8_t i=0; i<4; i++) {
899 uint16_t chan_mask = (1U<<
chan);
902 if (request_telemetry) {
934 dmaStreamSetPeripheral(group.
dma, &(group.
pwm_drv->tim->DMAR));
936 dmaStreamSetTransactionSize(group.
dma, buffer_length/
sizeof(uint32_t));
937 dmaStreamSetFIFO(group.
dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
938 dmaStreamSetMode(group.
dma,
940 STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD |
941 STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) |
942 STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE);
946 group.
pwm_drv->tim->DCR = 0x0D | STM32_TIM_DCR_DBL(3);
948 dmaStreamEnable(group.
dma);
957 dmaStreamDisable(group->
dma);
962 chSysUnlockFromISR();
990 if (group.
ch_mask & (1U<<chan)) {
995 new_serial_group = &group;
996 for (uint8_t j=0; j<4; j++) {
997 if (group.
chan[j] == chan) {
1005 if (!new_serial_group) {
1024 chThdSetPriority(HIGHPRIO);
1043 const uint32_t BIT_0 = bitval;
1044 const uint32_t BIT_1 = 0;
1050 buffer[9*stride] = BIT_1;
1053 for (uint8_t i = 0; i < 8; i++) {
1054 buffer[(1 + i) * stride] = (b & 1) ? BIT_1 : BIT_0;
1113 systime_t now = chVTGetSystemTimeX();
1114 uint8_t bit = palReadLine(
irq.
line);
1115 bool send_signal =
false;
1117 #if RCOU_SERIAL_TIMING_DEBUG 1118 palWriteLine(HAL_GPIO_LINE_GPIO55, bit);
1157 chSysUnlockFromISR();
1180 if ((byteval & 0x201) != 0x200) {
1185 b = uint8_t(byteval>>1);
1199 uint32_t gpio_mode = PAL_MODE_INPUT_PULLUP;
1200 uint32_t restore_mode = PAL_MODE_ALTERNATE(group.
alt_functions[group.
serial.
chan]) | PAL_STM32_OSPEED_MID2 | PAL_STM32_OTYPE_PUSHPULL;
1203 #if RCOU_SERIAL_TIMING_DEBUG 1209 palSetLineMode(line, gpio_mode);
1221 #if RCOU_SERIAL_TIMING_DEBUG 1222 palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
1226 #if RCOU_SERIAL_TIMING_DEBUG 1227 palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
1232 for (i=0; i<len; i++) {
1238 ((
GPIO *)hal.
gpio)->_attach_interrupt(line,
nullptr, 0);
1241 palSetLineMode(line, restore_mode);
1242 #if RCOU_SERIAL_TIMING_DEBUG 1243 palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
1278 return iomcu.get_safety_switch_state();
1291 return iomcu.force_safety_on();
1307 iomcu.force_safety_off();
1322 iomcu.set_safety_pwm(chmask, period_us);
1325 for (uint8_t i=0; i<16; i++) {
1326 if (chmask & (1U<<i)) {
1351 #ifdef HAL_GPIO_PIN_SAFETY_IN 1353 uint16_t safety_options = 0;
1357 bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);
1360 safety_pressed =
false;
1364 safety_pressed =
false;
1368 safety_pressed =
false;
1370 if (safety_pressed) {
1383 #elif HAL_WITH_IO_MCU 1388 #ifdef HAL_GPIO_PIN_LED_SAFETY 1391 palWriteLine(HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U <<
led_counter))?0:1);
1395 #endif // HAL_USE_PWM systime_t byte_start_tick
bool get_soft_armed() const
bool serial_setup_output(uint8_t chan, uint32_t baudrate) override
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
void set_freq_group(pwm_group &group)
AP_HAL::UARTDriver * console
bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high)
uint64_t last_dshot_send_us
bool enable_px4io_sbus_out(uint16_t rate_hz) override
uint16_t read_last_sent(uint8_t ch) override
static AP_BoardConfig * get_instance(void)
void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
uint16_t get_safety_mask(void) const
void force_safety_off(void) override
void set_output_mode(uint16_t mask, enum output_mode mode) override
void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
#define HAL_GPIO_INTERRUPT_BOTH
void timer_tick(void) override
void set_default_rate(uint16_t rate_hz) override
void serial_end(void) override
enum output_mode current_mode
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void set_freq(uint32_t chmask, uint16_t freq_hz)
uint16_t last_sent[max_channels]
static bool io_enabled(void)
uint16_t trigger_widest_pulse
static uint8_t get_pwm_count(void)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
bool serial_read_byte(uint8_t &b)
const uint16_t dshot_bit_length
uint64_t min_pulse_trigger_us
uint16_t io_fast_channel_mask
uint32_t safety_update_ms
virtual void printf(const char *,...) FMT_PRINTF(2
bool force_safety_on(void) override
uint16_t create_dshot_packet(const uint16_t value, bool telem_request)
uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override
void dma_allocate(Shared_DMA *ctx)
struct pwm_group * serial_group
static pwm_group pwm_group_list[]
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual enum safety_state safety_switch_state(void)
uint16_t safe_pwm[max_channels]
uint32_t dshot_pulse_time_us
void write(uint8_t ch, uint16_t period_us)
void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
static void serial_bit_irq(void)
void unlock_from_IRQ(void)
bool serial_write_bytes(const uint8_t *bytes, uint16_t len) override
static const eventmask_t serial_event_mask
virtual void * malloc_type(size_t size, Memory_Type mem_type)
uint8_t trigger_groupmask
AP_HAL::Util::safety_state _safety_switch_state(void)
void dma_deallocate(Shared_DMA *ctx)
AP_HAL::Util::safety_state safety_state
void set_group_mode(pwm_group &group)
bool serial_write_byte(uint8_t b)
virtual void delay_microseconds(uint16_t us)=0
bool mode_requires_dma(enum output_mode mode) const
void trigger_groups(void)
void enable_ch(uint8_t ch)
void disable_ch(uint8_t ch)
uint8_t active_fmu_channels
int8_t safety_button_counter
static struct ChibiOS::RCOutput::irq_state irq
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
uint16_t period[max_channels]
uint16_t get_freq(uint8_t ch)
void dshot_send(pwm_group &group, bool blocking)
static void dma_irq_callback(void *p, uint32_t flags)
const stm32_dma_stream_t * dma
uint16_t get_safety_button_options(void)
uint16_t telem_request_mask
static const uint8_t max_channels
AP_HAL::Scheduler * scheduler
const uint16_t dshot_buffer_length
struct ChibiOS::RCOutput::pwm_group::@40 serial
uint16_t fast_channel_mask
uint16_t read(uint8_t ch)