APM:Libraries
RCOutput.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include "RCOutput.h"
18 #include <AP_Math/AP_Math.h>
21 #include "GPIO.h"
22 
23 #if HAL_USE_PWM == TRUE
24 
25 using namespace ChibiOS;
26 
27 extern const AP_HAL::HAL& hal;
28 
29 #if HAL_WITH_IO_MCU
30 #include <AP_IOMCU/AP_IOMCU.h>
31 extern AP_IOMCU iomcu;
32 #endif
33 
34 #define RCOU_SERIAL_TIMING_DEBUG 0
35 
36 struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
37 struct RCOutput::irq_state RCOutput::irq;
38 
39 #define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list)
40 
41 // marker for a disabled channel
42 #define CHAN_DISABLED 255
43 
44 // #pragma GCC optimize("Og")
45 
46 /*
47  initialise RC output driver
48  */
50 {
51  uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
52  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
53  //Start Pwm groups
54  pwm_group &group = pwm_group_list[i];
56  for (uint8_t j = 0; j < 4; j++ ) {
57  uint8_t chan = group.chan[j];
58  if (chan >= pwm_count) {
59  group.chan[j] = CHAN_DISABLED;
60  }
61  if (group.chan[j] != CHAN_DISABLED) {
63  group.ch_mask |= (1U<<group.chan[j]);
64  }
65  }
66  if (group.ch_mask != 0) {
67  pwmStart(group.pwm_drv, &group.pwm_cfg);
68  group.pwm_started = true;
69  }
70  }
71 
72 #if HAL_WITH_IO_MCU
74  iomcu.init();
75  // with IOMCU the local (FMU) channels start at 8
76  chan_offset = 8;
77  }
78 #endif
79  chMtxObjectInit(&trigger_mutex);
80 
81  // setup default output rate of 50Hz
82  set_freq(0xFFFF, 50);
83 
84 #ifdef HAL_GPIO_PIN_SAFETY_IN
86 #endif
87 }
88 
89 /*
90  setup the output frequency for a group and start pwm output
91  */
93 {
94  if (mode_requires_dma(group.current_mode)) {
95  // speed setup in DMA handler
96  return;
97  }
98 
99  uint16_t freq_set = group.rc_frequency;
100  uint32_t old_clock = group.pwm_cfg.frequency;
101  uint32_t old_period = group.pwm_cfg.period;
102 
103  if (freq_set > 400 || group.current_mode == MODE_PWM_ONESHOT125) {
104  // use a 8MHz clock for higher frequencies or for
105  // oneshot125. Using 8MHz for oneshot125 results in the full
106  // 1000 steps for smooth output
107  group.pwm_cfg.frequency = 8000000;
108  } else if (freq_set <= 400) {
109  // use a 1MHz clock
110  group.pwm_cfg.frequency = 1000000;
111  }
112 
113  // check if the frequency is possible, and keep halving
114  // down to 1MHz until it is OK with the hardware timer we
115  // are using. If we don't do this we'll hit an assert in
116  // the ChibiOS PWM driver on some timers
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) {
121  group.pwm_cfg.frequency /= 2;
122  psc = (pwmp->clock / pwmp->config->frequency) - 1;
123  }
124 
125  if (group.current_mode == MODE_PWM_ONESHOT ||
127  // force a period of 0, meaning no pulses till we trigger
128  group.pwm_cfg.period = 0;
129  } else {
130  group.pwm_cfg.period = group.pwm_cfg.frequency/freq_set;
131  }
132 
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;
138  }
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;
142  }
143 
144  }
145 
146  if (old_clock != group.pwm_cfg.frequency ||
147  old_period != group.pwm_cfg.period ||
148  !group.pwm_started ||
149  force_reconfig) {
150  // we need to stop and start to setup the new clock
151  if (group.pwm_started) {
152  pwmStop(group.pwm_drv);
153  }
154  pwmStart(group.pwm_drv, &group.pwm_cfg);
155  group.pwm_started = true;
156  }
157  pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
158 }
159 
160 /*
161  set output frequency in HZ for a set of channels given by a mask
162  */
163 void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
164 {
165  //check if the request spans accross any of the channel groups
166  uint8_t update_mask = 0;
167 
168 #if HAL_WITH_IO_MCU
170  // change frequency on IOMCU
171  if (freq_hz > 50) {
172  io_fast_channel_mask = chmask;
173  }
174  iomcu.set_freq(chmask, freq_hz);
175  }
176 #endif
177 
178  // convert to a local (FMU) channel mask
179  chmask >>= chan_offset;
180  if (chmask == 0) {
181  return;
182  }
183 
184  /*
185  we enable the new frequency on all groups that have one
186  of the requested channels. This means we may enable high
187  speed on some channels that aren't requested, but that
188  is needed in order to fly a vehicle such a a hex
189  multicopter properly
190  */
191  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
192  // greater than 400 doesn't give enough room at higher periods for
193  // the down pulse. This still allows for high rate with oneshot and dshot.
194  pwm_group &group = pwm_group_list[i];
195  uint16_t group_freq = freq_hz;
196  if (group_freq > 400 && group.current_mode != MODE_PWM_BRUSHED) {
197  group_freq = 400;
198  }
199  if ((group.ch_mask & chmask) != 0) {
200  group.rc_frequency = group_freq;
201  set_freq_group(group);
202  update_mask |= group.ch_mask;
203  }
204  if (group_freq > 50) {
205  fast_channel_mask |= group.ch_mask;
206  }
207  }
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);
210  }
211 }
212 
213 /*
214  set default output rate
215  */
216 void RCOutput::set_default_rate(uint16_t freq_hz)
217 {
218 #if HAL_WITH_IO_MCU
220  iomcu.set_default_rate(freq_hz);
221  }
222 #endif
223  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
224  pwm_group &group = pwm_group_list[i];
225  if ((group.ch_mask & fast_channel_mask) || group.ch_mask == 0) {
226  // don't change fast channels
227  continue;
228  }
229  group.pwm_cfg.period = group.pwm_cfg.frequency/freq_hz;
230  if (group.pwm_started) {
231  pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
232  }
233  }
234 }
235 
236 uint16_t RCOutput::get_freq(uint8_t chan)
237 {
238  if (chan >= max_channels) {
239  return 0;
240  }
241 #if HAL_WITH_IO_MCU
242  if (chan < chan_offset) {
243  return iomcu.get_freq(chan);
244  }
245 #endif
246  chan -= chan_offset;
247 
248  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
249  pwm_group &group = pwm_group_list[i];
250  for (uint8_t j = 0; j < 4; j++) {
251  if (group.chan[j] == chan) {
252  return group.pwm_drv->config->frequency / group.pwm_drv->period;
253  }
254  }
255  }
256  // assume 50Hz default
257  return 50;
258 }
259 
261 {
262  if (chan >= max_channels) {
263  return;
264  }
265  if (chan < chan_offset) {
266  return;
267  }
268  chan -= chan_offset;
269 
270  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
271  pwm_group &group = pwm_group_list[i];
272  for (uint8_t j = 0; j < 4; j++) {
273  if ((group.chan[j] == chan) && !(en_mask & 1<<chan)) {
274  en_mask |= 1<<chan;
275  }
276  }
277  }
278 }
279 
281 {
282  if (chan >= max_channels) {
283  return;
284  }
285  if (chan < chan_offset) {
286  return;
287  }
288  chan -= chan_offset;
289 
290  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
291  pwm_group &group = pwm_group_list[i];
292  for (uint8_t j = 0; j < 4; j++) {
293  if (group.chan[j] == chan) {
294  pwmDisableChannel(group.pwm_drv, j);
295  en_mask &= ~(1<<chan);
296  }
297  }
298  }
299 }
300 
301 void RCOutput::write(uint8_t chan, uint16_t period_us)
302 {
303  if (chan >= max_channels) {
304  return;
305  }
306  last_sent[chan] = period_us;
307 
308 #if HAL_WITH_IO_MCU
309  // handle IO MCU channels
311  uint16_t io_period_us = period_us;
312  if (iomcu_oneshot125 && ((1U<<chan) & io_fast_channel_mask)) {
313  // the iomcu only has one oneshot setting, so we need to scale by a factor
314  // of 8 here for oneshot125
315  io_period_us /= 8;
316  }
317  iomcu.write_channel(chan, io_period_us);
318  }
319 #endif
320  if (chan < chan_offset) {
321  return;
322  }
323 
324  if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) {
325  // implement safety pwm value
326  period_us = safe_pwm[chan];
327  }
328 
329  chan -= chan_offset;
330 
331  period[chan] = period_us;
332 
333  if (chan < num_fmu_channels) {
335  if (!corked) {
336  push_local();
337  }
338  }
339 }
340 
341 /*
342  push values to local channels from period[] array
343  */
345 {
346  if (active_fmu_channels == 0) {
347  return;
348  }
349  uint16_t outmask = (1U<<active_fmu_channels)-1;
350  outmask &= en_mask;
351 
352  uint16_t widest_pulse = 0;
353  uint8_t need_trigger = 0;
354  bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
355 
356  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
357  pwm_group &group = pwm_group_list[i];
358  if (serial_group == &group) {
359  continue;
360  }
361  if (!group.pwm_started) {
362  continue;
363  }
364  for (uint8_t j = 0; j < 4; j++) {
365  uint8_t chan = group.chan[j];
366  if (chan == CHAN_DISABLED) {
367  continue;
368  }
369  if (outmask & (1UL<<chan)) {
370  uint32_t period_us = period[chan];
371 
372  if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
373  // safety is on, overwride pwm
374  period_us = safe_pwm[chan+chan_offset];
375  }
376 
377  if (group.current_mode == MODE_PWM_BRUSHED) {
378  if (period_us <= _esc_pwm_min) {
379  period_us = 0;
380  } else if (period_us >= _esc_pwm_max) {
381  period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv, 1, 1);
382  } else {
383  period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv,\
384  (_esc_pwm_max - _esc_pwm_min), (period_us - _esc_pwm_min));
385  }
386  pwmEnableChannel(group.pwm_drv, j, period_us);
387  } else if (group.current_mode == MODE_PWM_ONESHOT125) {
388  // this gives us a width in 125 ns increments, giving 1000 steps over the 125 to 250 range
389  uint32_t width = ((group.pwm_cfg.frequency/1000000U) * period_us) / 8U;
390  pwmEnableChannel(group.pwm_drv, j, width);
391  } else if (group.current_mode < MODE_PWM_DSHOT150) {
392  uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;
393  pwmEnableChannel(group.pwm_drv, j, width);
394  } else if (group.current_mode >= MODE_PWM_DSHOT150 && group.current_mode <= MODE_PWM_DSHOT1200) {
395  // set period_us to time for pulse output, to enable very fast rates
396  period_us = dshot_pulse_time_us;
397  }
398  if (period_us > widest_pulse) {
399  widest_pulse = period_us;
400  }
401  if (group.current_mode == MODE_PWM_ONESHOT ||
403  (group.current_mode >= MODE_PWM_DSHOT150 &&
404  group.current_mode <= MODE_PWM_DSHOT1200)) {
405  need_trigger |= (1U<<i);
406  }
407  }
408  }
409  }
410 
411  if (widest_pulse > 2300) {
412  widest_pulse = 2300;
413  }
414  trigger_widest_pulse = widest_pulse;
415 
416  trigger_groupmask = need_trigger;
417 
418  if (trigger_groupmask) {
419  trigger_groups();
420  }
421 }
422 
423 uint16_t RCOutput::read(uint8_t chan)
424 {
425  if (chan >= max_channels) {
426  return 0;
427  }
428 #if HAL_WITH_IO_MCU
429  if (chan < chan_offset) {
430  return iomcu.read_channel(chan);
431  }
432 #endif
433  chan -= chan_offset;
434  return period[chan];
435 }
436 
437 void RCOutput::read(uint16_t* period_us, uint8_t len)
438 {
439  if (len > max_channels) {
440  len = max_channels;
441  }
442 #if HAL_WITH_IO_MCU
443  for (uint8_t i=0; i<MIN(len, chan_offset); i++) {
444  period_us[i] = iomcu.read_channel(i);
445  }
446 #endif
447  if (len <= chan_offset) {
448  return;
449  }
450  len -= chan_offset;
451  period_us += chan_offset;
452 
453  memcpy(period_us, period, len*sizeof(uint16_t));
454 }
455 
457 {
458  if (chan >= max_channels) {
459  return 0;
460  }
461  return last_sent[chan];
462 }
463 
464 void RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
465 {
466  if (len > max_channels) {
467  len = max_channels;
468  }
469  for (uint8_t i=0; i<len; i++) {
470  period_us[i] = read_last_sent(i);
471  }
472 }
473 
474 /*
475  does an output mode require the use of the UP DMA channel?
476  */
478 {
479  switch (mode) {
480  case MODE_PWM_DSHOT150:
481  case MODE_PWM_DSHOT300:
482  case MODE_PWM_DSHOT600:
483  case MODE_PWM_DSHOT1200:
484  return true;
485  default:
486  break;
487  }
488  return false;
489 }
490 
491 /*
492  setup a group for DMA output at a given bitrate. The bit_width is
493  the value for a pulse width in the DMA buffer for a full bit.
494 
495  This is used for both DShot and serial output
496  */
497 bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high)
498 {
499  if (!group.dma_buffer) {
501  if (!group.dma_buffer) {
502  return false;
503  }
504  }
505  // for dshot we setup for DMAR based output
506  if (!group.dma) {
507  group.dma = STM32_DMA_STREAM(group.dma_up_stream_id);
511  if (!group.dma_handle) {
512  return false;
513  }
514  }
515 
516  // hold the lock during setup, to ensure there isn't a DMA operation ongoing
517  group.dma_handle->lock();
518 
519  // configure timer driver for DMAR at requested rate
520  if (group.pwm_started) {
521  pwmStop(group.pwm_drv);
522  group.pwm_started = false;
523  }
524 
525  // adjust frequency to give an allowed value given the
526  // clock. There is probably a better way to do this
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) {
531  prescaler++;
532  }
533  uint32_t freq = clock_hz / prescaler;
534  if (prescaler > 0x8000) {
535  group.dma_handle->unlock();
536  return false;
537  }
538 
539  group.pwm_cfg.frequency = freq;
540  group.pwm_cfg.period = bit_width;
541  group.pwm_cfg.dier = TIM_DIER_UDE;
542  group.pwm_cfg.cr2 = 0;
543  group.bit_width_mul = (freq + (target_frequency/2)) / target_frequency;
544 
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;
550  } else {
551  group.pwm_cfg.channels[j].mode = active_high?PWM_OUTPUT_ACTIVE_HIGH:PWM_OUTPUT_ACTIVE_LOW;
552  }
553  }
554  }
555 
556  pwmStart(group.pwm_drv, &group.pwm_cfg);
557  group.pwm_started = true;
558 
559  for (uint8_t j=0; j<4; j++) {
560  if (group.chan[j] != CHAN_DISABLED) {
561  pwmEnableChannel(group.pwm_drv, j, 0);
562  }
563  }
564  group.dma_handle->unlock();
565  return true;
566 }
567 
568 
569 /*
570  setup output mode for a group, using group.current_mode. Used to restore output
571  after serial operations
572  */
574 {
575  if (group.pwm_started) {
576  pwmStop(group.pwm_drv);
577  group.pwm_started = false;
578  }
579 
580  switch (group.current_mode) {
581  case MODE_PWM_BRUSHED:
582  // force zero output initially
583  for (uint8_t i=0; i<4; i++) {
584  if (group.chan[i] == CHAN_DISABLED) {
585  continue;
586  }
587  uint8_t chan = chan_offset + group.chan[i];
588  write(chan, 0);
589  }
590  break;
591 
593  const uint16_t rates[(1 + MODE_PWM_DSHOT1200) - MODE_PWM_DSHOT150] = { 150, 300, 600, 1200 };
594  uint32_t rate = rates[uint8_t(group.current_mode - MODE_PWM_DSHOT150)] * 1000UL;
595  const uint32_t bit_period = 19;
596 
597  // configure timer driver for DMAR at requested rate
598  if (!setup_group_DMA(group, rate, bit_period, true)) {
599  group.current_mode = MODE_PWM_NONE;
600  break;
601  }
602 
603  // calculate min time between pulses
604  dshot_pulse_time_us = 1000000UL * dshot_bit_length / rate;
605  break;
606  }
607 
608  case MODE_PWM_ONESHOT:
609  case MODE_PWM_ONESHOT125:
610  // for oneshot we set a period of 0, which results in no pulses till we trigger
611  group.pwm_cfg.period = 0;
612  group.rc_frequency = 1;
613  if (group.pwm_started) {
614  pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
615  }
616  break;
617 
618  case MODE_PWM_NORMAL:
619  case MODE_PWM_NONE:
620  // nothing needed
621  break;
622  }
623 
624  set_freq_group(group);
625 
626  if (group.current_mode != MODE_PWM_NONE &&
627  !group.pwm_started) {
628  pwmStart(group.pwm_drv, &group.pwm_cfg);
629  group.pwm_started = true;
630  for (uint8_t j=0; j<4; j++) {
631  if (group.chan[j] != CHAN_DISABLED) {
632  pwmEnableChannel(group.pwm_drv, j, 0);
633  }
634  }
635  }
636 }
637 
638 /*
639  setup output mode
640  */
641 void RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
642 {
643  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
644  pwm_group &group = pwm_group_list[i];
645  if (((group.ch_mask << chan_offset) & mask) == 0) {
646  // this group is not affected
647  continue;
648  }
649  if (mode_requires_dma(mode) && !group.have_up_dma) {
650  mode = MODE_PWM_NONE;
651  }
652  if (mode > MODE_PWM_NORMAL) {
653  fast_channel_mask |= group.ch_mask;
654  }
655  if (group.current_mode != mode) {
656  group.current_mode = mode;
657  set_group_mode(group);
658  }
659  }
660 #if HAL_WITH_IO_MCU
661  if ((mode == MODE_PWM_ONESHOT ||
662  mode == MODE_PWM_ONESHOT125) &&
663  (mask & ((1U<<chan_offset)-1)) &&
666  // also setup IO to use a 1Hz frequency, so we only get output
667  // when we trigger
668  iomcu.set_freq(io_fast_channel_mask, 1);
669  return iomcu.set_oneshot_mode();
670  }
671 #endif
672 }
673 
674 /*
675  start corking output
676  */
677 void RCOutput::cork(void)
678 {
679  corked = true;
680 #if HAL_WITH_IO_MCU
682  iomcu.cork();
683  }
684 #endif
685 }
686 
687 /*
688  stop corking output
689  */
690 void RCOutput::push(void)
691 {
692  corked = false;
693  push_local();
694 #if HAL_WITH_IO_MCU
696  iomcu.push();
697  }
698 #endif
699 }
700 
701 /*
702  enable sbus output
703  */
704 bool RCOutput::enable_px4io_sbus_out(uint16_t rate_hz)
705 {
706 #if HAL_WITH_IO_MCU
708  return iomcu.enable_sbus_out(rate_hz);
709  }
710 #endif
711  return false;
712 }
713 
714 /*
715  trigger output groups for oneshot or dshot modes
716  */
718 {
719  if (!chMtxTryLock(&trigger_mutex)) {
720  return;
721  }
722  uint64_t now = AP_HAL::micros64();
723  if (now < min_pulse_trigger_us) {
724  // guarantee minimum pulse separation
726  }
727 
728  osalSysLock();
729  for (uint8_t i = 0; i < NUM_GROUPS; i++) {
730  pwm_group &group = pwm_group_list[i];
731  if (irq.waiter) {
732  // doing serial output, don't send pulses
733  continue;
734  }
735  if (group.current_mode == MODE_PWM_ONESHOT ||
737  if (trigger_groupmask & (1U<<i)) {
738  // this triggers pulse output for a channel group
739  group.pwm_drv->tim->EGR = STM32_TIM_EGR_UG;
740  }
741  }
742  }
743  osalSysUnlock();
744 
745  for (uint8_t i = 0; i < NUM_GROUPS; i++) {
746  pwm_group &group = pwm_group_list[i];
747  if (serial_group == &group) {
748  continue;
749  }
751  dshot_send(group, false);
752  }
753  }
754 
755  /*
756  calculate time that we are allowed to trigger next pulse
757  to guarantee at least a 50us gap between pulses
758  */
760 
761  chMtxUnlock(&trigger_mutex);
762 }
763 
764 /*
765  periodic timer. This is used for oneshot and dshot modes, plus for
766  safety switch update
767  */
769 {
770  safety_update();
771 
772  uint64_t now = AP_HAL::micros64();
773  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
774  pwm_group &group = pwm_group_list[i];
775  if (serial_group != &group &&
776  group.current_mode >= MODE_PWM_DSHOT150 &&
777  group.current_mode <= MODE_PWM_DSHOT1200 &&
778  now - group.last_dshot_send_us > 900) {
779  // do a blocking send now, to guarantee DShot sends at
780  // above 1000 Hz. This makes the protocol more reliable on
781  // long cables, and also keeps some ESCs happy that don't
782  // like low rates
783  dshot_send(group, true);
784  }
785  }
786  if (min_pulse_trigger_us == 0 ||
787  serial_group != nullptr) {
788  return;
789  }
790  if (now > min_pulse_trigger_us &&
791  now - min_pulse_trigger_us > 4000) {
792  // trigger at a minimum of 250Hz
793  trigger_groups();
794  }
795 }
796 
797 /*
798  allocate DMA channel
799  */
801 {
802  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
803  pwm_group &group = pwm_group_list[i];
804  if (group.dma_handle == ctx) {
805  dmaStreamAllocate(group.dma, 10, dma_irq_callback, &group);
806  }
807  }
808 }
809 
810 /*
811  deallocate DMA channel
812  */
814 {
815  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
816  pwm_group &group = pwm_group_list[i];
817  if (group.dma_handle == ctx) {
818  dmaStreamRelease(group.dma);
819  }
820  }
821 }
822 
823 /*
824  create a DSHOT 16 bit packet. Based on prepareDshotPacket from betaflight
825  */
826 uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request)
827 {
828  uint16_t packet = (value << 1);
829 
830  if (telem_request) {
831  packet |= 1;
832  }
833 
834  // compute checksum
835  uint16_t csum = 0;
836  uint16_t csum_data = packet;
837  for (uint8_t i = 0; i < 3; i++) {
838  csum ^= csum_data;
839  csum_data >>= 4;
840  }
841  csum &= 0xf;
842  // append checksum
843  packet = (packet << 4) | csum;
844 
845  return packet;
846 }
847 
848 /*
849  fill in a DMA buffer for dshot
850  */
851 void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
852 {
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;
857  packet <<= 1;
858  }
859 }
860 
861 /*
862  send a set of DShot packets for a channel group
863  This call be called in blocking mode from the timer, in which case it waits for the DMA lock.
864  In normal operation it doesn't wait for the DMA lock.
865  */
866 void RCOutput::dshot_send(pwm_group &group, bool blocking)
867 {
868  if (irq.waiter) {
869  // doing serial output, don't send DShot pulses
870  return;
871  }
872 
873  if (blocking) {
874  group.dma_handle->lock();
875  } else {
876  if (!group.dma_handle->lock_nonblock()) {
877  return;
878  }
879  }
880 
881  bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
882 
883  for (uint8_t i=0; i<4; i++) {
884  uint8_t chan = group.chan[i];
885  if (chan != CHAN_DISABLED) {
886  uint16_t pwm = period[chan];
887 
888  if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
889  // safety is on, overwride pwm
890  pwm = safe_pwm[chan+chan_offset];
891  }
892 
894  uint16_t value = 2000UL * uint32_t(pwm - _esc_pwm_min) / uint32_t(_esc_pwm_max - _esc_pwm_min);
895  if (value != 0) {
896  // dshot values are from 48 to 2047. Zero means off.
897  value += 47;
898  }
899  uint16_t chan_mask = (1U<<chan);
900  bool request_telemetry = (telem_request_mask & chan_mask)?true:false;
901  uint16_t packet = create_dshot_packet(value, request_telemetry);
902  if (request_telemetry) {
903  telem_request_mask &= ~chan_mask;
904  }
905  fill_DMA_buffer_dshot(group.dma_buffer + i, 4, packet, group.bit_width_mul);
906  }
907  }
908 
909  // start sending the pulses out
911 
913 }
914 
915 /*
916  send a series of pulses for a group using DMAR. Pulses must have
917  been encoded into the group dma_buffer with interleaving for the 4
918  channels in the group
919  */
920 void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
921 {
922  /*
923  The DMA approach we are using is based on the DMAR method from
924  betaflight. We use the TIMn_UP DMA channel for the timer, and
925  setup an interleaved set of pulse durations, with a stride of 4
926  (for the 4 channels). We use the DMAR register to point the DMA
927  engine at the 4 CCR registers of the timer, so it fills in the
928  pulse widths for each timer in turn. This means we only use a
929  single DMA channel for groups of 4 timer channels. See the "DMA
930  address for full transfer TIMx_DMAR" section of the
931  datasheet. Many thanks to the betaflight developers for coming
932  up with this great method.
933  */
934  dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
935  dmaStreamSetMemory0(group.dma, group.dma_buffer);
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,
939  STM32_DMA_CR_CHSEL(group.dma_up_channel) |
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);
943 
944  // setup for 4 burst strided transfers. 0x0D is the register
945  // address offset of the CCR registers in the timer peripheral
946  group.pwm_drv->tim->DCR = 0x0D | STM32_TIM_DCR_DBL(3);
947 
948  dmaStreamEnable(group.dma);
949 }
950 
951 /*
952  DMA interrupt handler. Used to mark DMA completed for DShot
953  */
954 void RCOutput::dma_irq_callback(void *p, uint32_t flags)
955 {
956  pwm_group *group = (pwm_group *)p;
957  dmaStreamDisable(group->dma);
958  if (group->in_serial_dma && irq.waiter) {
959  // tell the waiting process we've done the DMA
960  chSysLockFromISR();
961  chEvtSignalI(irq.waiter, serial_event_mask);
962  chSysUnlockFromISR();
963  } else {
964  group->dma_handle->unlock_from_IRQ();
965  }
966 }
967 
968 /*
969  setup for serial output to an ESC using the given
970  baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
971  databits. This is used for passthrough ESC configuration and
972  firmware flashing
973 
974  While serial output is active normal output to the channel group is
975  suspended.
976 */
977 bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate)
978 {
979  // account for IOMCU channels
980  chan -= chan_offset;
981  pwm_group *new_serial_group = nullptr;
982 
983  // find the channel group
984  for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
985  pwm_group &group = pwm_group_list[i];
986  if (group.current_mode == MODE_PWM_BRUSHED) {
987  // can't do serial output with brushed motors
988  continue;
989  }
990  if (group.ch_mask & (1U<<chan)) {
991  if (serial_group && serial_group != &group) {
992  // we're changing to a new group, end the previous output
993  serial_end();
994  }
995  new_serial_group = &group;
996  for (uint8_t j=0; j<4; j++) {
997  if (group.chan[j] == chan) {
998  group.serial.chan = j;
999  }
1000  }
1001  break;
1002  }
1003  }
1004 
1005  if (!new_serial_group) {
1006  if (serial_group) {
1007  // shutdown old group
1008  serial_end();
1009  }
1010  return false;
1011  }
1012 
1013  // setup the group for serial output. We ask for a bit width of 1, which gets modified by the
1014  if (!setup_group_DMA(*new_serial_group, baudrate, 10, false)) {
1015  return false;
1016  }
1017 
1018  serial_group = new_serial_group;
1019 
1020  // run the thread doing serial IO at highest priority. This is needed to ensure we don't
1021  // lose bytes when we switch between output and input
1022  serial_thread = chThdGetSelfX();
1023  serial_priority = chThdGetSelfX()->realprio;
1024  chThdSetPriority(HIGHPRIO);
1025 
1026  // remember the bit period for serial_read_byte()
1027  serial_group->serial.bit_time_us = 1000000UL / baudrate;
1028 
1029  // remember the thread that set things up. This is also used to
1030  // mark the group as doing serial output, so normal output is
1031  // suspended
1032  irq.waiter = chThdGetSelfX();
1033 
1034  return true;
1035 }
1036 
1037 
1038 /*
1039  fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit
1040  */
1041 void RCOutput::fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
1042 {
1043  const uint32_t BIT_0 = bitval;
1044  const uint32_t BIT_1 = 0;
1045 
1046  // start bit
1047  buffer[0] = BIT_0;
1048 
1049  // stop bit
1050  buffer[9*stride] = BIT_1;
1051 
1052  // 8 data bits
1053  for (uint8_t i = 0; i < 8; i++) {
1054  buffer[(1 + i) * stride] = (b & 1) ? BIT_1 : BIT_0;
1055  b >>= 1;
1056  }
1057 }
1058 
1059 
1060 /*
1061  send one serial byte, blocking call, should be called with the DMA lock held
1062 */
1064 {
1065  chEvtGetAndClearEvents(serial_event_mask);
1066 
1068 
1069  serial_group->in_serial_dma = true;
1070 
1071  // start sending the pulses out
1072  send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t));
1073 
1074  // wait for the event
1075  eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, MS2ST(2));
1076 
1077  serial_group->in_serial_dma = false;
1078 
1079  return (mask & serial_event_mask) != 0;
1080 }
1081 
1082 /*
1083  send a set of serial bytes, blocking call
1084 */
1085 bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
1086 {
1087  if (!serial_group) {
1088  return false;
1089  }
1092  while (len--) {
1093  if (!serial_write_byte(*bytes++)) {
1095  return false;
1096  }
1097  }
1098 
1099  // add a small delay for last word of output to have completely
1100  // finished
1101  hal.scheduler->delay_microseconds(25);
1102 
1104  return true;
1105 }
1106 
1107 /*
1108  irq handler for bit transition in serial_read_byte()
1109  This implements a one byte soft serial reader
1110  */
1112 {
1113  systime_t now = chVTGetSystemTimeX();
1114  uint8_t bit = palReadLine(irq.line);
1115  bool send_signal = false;
1116 
1117 #if RCOU_SERIAL_TIMING_DEBUG
1118  palWriteLine(HAL_GPIO_LINE_GPIO55, bit);
1119 #endif
1120 
1121  if (irq.nbits == 0 || bit == irq.last_bit) {
1122  // start of byte, should be low
1123  if (bit != 0) {
1124  irq.byteval = 0x200;
1125  send_signal = true;
1126  } else {
1127  irq.nbits = 1;
1128  irq.byte_start_tick = now;
1129  irq.bitmask = 0;
1130  }
1131  } else {
1132  systime_t dt = now - irq.byte_start_tick;
1133  uint8_t bitnum = (dt+(irq.bit_time_tick/2)) / irq.bit_time_tick;
1134 
1135  if (bitnum > 10) {
1136  bitnum = 10;
1137  }
1138  if (!bit) {
1139  // set the bits that we've processed
1140  irq.bitmask |= ((1U<<bitnum)-1) & ~((1U<<irq.nbits)-1);
1141  }
1142  irq.nbits = bitnum;
1143 
1144  if (irq.nbits == 10) {
1145  send_signal = true;
1146  irq.byteval = irq.bitmask & 0x3FF;
1147  irq.bitmask = 0;
1148  irq.nbits = 1;
1149  irq.byte_start_tick = now;
1150  }
1151  }
1152  irq.last_bit = bit;
1153 
1154  if (send_signal) {
1155  chSysLockFromISR();
1156  chEvtSignalI(irq.waiter, serial_event_mask);
1157  chSysUnlockFromISR();
1158  }
1159 }
1160 
1161 
1162 /*
1163  read a byte from a port, using serial parameters from serial_setup_output()
1164 */
1166 {
1167  bool timed_out = ((chEvtWaitAnyTimeout(serial_event_mask, MS2ST(10)) & serial_event_mask) == 0);
1168 
1169  uint16_t byteval = irq.byteval;
1170 
1171  if (timed_out) {
1172  // we can accept a byte with a timeout if the last bit was 1
1173  // and the start bit is set correctly
1174  if (irq.last_bit == 0) {
1175  return false;
1176  }
1177  byteval = irq.bitmask | 0x200;
1178  }
1179 
1180  if ((byteval & 0x201) != 0x200) {
1181  // wrong start/stop bits
1182  return false;
1183  }
1184 
1185  b = uint8_t(byteval>>1);
1186  return true;
1187 }
1188 
1189 /*
1190  read a byte from a port, using serial parameters from serial_setup_output()
1191 */
1192 uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
1193 {
1194  if (serial_group == nullptr) {
1195  return 0;
1196  }
1197  pwm_group &group = *serial_group;
1198  const ioline_t line = group.pal_lines[group.serial.chan];
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;
1201  uint16_t i = 0;
1202 
1203 #if RCOU_SERIAL_TIMING_DEBUG
1204  hal.gpio->pinMode(54, 1);
1205  hal.gpio->pinMode(55, 1);
1206 #endif
1207 
1208  // assume GPIO mappings for PWM outputs start at 50
1209  palSetLineMode(line, gpio_mode);
1210 
1211  chEvtGetAndClearEvents(serial_event_mask);
1212 
1213  irq.line = group.pal_lines[group.serial.chan];
1214  irq.nbits = 0;
1215  irq.bitmask = 0;
1216  irq.byteval = 0;
1218  irq.last_bit = 0;
1219  irq.waiter = chThdGetSelfX();
1220 
1221 #if RCOU_SERIAL_TIMING_DEBUG
1222  palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
1223 #endif
1224 
1225  if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, HAL_GPIO_INTERRUPT_BOTH)) {
1226 #if RCOU_SERIAL_TIMING_DEBUG
1227  palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
1228 #endif
1229  return false;
1230  }
1231 
1232  for (i=0; i<len; i++) {
1233  if (!serial_read_byte(buf[i])) {
1234  break;
1235  }
1236  }
1237 
1238  ((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0);
1239  irq.waiter = nullptr;
1240 
1241  palSetLineMode(line, restore_mode);
1242 #if RCOU_SERIAL_TIMING_DEBUG
1243  palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
1244 #endif
1245  return i;
1246 }
1247 
1248 /*
1249  end serial output
1250 */
1252 {
1253  if (serial_group) {
1254  pwm_group &group = *serial_group;
1255  // restore normal output
1256  if (group.pwm_started) {
1257  pwmStop(group.pwm_drv);
1258  group.pwm_started = false;
1259  }
1260  set_group_mode(group);
1261  set_freq_group(group);
1262  irq.waiter = nullptr;
1263  if (serial_thread == chThdGetSelfX()) {
1264  chThdSetPriority(serial_priority);
1265  serial_thread = nullptr;
1266  }
1267  }
1268  serial_group = nullptr;
1269 }
1270 
1271 /*
1272  get safety switch state for Util.cpp
1273  */
1275 {
1276 #if HAL_WITH_IO_MCU
1278  return iomcu.get_safety_switch_state();
1279  }
1280 #endif
1281  return safety_state;
1282 }
1283 
1284 /*
1285  force the safety switch on, disabling PWM output from the IO board
1286 */
1288 {
1289 #if HAL_WITH_IO_MCU
1291  return iomcu.force_safety_on();
1292  }
1293  return false;
1294 #else
1296  return true;
1297 #endif
1298 }
1299 
1300 /*
1301  force the safety switch off, enabling PWM output from the IO board
1302 */
1304 {
1305 #if HAL_WITH_IO_MCU
1307  iomcu.force_safety_off();
1308  }
1309 #else
1311 #endif
1312 }
1313 
1314 /*
1315  set PWM to send to a set of channels when the safety switch is
1316  in the safe state
1317 */
1318 void RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
1319 {
1320 #if HAL_WITH_IO_MCU
1322  iomcu.set_safety_pwm(chmask, period_us);
1323  }
1324 #endif
1325  for (uint8_t i=0; i<16; i++) {
1326  if (chmask & (1U<<i)) {
1327  safe_pwm[i] = period_us;
1328  }
1329  }
1330 }
1331 
1332 /*
1333  update safety state
1334  */
1336 {
1337  uint32_t now = AP_HAL::millis();
1338  if (now - safety_update_ms < 100) {
1339  // update safety at 10Hz
1340  return;
1341  }
1342  safety_update_ms = now;
1343 
1345 
1346  if (boardconfig) {
1347  // remember mask of channels to allow with safety on
1348  safety_mask = boardconfig->get_safety_mask();
1349  }
1350 
1351 #ifdef HAL_GPIO_PIN_SAFETY_IN
1352  // handle safety button
1353  uint16_t safety_options = 0;
1354  if (boardconfig) {
1355  safety_options = boardconfig->get_safety_button_options();
1356  }
1357  bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);
1359  hal.util->get_soft_armed()) {
1360  safety_pressed = false;
1361  }
1364  safety_pressed = false;
1365  }
1368  safety_pressed = false;
1369  }
1370  if (safety_pressed) {
1372  } else {
1374  }
1375  if (safety_button_counter == 10) {
1376  // safety has been pressed for 1 second, change state
1379  } else {
1381  }
1382  }
1383 #elif HAL_WITH_IO_MCU
1385  iomcu.set_safety_mask(safety_mask);
1386 #endif
1387 
1388 #ifdef HAL_GPIO_PIN_LED_SAFETY
1389  led_counter = (led_counter+1) % 16;
1390  const uint16_t led_pattern = safety_state==AP_HAL::Util::SAFETY_DISARMED?0x5500:0xFFFF;
1391  palWriteLine(HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1);
1392 #endif
1393 }
1394 
1395 #endif // HAL_USE_PWM
bool get_soft_armed() const
Definition: Util.h:15
bool serial_setup_output(uint8_t chan, uint32_t baudrate) override
Definition: RCOutput.cpp:977
uint16_t _esc_pwm_min
Definition: RCOutput.h:211
void push_local(void)
Definition: RCOutput.cpp:344
void safety_update(void)
Definition: RCOutput.cpp:1335
thread_t * serial_thread
Definition: RCOutput.h:207
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
uint16_t _esc_pwm_max
Definition: RCOutput.h:212
void set_freq_group(pwm_group &group)
Definition: RCOutput.cpp:92
tprio_t serial_priority
Definition: RCOutput.h:208
AP_HAL::UARTDriver * console
Definition: HAL.h:110
bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high)
Definition: RCOutput.cpp:497
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:704
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:456
static AP_BoardConfig * get_instance(void)
void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
Definition: RCOutput.cpp:1041
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
uint16_t get_safety_mask(void) const
void force_safety_off(void) override
Definition: RCOutput.cpp:1303
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:641
AP_HAL::Util * util
Definition: HAL.h:115
void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
Definition: RCOutput.cpp:920
#define HAL_GPIO_INTERRUPT_BOTH
Definition: GPIO.h:14
void timer_tick(void) override
Definition: RCOutput.cpp:768
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:216
void serial_end(void) override
Definition: RCOutput.cpp:1251
enum output_mode current_mode
Definition: RCOutput.h:149
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCOutput.cpp:10
static uint16_t pwm
Definition: RCOutput.cpp:20
void set_freq(uint32_t chmask, uint16_t freq_hz)
Definition: RCOutput.cpp:163
uint16_t last_sent[max_channels]
Definition: RCOutput.h:226
#define MIN(a, b)
Definition: usb_conf.h:215
static bool io_enabled(void)
uint16_t trigger_widest_pulse
Definition: RCOutput.h:247
static uint8_t get_pwm_count(void)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
uint16_t safety_mask
Definition: RCOutput.h:268
bool serial_read_byte(uint8_t &b)
Definition: RCOutput.cpp:1165
const uint16_t dshot_bit_length
Definition: RCOutput.h:277
uint64_t min_pulse_trigger_us
Definition: RCOutput.h:238
void push(void) override
Definition: RCOutput.cpp:690
uint16_t io_fast_channel_mask
Definition: RCOutput.h:235
uint8_t chan_offset
Definition: RCOutput.h:215
uint32_t safety_update_ms
Definition: RCOutput.h:263
void cork(void) override
Definition: RCOutput.cpp:677
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool force_safety_on(void) override
Definition: RCOutput.cpp:1287
uint16_t create_dshot_packet(const uint16_t value, bool telem_request)
Definition: RCOutput.cpp:826
uint8_t led_counter
Definition: RCOutput.h:264
uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override
Definition: RCOutput.cpp:1192
void dma_allocate(Shared_DMA *ctx)
Definition: RCOutput.cpp:800
uint32_t millis()
Definition: system.cpp:157
struct pwm_group * serial_group
Definition: RCOutput.h:206
#define SHARED_DMA_NONE
Definition: shared_dma.h:24
static pwm_group pwm_group_list[]
Definition: RCOutput.h:210
uint64_t micros64()
Definition: system.cpp:162
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
uint16_t safe_pwm[max_channels]
Definition: RCOutput.h:231
uint32_t dshot_pulse_time_us
Definition: RCOutput.h:279
void write(uint8_t ch, uint16_t period_us)
Definition: RCOutput.cpp:301
uint8_t num_fmu_channels
Definition: RCOutput.h:218
void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
Definition: RCOutput.cpp:851
bool lock_nonblock(void)
Definition: shared_dma.cpp:104
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:1318
safety_state
Definition: Util.h:35
static void serial_bit_irq(void)
Definition: RCOutput.cpp:1111
void unlock_from_IRQ(void)
Definition: shared_dma.cpp:164
mutex_t trigger_mutex
Definition: RCOutput.h:241
bool serial_write_bytes(const uint8_t *bytes, uint16_t len) override
Definition: RCOutput.cpp:1085
static const eventmask_t serial_event_mask
Definition: RCOutput.h:294
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
uint8_t trigger_groupmask
Definition: RCOutput.h:244
bool iomcu_oneshot125
Definition: RCOutput.h:250
uint32_t en_mask
Definition: RCOutput.h:229
AP_HAL::Util::safety_state _safety_switch_state(void)
Definition: RCOutput.cpp:1274
void dma_deallocate(Shared_DMA *ctx)
Definition: RCOutput.cpp:813
AP_HAL::Util::safety_state safety_state
Definition: RCOutput.h:262
AP_HAL::GPIO * gpio
Definition: HAL.h:111
void set_group_mode(pwm_group &group)
Definition: RCOutput.cpp:573
bool serial_write_byte(uint8_t b)
Definition: RCOutput.cpp:1063
virtual void delay_microseconds(uint16_t us)=0
#define NUM_GROUPS
Definition: RCOutput.cpp:39
bool mode_requires_dma(enum output_mode mode) const
Definition: RCOutput.cpp:477
void trigger_groups(void)
Definition: RCOutput.cpp:717
void enable_ch(uint8_t ch)
Definition: RCOutput.cpp:260
float value
void disable_ch(uint8_t ch)
Definition: RCOutput.cpp:280
uint8_t active_fmu_channels
Definition: RCOutput.h:221
int8_t safety_button_counter
Definition: RCOutput.h:265
static struct ChibiOS::RCOutput::irq_state irq
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
uint16_t period[max_channels]
Definition: RCOutput.h:230
uint16_t get_freq(uint8_t ch)
Definition: RCOutput.cpp:236
void dshot_send(pwm_group &group, bool blocking)
Definition: RCOutput.cpp:866
static void dma_irq_callback(void *p, uint32_t flags)
Definition: RCOutput.cpp:954
const stm32_dma_stream_t * dma
Definition: RCOutput.h:152
uint16_t get_safety_button_options(void)
#define CHAN_DISABLED
Definition: RCOutput.cpp:42
uint16_t telem_request_mask
Definition: RCOutput.h:280
static const uint8_t max_channels
Definition: RCOutput.h:223
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
const uint16_t dshot_buffer_length
Definition: RCOutput.h:278
struct ChibiOS::RCOutput::pwm_group::@40 serial
uint16_t fast_channel_mask
Definition: RCOutput.h:234
uint16_t read(uint8_t ch)
Definition: RCOutput.cpp:423