APM:Libraries
RCOutput.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
4 #include "RCOutput.h"
5 
6 #include <sys/types.h>
7 #include <sys/stat.h>
8 #include <fcntl.h>
9 #include <unistd.h>
10 
11 #include <drivers/drv_pwm_output.h>
12 #include <drivers/drv_hrt.h>
13 #include <drivers/drv_pwm_output.h>
14 #include <drivers/drv_sbus.h>
15 
17 
18 extern const AP_HAL::HAL& hal;
19 
20 using namespace VRBRAIN;
21 
22 /*
23  enable RCOUT_DEBUG_LATENCY to measure output latency using a logic
24  analyser. AUX6 will go high during the cork/push output.
25  */
26 #define RCOUT_DEBUG_LATENCY 0
27 
29 {
30  _perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
31  _pwm_fd = open(PWM_OUTPUT0_DEVICE_PATH, O_RDWR);
32  if (_pwm_fd == -1) {
33  AP_HAL::panic("Unable to open " PWM_OUTPUT0_DEVICE_PATH);
34  }
35  if (ioctl(_pwm_fd, PWM_SERVO_ARM, 0) != 0) {
36  hal.console->printf("RCOutput: Unable to setup IO arming\n");
37  }
38  if (ioctl(_pwm_fd, PWM_SERVO_SET_ARM_OK, 0) != 0) {
39  hal.console->printf("RCOutput: Unable to setup IO arming OK\n");
40  }
41 
42  _rate_mask_main = 0;
43  _rate_mask_alt = 0;
44  _alt_fd = -1;
45  _servo_count = 0;
46  _alt_servo_count = 0;
47 
48  if (ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count) != 0) {
49  hal.console->printf("RCOutput: Unable to get servo count\n");
50  return;
51  }
52 
53  for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
54  _outputs[i].pwm_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), i);
55  }
56 
57 
58 
59 
60 
61 
62 
63 
64 
65 
66 
67 
68 
69  // ensure not to write zeros to disabled channels
70  for (uint8_t i=0; i < VRBRAIN_NUM_OUTPUT_CHANNELS; i++) {
73  }
74 }
75 
76 
78 {
79  if (_alt_fd == -1) {
80  return;
81  }
82  if (ioctl(_alt_fd, PWM_SERVO_ARM, 0) != 0) {
83  hal.console->printf("RCOutput: Unable to setup alt IO arming\n");
84  return;
85  }
86  if (ioctl(_alt_fd, PWM_SERVO_SET_ARM_OK, 0) != 0) {
87  hal.console->printf("RCOutput: Unable to setup alt IO arming OK\n");
88  return;
89  }
90  if (ioctl(_alt_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_alt_servo_count) != 0) {
91  hal.console->printf("RCOutput: Unable to get servo count\n");
92  }
93 }
94 
95 /*
96  set output frequency on outputs associated with fd
97  */
98 void VRBRAINRCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
99 {
101  freq_hz /= 8; // divide by 8 for 8MHz clock
102  // remember max period
103  _period_max = 1000000UL/freq_hz;
104  }
105 
106  // we can't set this per channel
107  if (freq_hz > 50 || freq_hz == 1) {
108  // we're being asked to set the alt rate
110  /*
111  set a 1Hz update for oneshot. This periodic output will
112  never actually trigger, instead we will directly trigger
113  the pulse after each push()
114  */
115  freq_hz = 1;
116  }
117  //::printf("SET_UPDATE_RATE %d %u\n", fd, (unsigned)freq_hz);
118  if (ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, (unsigned long)freq_hz) != 0) {
119  hal.console->printf("RCOutput: Unable to set alt rate to %uHz\n", (unsigned)freq_hz);
120  return;
121  }
122  _freq_hz = freq_hz;
123  }
124 
125  /* work out the new rate mask. The outputs have 4 groups of servos.
126 
127  Group 0: channels 0 1 2 3
128  Group 1: channels 4 5
129  Group 2: channels 6 7
130  Group 3: channels 8 9 10
131 
132  Group 0: channels 0 1 2
133  Group 1: channels 3 4 5
134  Group 2: channels 6 7
135  Group 3: channels 8 9 10 11
136 
137  Channels within a group must be set to the same rate.
138 
139  For the moment we never set the channels above 8 to more than
140  50Hz
141  */
142  if (freq_hz > 50 || freq_hz == 1) {
143  // we are setting high rates on the given channels
144  rate_mask |= chmask & 0xFFF;
145 #if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
146  if (rate_mask & 0x0F) {
147  rate_mask |= 0x0F;
148  }
149  if (rate_mask & 0x30) {
150  rate_mask |= 0x30;
151  }
152  if (rate_mask & 0xC0) {
153  rate_mask |= 0xC0;
154  }
155  if (rate_mask & 0x700) {
156  rate_mask |= 0x700;
157  }
158 #else
159  if (rate_mask & 0x07) {
160  rate_mask |= 0x07;
161  }
162  if (rate_mask & 0x38) {
163  rate_mask |= 0x38;
164  }
165  if (rate_mask & 0xC0) {
166  rate_mask |= 0xC0;
167  }
168  if (rate_mask & 0xF00) {
169  rate_mask |= 0xF00;
170  }
171 #endif
172  } else {
173  // we are setting low rates on the given channels
174 #if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
175  if (chmask & 0x0F) {
176  rate_mask &= ~0x0F;
177  }
178  if (chmask & 0x30) {
179  rate_mask &= ~0x30;
180  }
181  if (chmask & 0xC0) {
182  rate_mask &= ~0xC0;
183  }
184  if (chmask & 0x700) {
185  rate_mask &= ~0x700;
186  }
187 #else
188  if (chmask & 0x07) {
189  rate_mask &= ~0x07;
190  }
191  if (chmask & 0x38) {
192  rate_mask &= ~0x38;
193  }
194  if (chmask & 0xC0) {
195  rate_mask &= ~0xC0;
196  }
197  if (chmask & 0xF00) {
198  rate_mask &= ~0xF00;
199  }
200 #endif
201  }
202 
203  if (ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, rate_mask) != 0) {
204  hal.console->printf("RCOutput: Unable to set alt rate mask to 0x%x\n", (unsigned)rate_mask);
205  }
206 
208  ioctl(fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
209  }
210 }
211 
212 /*
213  set output frequency
214  */
215 void VRBRAINRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
216 {
217  if (freq_hz > 50 && (_output_mode == MODE_PWM_ONESHOT || _output_mode == MODE_PWM_ONESHOT125)) {
218  // rate is irrelevent in oneshot
219  return;
220  }
221 
222  // re-fetch servo count as it might have changed due to a change in BRD_PWM_COUNT
223  if (_pwm_fd != -1 && ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count) != 0) {
224  hal.console->printf("RCOutput: Unable to get servo count\n");
225  return;
226  }
227 
228  // greater than 400 doesn't give enough room at higher periods for
229  // the down pulse
230  if (freq_hz > 400 && _output_mode != MODE_PWM_BRUSHED) {
231  freq_hz = 400;
232  }
233  uint32_t primary_mask = chmask & ((1UL<<_servo_count)-1);
234  uint32_t alt_mask = chmask >> _servo_count;
235  if (primary_mask && _pwm_fd != -1) {
236  set_freq_fd(_pwm_fd, primary_mask, freq_hz, _rate_mask_main);
237  }
238  if (alt_mask && _alt_fd != -1) {
239  set_freq_fd(_alt_fd, alt_mask, freq_hz, _rate_mask_alt);
240  }
241 }
242 
243 uint16_t VRBRAINRCOutput::get_freq(uint8_t ch)
244 {
245  if (ch < _servo_count) {
246  if (_rate_mask_main & (1U<<ch)) {
247  return _freq_hz;
248  }
249  } else if (_alt_fd != -1) {
250  if (_rate_mask_alt & (1U<<(ch-_servo_count))) {
251  return _freq_hz;
252  }
253  }
254  return 50;
255 }
256 
258 {
259  if (ch >= VRBRAIN_NUM_OUTPUT_CHANNELS) {
260  return;
261  }
262  if (ch >= 8 && !(_enabled_channels & (1U<<ch))) {
263  // this is the first enable of an auxiliary channel - setup
264  // aux channels now. This delayed setup makes it possible to
265  // use BRD_PWM_COUNT to setup the number of PWM channels.
267  }
268  _enabled_channels |= (1U<<ch);
269  if (_period[ch] == PWM_IGNORE_THIS_CHANNEL) {
270  _period[ch] = 0;
271  _last_sent[ch] = 0;
272  }
273 }
274 
276 {
277  if (ch >= VRBRAIN_NUM_OUTPUT_CHANNELS) {
278  return;
279  }
280 
281  _enabled_channels &= ~(1U<<ch);
283 }
284 
285 void VRBRAINRCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
286 {
287  struct pwm_output_values pwm_values;
288  memset(&pwm_values, 0, sizeof(pwm_values));
289  for (uint8_t i=0; i<_servo_count; i++) {
290  if ((1UL<<i) & chmask) {
291  pwm_values.values[i] = period_us;
292  }
293  pwm_values.channel_count++;
294  }
295  int ret = ioctl(_pwm_fd, PWM_SERVO_SET_DISARMED_PWM, (long unsigned int)&pwm_values);
296  if (ret != OK) {
297  hal.console->printf("Failed to setup disarmed PWM for 0x%08x to %u\n", (unsigned)chmask, period_us);
298  }
299 }
300 
301 void VRBRAINRCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
302 {
303  struct pwm_output_values pwm_values;
304  memset(&pwm_values, 0, sizeof(pwm_values));
305  for (uint8_t i=0; i<_servo_count; i++) {
306  if ((1UL<<i) & chmask) {
307  pwm_values.values[i] = period_us;
308  }
309  pwm_values.channel_count++;
310  }
311  int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FAILSAFE_PWM, (long unsigned int)&pwm_values);
312  if (ret != OK) {
313  hal.console->printf("Failed to setup failsafe PWM for 0x%08x to %u\n", (unsigned)chmask, period_us);
314  }
315 }
316 
318 {
321  return true;
322 }
323 
325 {
328 }
329 
331 {
332  // check if there is a pending saftey_state change. If so (timer != 0) then set it.
333  uint32_t now = AP_HAL::millis();
335  now - _safety_state_request_last_ms >= 100) {
340  // current != requested, set it
341  ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
344  // current != requested, set it
345  ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
347  }
348  }
349 }
350 
352 {
356  }
357 }
358 
359 void VRBRAINRCOutput::write(uint8_t ch, uint16_t period_us)
360 {
361  if (ch >= VRBRAIN_NUM_OUTPUT_CHANNELS) {
362  return;
363  }
364  if (!(_enabled_channels & (1U<<ch))) {
365  // not enabled
366  return;
367  }
368  if (ch >= _max_channel) {
369  _max_channel = ch + 1;
370  }
371 
373  // we treat oneshot125 very simply on HAL_PX4, with 1us
374  // resolution. Correctly handling it would use a 125 nsec
375  // step size, to give the full 1000 steps
376  period_us /= 8;
377  }
378 
379  // keep unscaled value
380  _last_sent[ch] = period_us;
381 
383  // map from the PWM range to 0 t0 100% duty cycle. For 16kHz
384  // this ends up being 0 to 500 pulse width in units of
385  // 125usec.
386  if (period_us <= _esc_pwm_min) {
387  period_us = 0;
388  } else if (period_us >= _esc_pwm_max) {
389  period_us = _period_max;
390  } else {
391  uint32_t pdiff = period_us - _esc_pwm_min;
392  period_us = pdiff*_period_max/(_esc_pwm_max - _esc_pwm_min);
393  }
394  }
395 
396  /*
397  only mark an update is needed if there has been a change, or we
398  are in oneshot mode. In oneshot mode we always need to send the
399  output
400  */
401  if (period_us != _period[ch] ||
404  _period[ch] = period_us;
405  _need_update = true;
406 // up_pwm_servo_set(ch, period_us);
407  }
408 }
409 
410 uint16_t VRBRAINRCOutput::read(uint8_t ch)
411 {
412  if (ch >= VRBRAIN_NUM_OUTPUT_CHANNELS) {
413  return 0;
414  }
415  // if px4io has given us a value for this channel use that,
416  // otherwise use the value we last sent. This makes it easier to
417  // observe the behaviour of failsafe in px4io
418  for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
419  if (_outputs[i].pwm_sub >= 0 &&
420  ch < _outputs[i].outputs.noutputs &&
421  _outputs[i].outputs.output[ch] > 0) {
422  return _outputs[i].outputs.output[ch];
423  }
424  }
425  return _period[ch];
426 }
427 
428 void VRBRAINRCOutput::read(uint16_t* period_us, uint8_t len)
429 {
430  for (uint8_t i=0; i<len; i++) {
431  period_us[i] = read(i);
432  }
433 }
434 
436 {
437  if (ch >= VRBRAIN_NUM_OUTPUT_CHANNELS) {
438  return 0;
439  }
440 
441  return _last_sent[ch];
442 }
443 
444 void VRBRAINRCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
445 {
446  for (uint8_t i=0; i<len; i++) {
447  period_us[i] = read_last_sent(i);
448  }
449 }
450 
451 /*
452  update actuator armed state
453  */
455 {
456  if (_armed.armed == arm) {
457  // already armed;
458  return;
459  }
460 
461  _armed.timestamp = hrt_absolute_time();
462  _armed.armed = arm;
463  if (arm) {
464  // this latches ready_to_arm to true once set once. Otherwise
465  // we have a race condition with px4io safety switch update
466  _armed.ready_to_arm = true;
467  }
468  _armed.lockdown = false;
469  _armed.force_failsafe = false;
470 
471  if (_actuator_armed_pub == nullptr) {
472  _actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed);
473  } else {
474  orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed);
475  }
476 }
477 
479 {
480  uint32_t now = AP_HAL::micros();
481 
482  if ((_enabled_channels & ((1U<<_servo_count)-1)) == 0) {
483  // no channels enabled
484  _arm_actuators(false);
485  goto update_pwm;
486  }
487 
488  // always send at least at 20Hz, otherwise the IO board may think
489  // we are dead
490  if (now - _last_output > 50000) {
491  _need_update = true;
492  }
493 
494  // check for PWM count changing. This can happen then the user changes BRD_PWM_COUNT
495  if (now - _last_config_us > 1000000) {
496  if (_pwm_fd != -1) {
497  ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count);
498  }
499  if (_alt_fd != -1) {
500  ioctl(_alt_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_alt_servo_count);
501  }
502  _last_config_us = now;
503  }
504 
505  if (_need_update && _pwm_fd != -1) {
506  _need_update = false;
507  perf_begin(_perf_rcout);
509  if (_sbus_enabled) {
510  to_send = _max_channel;
511  }
512  if (to_send > 0) {
513  for (int i=to_send-1; i >= 0; i--) {
514  if (_period[i] == PWM_IGNORE_THIS_CHANNEL) {
515  to_send = i;
516  } else {
517  break;
518  }
519  }
520  }
521  if (to_send > 0) {
522  _arm_actuators(true);
523 
524  ::write(_pwm_fd, _period, to_send*sizeof(_period[0]));
525  }
526  if (_max_channel > _servo_count) {
527  // maybe send updates to alt_fd
528  if (_alt_fd != -1 && _alt_servo_count > 0) {
529  uint8_t n = _max_channel - _servo_count;
530  if (n > _alt_servo_count) {
531  n = _alt_servo_count;
532  }
533  if (n > 0) {
534  ::write(_alt_fd, &_period[_servo_count], n*sizeof(_period[0]));
535  }
536  }
537  }
538 
539  perf_end(_perf_rcout);
540  _last_output = now;
541  }
542 
543 update_pwm:
544  for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
545  bool rc_updated = false;
546  if (_outputs[i].pwm_sub >= 0 &&
547  orb_check(_outputs[i].pwm_sub, &rc_updated) == 0 &&
548  rc_updated) {
549  orb_copy(ORB_ID(actuator_outputs), _outputs[i].pwm_sub, &_outputs[i].outputs);
550  }
551  }
552 
553 }
554 
556 {
557 #if RCOUT_DEBUG_LATENCY
558  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
559  hal.gpio->write(55, 1);
560 #endif
561  _corking = true;
562 }
563 
565 {
566 #if RCOUT_DEBUG_LATENCY
567  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
568  hal.gpio->write(55, 0);
569 #endif
570  if (_corking) {
571  _corking = false;
573  // run timer immediately in oneshot mode
574  _send_outputs();
575  }
576  }
577 }
578 
580 {
582  /* in oneshot mode the timer does nothing as the outputs are
583  * sent from push() */
584  _send_outputs();
585  }
586 
588 }
589 
590 /*
591  enable sbus output
592  */
594 {
595  int fd = open("/dev/px4io", 0);
596  if (fd == -1) {
597  return false;
598  }
599  for (uint8_t tries=0; tries<10; tries++) {
600  if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) {
601  continue;
602  }
603  if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate_hz) != 0) {
604  continue;
605  }
606  close(fd);
607  _sbus_enabled = true;
608  return true;
609  }
610  close(fd);
611  return false;
612 }
613 
614 /*
615  setup output mode
616  */
617 void VRBRAINRCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
618 {
619  if (_output_mode == mode) {
620  // no change
621  return;
622  }
623  if (mode == MODE_PWM_ONESHOT || mode == MODE_PWM_ONESHOT125) {
624  // when using oneshot we don't want the regular pulses. The
625  // best we can do with the current PX4Firmware code is ask for
626  // 1Hz. This does still produce pulses, but the trigger calls
627  // mean the timer is constantly reset, so no pulses are
628  // produced except when triggered by push() when the main loop
629  // is running
631  if (_alt_fd != -1) {
633  }
634  }
635  _output_mode = mode;
636  switch (_output_mode) {
637  case MODE_PWM_ONESHOT:
638  case MODE_PWM_ONESHOT125:
639  ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);
640  if (_alt_fd != -1) {
641  ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
642  }
643  break;
644  case MODE_PWM_DSHOT150:
645  case MODE_PWM_DSHOT300:
646  case MODE_PWM_DSHOT600:
647  case MODE_PWM_DSHOT1200:
648  // treat as normal PWM for now
649  hal.console->printf("DShot not supported\n");
650  FALLTHROUGH;
651  case MODE_PWM_NORMAL:
652  ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
653  if (_alt_fd != -1) {
654  ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 0);
655  }
656  break;
657  case MODE_PWM_BRUSHED:
658  // setup an 8MHz clock. This has the effect of scaling all outputs by 8x
659  ioctl(_pwm_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
660  if (_alt_fd != -1) {
661  ioctl(_alt_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
662  }
663  break;
664  }
665 }
666 
667 
668 // set default output update rate
669 void VRBRAINRCOutput::set_default_rate(uint16_t rate_hz)
670 {
671  if (rate_hz != _default_rate_hz) {
672  // set servo update rate for first 8 pwm channels
673  ioctl(_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
674  if (_alt_fd != -1) {
675  // set servo update rate for auxiliary channels
676  ioctl(_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
677  }
678  _default_rate_hz = rate_hz;
679  }
680 }
681 
682 #endif // CONFIG_HAL_BOARD
void timer_tick(void) override
Definition: RCOutput.cpp:579
perf_counter_t _perf_rcout
Definition: RCOutput.h:57
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:243
enum AP_HAL::Util::safety_state _safety_state_request
Definition: RCOutput.h:82
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:275
uint32_t _safety_state_request_last_ms
Definition: RCOutput.h:83
volatile bool _need_update
Definition: RCOutput.h:55
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
Definition: RCOutput.cpp:98
#define FALLTHROUGH
Definition: AP_Common.h:50
unsigned _alt_servo_count
Definition: RCOutput.h:61
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:435
struct VRBRAIN::VRBRAINRCOutput::@116 _outputs[ORB_MULTI_MAX_INSTANCES]
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:301
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:285
AP_HAL::Util * util
Definition: HAL.h:115
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:593
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCOutput.cpp:10
volatile uint8_t _max_channel
Definition: RCOutput.h:54
uint32_t _last_config_us
Definition: RCOutput.h:59
virtual void write(uint8_t pin, uint8_t value)=0
orb_advert_t _actuator_armed_pub
Definition: RCOutput.h:72
void force_safety_off(void) override
Definition: RCOutput.cpp:324
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
enum output_mode _output_mode
Definition: RCOutput.h:80
uint16_t _enabled_channels
Definition: RCOutput.h:64
#define VRBRAIN_NUM_OUTPUT_CHANNELS
Definition: RCOutput.h:8
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:215
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
virtual void pinMode(uint8_t pin, uint8_t output)=0
void init() override
Definition: RCOutput.cpp:28
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:359
void force_safety_no_wait(void) override
Definition: RCOutput.cpp:351
void _arm_actuators(bool arm)
Definition: RCOutput.cpp:454
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
actuator_outputs_s outputs
Definition: RCOutput.h:68
uint16_t _period[VRBRAIN_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:50
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:257
uint16_t _last_sent[VRBRAIN_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:53
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:617
AP_HAL::GPIO * gpio
Definition: HAL.h:111
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:410
void force_safety_pending_requests(void)
Definition: RCOutput.cpp:330
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define PWM_IGNORE_THIS_CHANNEL
Definition: RCOutput.h:14
uint32_t _rate_mask_main
Definition: RCOutput.h:62
void _init_alt_channels(void)
Definition: RCOutput.cpp:77
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:669
uint16_t _default_rate_hz
Definition: RCOutput.h:85
uint32_t micros()
Definition: system.cpp:152
bool force_safety_on(void) override
Definition: RCOutput.cpp:317
actuator_armed_s _armed
Definition: RCOutput.h:70