APM:Libraries
RCOutput.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 
6 
7 #pragma GCC optimize ("O2")
8 
9 #include "AP_HAL_F4Light.h"
10 #include "RCOutput.h"
12 #include <4way/serial_4way.h>
13 
14 #include "GPIO.h"
15 
16 using namespace F4Light;
17 
18 
19 // only one!
20 //#define DEBUG_PWM 5 // motor 6
21 //#define DEBUG_INT 5
22 
23 
24 #define F4Light_OUT_CHANNELS 6 // motor's channels enabled by default
25 
26 
27 #ifndef SERVO_PIN_5
28  #define SERVO_PIN_5 ((uint8_t)-1)
29 #endif
30 
31 #ifndef SERVO_PIN_6
32  #define SERVO_PIN_6 ((uint8_t)-1)
33 #endif
34 
35 #ifndef SERVO_PIN_7
36  #define SERVO_PIN_7 ((uint8_t)-1)
37 #endif
38 
39 #ifndef SERVO_PIN_8
40  #define SERVO_PIN_8 ((uint8_t)-1)
41 #endif
42 
43 #ifndef SERVO_PIN_9
44  #define SERVO_PIN_9 ((uint8_t)-1)
45 #endif
46 
47 #ifndef SERVO_PIN_10
48  #define SERVO_PIN_10 ((uint8_t)-1)
49 #endif
50 
51 #ifndef SERVO_PIN_11
52  #define SERVO_PIN_11 ((uint8_t)-1)
53 #endif
54 
55 
56 
57 // #if FRAME_CONFIG == QUAD_FRAME // this is only QUAD layouts
58 
59 // ArduCopter
60 static const uint8_t output_channels_arducopter[]= { // pin assignment
61  SERVO_PIN_1, //Timer3/3 - 1
62  SERVO_PIN_2, //Timer3/4 - 2
63  SERVO_PIN_3, //Timer2/3 - 3
64  SERVO_PIN_4, //Timer2/2 - 4
65  SERVO_PIN_5,
67 
68  // servo channels on input port
69  SERVO_PIN_7, // PB15 CH2_IN - PPM2
70  SERVO_PIN_8, // PC6 CH3_IN UART6
71  SERVO_PIN_9, // PC7 CH4_IN UART6
72  SERVO_PIN_10, // PC8 CH5_IN i2c
73  SERVO_PIN_11, // PC9 CH6_IN i2c
74 };
75 
76 
77 // mimics foreign layouts
78 
79 // OpenPilot
80 static const uint8_t output_channels_openpilot[]= { // pin assignment
81  SERVO_PIN_2, //Timer3/4 - 2
82  SERVO_PIN_4, //Timer2/2 - 4
83  SERVO_PIN_1, //Timer3/3 - 1
84  SERVO_PIN_3, //Timer2/3 - 3
85  SERVO_PIN_5, //Timer2/1
86  SERVO_PIN_6, //Timer2/0
87 
88  // servo channels on input port
89  SERVO_PIN_7, // PB15 CH2_IN - PPM2
90  SERVO_PIN_8, // PC6 CH3_IN UART6
91  SERVO_PIN_9, // PC7 CH4_IN UART6
92  SERVO_PIN_10, // PC8 CH5_IN i2c
93  SERVO_PIN_11, // PC9 CH6_IN i2c
94 };
95 
96 
97 // Cleanflight
98 static const uint8_t output_channels_cleanflight[]= { // pin assignment
99  SERVO_PIN_2, //Timer3/4 - 2
100  SERVO_PIN_3, //Timer2/3 - 3
101  SERVO_PIN_4, //Timer2/2 - 4
102  SERVO_PIN_1, //Timer3/3 - 1
103  SERVO_PIN_5, //Timer2/1
104  SERVO_PIN_6, //Timer2/0
105 
106  // servo channels on input port
107  SERVO_PIN_7, // PB15 CH2_IN - PPM2
108  SERVO_PIN_8, // PC6 CH3_IN UART6
109  SERVO_PIN_9, // PC7 CH4_IN UART6
110  SERVO_PIN_10, // PC8 CH5_IN i2c
111  SERVO_PIN_11, // PC9 CH6_IN i2c
112 };
113 
114 // Arducopter, shifted 2 pins right to use up to 2 servos
115 static const uint8_t output_channels_servo[]= { // pin assignment
116  SERVO_PIN_3, //Timer2/3 - 1
117  SERVO_PIN_4, //Timer2/2 - 2
118  SERVO_PIN_5, //Timer2/1 - 3
119  SERVO_PIN_6, //Timer2/0 - 4
120  SERVO_PIN_1, //Timer3/3 servo1
121  SERVO_PIN_2, //Timer3/4 servo2
122 
123  // servo channels on input port
124  SERVO_PIN_7, // PB15 CH2_IN - PPM2
125  SERVO_PIN_8, // PC6 CH3_IN UART6
126  SERVO_PIN_9, // PC7 CH4_IN UART6
127  SERVO_PIN_10, // PC8 CH5_IN i2c
128  SERVO_PIN_11, // PC9 CH6_IN i2c
129 };
130 
131 
132 
133 static const uint8_t * const revo_motor_map[]={
138 };
139 
140 
141 // #endif
142 
143 static const uint8_t *output_channels = output_channels_openpilot; // current pin assignment
144 
146 bool RCOutput::_once_mode = false;
147 
151 uint16_t RCOutput::_enabled_channels=0;
153 bool RCOutput::_corked=0;
154 uint8_t RCOutput::_used_channels=0;
155 
156 uint8_t RCOutput::_servo_mask=0;
157 
160 
161 uint8_t RCOutput::_pwm_type=0;
162 
165 
166 
167 #define PWM_TIMER_KHZ 2000 // 1000 in cleanflight
168 #define ONESHOT125_TIMER_KHZ 8000 // 8000 in cleanflight
169 #define ONESHOT42_TIMER_KHZ 28000 // 24000 in cleanflight
170 #define PWM_BRUSHED_TIMER_KHZ 16000 // 8000 in cleanflight
171 
172 #define _BV(bit) (1U << (bit))
173 
175 {
176  memset(&_period[0], 0, sizeof(_period));
177  memset(&_initialized[0], 0, sizeof(_initialized));
178 
179  _used_channels=0;
180 
181 }
182 
183 
186  esc4wayProcess(uart);
187 }
188 
189 
190 void RCOutput::lateInit(){ // 2nd stage with loaded parameters
191 
192  uint8_t map = hal_param_helper->_motor_layout;
193  _servo_mask = hal_param_helper->_servo_mask;
194  _pwm_type = hal_param_helper->_pwm_type;
195 
196  if(map >= ARRAY_SIZE(revo_motor_map)) return; // don't initialize if parameter is wrong
198 
199  InitPWM();
200 }
201 
203 {
204  for(uint8_t i = 0; i < F4Light_MAX_OUTPUT_CHANNELS; i++) {
205  _freq[i] = 50;
206  }
207  fill_timers();
208  _set_output_mode(MODE_PWM_NORMAL); // init timers
209 }
210 
211 
212 
213 // not from _freq to take channel dependency
214 uint16_t RCOutput::get_freq(uint8_t ch) {
215  if(ch >= F4Light_MAX_OUTPUT_CHANNELS) return 0;
216 
218 
219  /* transform to period by inverse of _time_period(icr) */
220  return (uint16_t)(dev->state->freq / timer_get_reload(dev));
221 }
222 
223 // fill array of used timers
225  memset(out_timers, 0, sizeof(out_timers)); // clear it first
226  num_out_timers=0;
227 
228  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
229  if (!(_enabled_channels & _BV(ch))) continue; // not enabled
230 
231  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
232 
233  bool add=true;
234  for(uint8_t i =0; i<num_out_timers;i++){
235  if(out_timers[i]==tim){
236  add=false;
237  break;
238  }
239  }
240  if(add) out_timers[num_out_timers++] = tim;
241  }
242 }
243 
244 
246 
247  uint32_t period=0;
248  uint32_t freq;
249 
250  _once_mode=false;
251 
252 
253  switch(_pwm_type) {
254  case 0:
255  default:
256  switch(mode){
257  case MODE_PWM_NORMAL:
259  break;
260 
261  case MODE_PWM_BRUSHED:
263  break;
264 
265  default:
266  case MODE_PWM_ONESHOT:
268  break;
269  }
270  break;
271 
272  case 1:
274  break;
275 
276  case 2:
278  break;
279 
280  case 3:
282  break;
283 
284  case 4:
286  break;
287  }
288 
289 // TODO: remove hardwiring timers
290 // TODO: we should change mode only for channels with freq > 50Hz
291 
292  switch(_mode){
293 
294  case BOARD_PWM_NORMAL:
295  default:
296 // output uses timers 2 & 3 so let init them for PWM mode
297  period = ((PWM_TIMER_KHZ*1000UL) / 50); // 50Hz by default - will be corrected late per-channel in init_channel()
298  freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
299  break;
300 
301  case BOARD_PWM_ONESHOT: // same as PWM but with manual restarting
302 // output uses timers 2 & 3 so let init them for PWM mode
303  period = (uint32_t)-1; // max possible
304  freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
305  _once_mode=true;
306  break;
307 
309  period = (uint32_t)-1; // max possible
310  freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
311 // at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
312  _once_mode=true;
313  break;
314 
315  case BOARD_PWM_PWM125: // like Oneshot125 but PWM so not once
316  period = (uint32_t)-1; // max possible
317  freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
318 // at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
319  break;
320 
321  case BOARD_PWM_ONESHOT42:
322  period = (uint32_t)-1; // max possible
323  freq = ONESHOT42_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
324 // at 28Mhz, period with 65536 will be 427Hz so even 16-bit timer should not overflows at 500Hz loop, but very close to
325  _once_mode=true;
326  break;
327 
328  case BOARD_PWM_BRUSHED:
329  // dev period freq, kHz
330  period = 1000;
331  freq = PWM_BRUSHED_TIMER_KHZ; // 16MHz - 0..1 in 1000 steps
332  break;
333  }
334 
335 
336 #if 1
337 // correct code should init all timers used for outputs
338 
339  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
340  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
341  tim->state->update=false; // reset flag first
342  }
343 
344  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
345  if (!(_enabled_channels & _BV(ch))) continue; // not enabled
346 
347  if(_freq[ch]>50){
348  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
349  tim->state->update=true; // set flag for update for needed timer
350  }
351  }
352 
353  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
354  uint8_t pin = output_channels[ch];
355 
356  const timer_dev *tim = PIN_MAP[pin].timer_device;
357  if(tim->state->update) {
358  configTimeBase(tim, period, freq);
359  tim->state->update = false; // only once
360  if(_mode == BOARD_PWM_BRUSHED) tim->state->freq_scale=1;
361  }
362  }
363 
364 #else // raw and dirty way
365 
366  // dev period freq, kHz
367  configTimeBase(TIMER2, period, freq); // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
368  configTimeBase(TIMER3, period, freq); // 16MHz 62.5ns ticks
369 
370  if(_mode == BOARD_PWM_BRUSHED) {
371  TIMER2->state->freq_scale=1;
372  TIMER3->state->freq_scale=1;
373  }
374 
375 #endif
376 
377  init_channels();
378 
379 #if 1
380  for(uint8_t i =0; i<num_out_timers;i++){
382  }
383 #else
386 #endif
387 }
388 
390 
391  uint32_t period=0;
392  uint32_t freq;
393 
394  switch(_mode){
395 
396  case BOARD_PWM_NORMAL:
397  default:
398 // output uses timers 2 & 3 so let init them for PWM mode
399  period = ((PWM_TIMER_KHZ*1000UL) / 50); // 50Hz by default - will be corrected late per-channel in init_channel()
400  freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
401  break;
402 
403  case BOARD_PWM_ONESHOT: // same as PWM but with manual restarting
404 // output uses timers 2 & 3 so let init them for PWM mode
405  period = (uint32_t)-1; // max possible
406  freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
407  break;
408 
410  period = (uint32_t)-1; // max possible
411  freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
412 // at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
413  break;
414 
415  case BOARD_PWM_PWM125: // like Oneshot125 but PWM so not once
416  period = (uint32_t)-1; // max possible
417  freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
418 // at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
419  break;
420 
421  case BOARD_PWM_ONESHOT42:
422  period = (uint32_t)-1; // max possible
423  freq = ONESHOT42_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
424 // at 28Mhz, period with 65536 will be 427Hz so even 16-bit timer should not overflows at 500Hz loop, but very close to
425  break;
426 
427  case BOARD_PWM_BRUSHED:
428  // dev period freq, kHz
429  period = 1000;
430  freq = PWM_BRUSHED_TIMER_KHZ; // 16MHz - 0..1 in 1000 steps
431  break;
432  }
433 
434 
435  uint8_t pin = output_channels[ch];
436 
437  const timer_dev *tim = PIN_MAP[pin].timer_device;
438  configTimeBase(tim, period, freq);
439  if(_mode == BOARD_PWM_BRUSHED) tim->state->freq_scale=1;
440 }
441 
442 
443 
444 
445 bool RCOutput::is_servo_enabled(uint8_t ch){
446  if(ch>=F4Light_OUT_CHANNELS){ // servos
447  uint8_t sn = ch - F4Light_OUT_CHANNELS;
448  if(!(_servo_mask & (1<<sn)) ) return false;
449  }
450 
451  return true;
452 }
453 
454 // for Oneshot125
455 // [1000;2000] => [125;250]
456 // so frequency of timers should be 8 times more - 16MHz, but timers on 84MHz can give only 16.8MHz
457 
458 // channels 1&2, 3&4&5&6 can has a different rates
459 void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {
460  uint32_t mask=1;
461 
462  uint16_t freq = freq_hz;
463 
464  for(uint8_t i=0; i< F4Light_MAX_OUTPUT_CHANNELS; i++) { // кто последний тот и папа
465  if(chmask & mask) {
466  if(!(_enabled_channels & mask) ) return; // not enabled
467 
468 // for true one-shot if(_once_mode && freq_hz>50) continue; // no frequency in OneShoot modes
469  _freq[i] = freq_hz;
470 
471  if(_once_mode && freq_hz>50) freq = freq_hz / 2; // divide frequency by 2 in OneShoot modes
472  const uint8_t pin = output_channels[i];
474  timer_set_reload(dev, _timer_period(freq, dev));
475  }
476  mask <<= 1;
477  }
478 }
479 
480 void RCOutput::init_channel(uint8_t ch){
481  if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
482 
483  uint8_t pin = output_channels[ch];
484  if (pin >= BOARD_NR_GPIO_PINS) return;
485 
486  const stm32_pin_info &p = PIN_MAP[pin];
487  const timer_dev *dev = p.timer_device;
488 
490 
491  uint16_t freq = _freq[ch];
492  if(_once_mode && freq>50) freq/=2;
493  timer_set_reload(dev, _timer_period(freq, dev));
494  if(_once_mode) {
495  timer_set_compare(dev, p.timer_channel, 0); // to prevent outputs in case of timer overflow
496  }
497 }
498 
499 
501  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
502  init_channel(ch);
503  }
504 }
505 
506 /* constrain pwm to be between min and max pulsewidth */
507 static inline uint16_t constrain_period(uint16_t p) {
510  return p;
511 }
512 
513 void RCOutput::set_pwm(uint8_t ch, uint16_t pwm){
514 
515  if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
516 
517  if (!(_enabled_channels & _BV(ch))) return; // not enabled
518 
519  if(!is_servo_enabled(ch)) return; // disabled servo
520 
521  uint8_t pin = output_channels[ch];
522  if (pin >= BOARD_NR_GPIO_PINS) return;
523 
524  switch(_mode){
525  case BOARD_PWM_BRUSHED:
526  pwm -= 1000; // move from 1000..2000 to 0..1000
527  break;
528 
529  case BOARD_PWM_ONESHOT42: // works at single freq
531  break;
532 
533  default:
534  pwm <<= 1; // frequency of timers 2MHz
535  break;
536  }
537 
538  const stm32_pin_info &p = PIN_MAP[pin];
539  const timer_dev *dev = p.timer_device;
540 
541  pwm *= dev->state->freq_scale; // take into account the inaccuracy of setting the timer frequency for small prescalers
542  timer_set_compare(dev, p.timer_channel, pwm);
543 }
544 
545 void RCOutput::write(uint8_t ch, uint16_t period_us)
546 {
547  if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
548 
549  if(_used_channels<ch) _used_channels=ch+1;
550 
551  uint16_t pwm = constrain_period(period_us);
552 
553  if(_period[ch]==pwm) return; // already so
554 
555  _period[ch]=pwm;
556 
557  if(_corked) return;
558 
559  set_pwm(ch, pwm);
560 }
561 
562 
563 
564 void RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
565 {
566  if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
567 
568  for (int i = 0; i < len; i++) {
569  write(i + ch, period_us[i]);
570  }
571 }
572 
573 uint16_t RCOutput::read(uint8_t ch)
574 {
576 
577  return _period[ch];
578 }
579 
580 void RCOutput::read(uint16_t* period_us, uint8_t len)
581 {// here we don't need to limit channel count - all unsupported will be read as RC_INPUT_MIN_PULSEWIDT
582  for (int i = 0; i < len; i++) {
583  period_us[i] = read(i);
584  }
585 }
586 
587 void RCOutput::enable_ch(uint8_t ch)
588 {
589  if (ch >= F4Light_MAX_OUTPUT_CHANNELS)
590  return;
591 
592  if(_enabled_channels & (1U<<ch) ) return; // already OK
593 
594  if(!is_servo_enabled(ch)) return; // disabled servo
595 
596  _enabled_channels |= (1U<<ch);
597  if (_period[ch] == PWM_IGNORE_THIS_CHANNEL) {
598  _period[ch] = 0;
599  }
600 
601  if(!_initialized[ch]) {
602 
603  uint8_t pin = output_channels[ch];
604 
606  GPIO::_pinMode(pin, PWM);
607  init_channel(ch);
608 
610 
611  timer_resume(dev);
612 
613  _initialized[ch]=true;
614  }
615 
616  fill_timers(); // re-calculate list of used timers
617 }
618 
619 void RCOutput::disable_ch(uint8_t ch)
620 {
621  if (ch >= F4Light_MAX_OUTPUT_CHANNELS) {
622  return;
623  }
624 
625  if(!is_servo_enabled(ch)) return; // disabled servo
626 
627  _enabled_channels &= ~(1U<<ch);
629 
630 
631  uint8_t pin = output_channels[ch];
632  if (pin >= BOARD_NR_GPIO_PINS) return;
633 
634  GPIO::_pinMode(pin, OUTPUT);
635  GPIO::_write(pin, 0);
636 
637  fill_timers(); // re-calculate list of used timers
638 }
639 
640 
642 {
643 #ifdef DEBUG_PWM
644  uint8_t spin = output_channels[DEBUG_PWM]; // motor 6 as strobe
645  GPIO::_pinMode(spin, OUTPUT);
646  GPIO::_write(spin, 1);
647 #endif
648 
649  for (uint16_t ch = 0; ch < _used_channels; ch++) {
650  set_pwm(ch, _period[ch]);
651  }
652 
653  if(_once_mode){ // generate timer's update on ALL used pins, but only once per timer
654 
655 #if 1
656  for(uint8_t i =0; i<num_out_timers;i++){
658  }
659 
660  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
661  const stm32_pin_info &p = PIN_MAP[output_channels[ch]];
662  timer_set_compare(p.timer_device, p.timer_channel, 0); // to prevent outputs in case of timer overflows
663  }
664 
665 #else
666 
667  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
668  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
669  tim->state->update=false; // reset flag first
670  }
671 
672  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
673  if (!(_enabled_channels & _BV(ch))) continue; // not enabled
674  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
675 
676  tim->state->update=true; // set flag for update for needed timer
677  }
678 
679  for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
680  const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
681  if(tim->state->update) {
683  tim->state->update = false; // only once
684  }
685  }
686 #endif
687  }
688 
689  _corked = false;
690 
691 #ifdef DEBUG_PWM
692  GPIO::_write(spin, 0);
693 #endif
694 }
695 
#define SERVO_PIN_11
Definition: RCOutput.cpp:52
static uint16_t _enabled_channels
Definition: RCOutput.h:96
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
Definition: timer.c:442
static void lateInit()
Definition: RCOutput.cpp:190
#define PWM_TIMER_KHZ
Definition: RCOutput.cpp:167
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:459
static void init_channel(uint8_t ch)
Definition: RCOutput.cpp:480
static uint8_t _initialized[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:105
static const uint8_t *const revo_motor_map[]
Definition: RCOutput.cpp:133
static uint32_t _timer_period(uint16_t speed_hz, const timer_dev *dev)
Definition: RCOutput.h:79
static uint8_t _servo_mask
Definition: RCOutput.h:103
void push() override
Definition: RCOutput.cpp:641
static void fill_timers()
Definition: RCOutput.cpp:224
static void set_pwm(uint8_t ch, uint16_t pwm)
Definition: RCOutput.cpp:513
static const uint8_t output_channels_cleanflight[]
Definition: RCOutput.cpp:98
#define _BV(bit)
Definition: RCOutput.cpp:172
#define TIMER2
Definition: timer.h:610
timer_Channel timer_channel
Definition: boards.h:93
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
BOARD_PWM_MODES
Definition: RCOutput.h:19
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static bool _once_mode
Definition: RCOutput.h:102
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:573
Definition: GPIO.h:35
#define SERVO_PIN_5
Definition: RCOutput.cpp:28
static uint16_t constrain_period(uint16_t p)
Definition: RCOutput.cpp:507
static void InitPWM(void)
Definition: RCOutput.cpp:202
static uint16_t pwm
Definition: RCOutput.cpp:20
#define RC_INPUT_MIN_PULSEWIDTH
Definition: RCInput.h:5
uint32_t freq
Definition: timer.h:563
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:587
static bool is_servo_enabled(uint8_t ch)
Definition: RCOutput.cpp:445
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool update
Definition: timer.h:562
#define SERVO_PIN_9
Definition: RCOutput.cpp:44
#define ONESHOT42_TIMER_KHZ
Definition: RCOutput.cpp:169
static INLINE void timer_resume(const timer_dev *dev)
Start a timer&#39;s counter.
Definition: timer.h:690
#define SERVO_PIN_2
Definition: board.h:175
static const uint8_t * output_channels
Definition: RCOutput.cpp:143
#define F4Light_MAX_OUTPUT_CHANNELS
Definition: RCOutput.h:16
#define TIMER3
Definition: timer.h:611
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:619
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define PWM_BRUSHED_TIMER_KHZ
Definition: RCOutput.cpp:170
static uint16_t timer_get_reload(const timer_dev *dev)
Returns a timer&#39;s reload value.
Definition: timer.h:753
static uint16_t _period[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:87
const timer_dev *const timer_device
Definition: boards.h:90
static const timer_dev * out_timers[16]
Definition: RCOutput.h:117
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:545
static bool _corked
Definition: RCOutput.h:98
#define SERVO_PIN_10
Definition: RCOutput.cpp:48
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
#define F4Light_OUT_CHANNELS
Definition: RCOutput.cpp:24
static const uint8_t output_channels_servo[]
Definition: RCOutput.cpp:115
static void timer_set_compare(const timer_dev *dev, timer_Channel channel, uint16_t value)
Set the compare value for the given timer channel.
Definition: timer.h:783
#define BOARD_NR_GPIO_PINS
Definition: board.h:96
float freq_scale
Definition: timer.h:564
#define RC_INPUT_MAX_PULSEWIDTH
Definition: RCInput.h:6
#define SERVO_PIN_8
Definition: RCOutput.cpp:40
Definition: GPIO.h:87
static void _set_pin_output_mode(uint8_t ch)
Definition: RCOutput.cpp:389
static uint32_t _timer2_preload
Definition: RCOutput.h:111
static uint8_t _pwm_type
Definition: RCOutput.h:114
static uint8_t num_out_timers
Definition: RCOutput.h:118
static enum BOARD_PWM_MODES _mode
Definition: RCOutput.h:101
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:214
uint16_t RCOutput::_period [F4Light_MAX_OUTPUT_CHANNELS] IN_CCM
Definition: RCOutput.cpp:148
timerState * state
Definition: timer.h:578
static uint16_t _timer3_preload
Definition: RCOutput.h:112
static uint16_t _freq[F4Light_MAX_OUTPUT_CHANNELS]
Definition: RCOutput.h:88
static uint8_t _used_channels
Definition: RCOutput.h:100
#define SERVO_PIN_4
Definition: board.h:177
void esc4wayProcess(AP_HAL::UARTDriver *uartPort)
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
Definition: timer.c:357
#define ONESHOT125_TIMER_KHZ
Definition: RCOutput.cpp:168
#define SERVO_PIN_3
Definition: board.h:176
static void _set_output_mode(enum output_mode mode)
Definition: RCOutput.cpp:245
static void init_channels()
Definition: RCOutput.cpp:500
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer&#39;s reload value.
Definition: timer.h:763
static int8_t pin
Definition: AnalogIn.cpp:15
#define PWM_IGNORE_THIS_CHANNEL
Definition: RCOutput.h:14
void init() override
Definition: RCOutput.cpp:174
static const uint8_t output_channels_arducopter[]
Definition: RCOutput.cpp:60
#define SERVO_PIN_7
Definition: RCOutput.cpp:36
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
#define SERVO_PIN_6
Definition: RCOutput.cpp:32
static bool _sbus_enabled
Definition: RCOutput.h:97
static const uint8_t output_channels_openpilot[]
Definition: RCOutput.cpp:80
static void do_4way_if(AP_HAL::UARTDriver *uart)
Definition: RCOutput.cpp:184
#define SERVO_PIN_1
Definition: board.h:174
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.
Definition: timer.h:807
uint8_t esc4wayInit(const uint8_t *output_channels, uint8_t nm)