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_PX4
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 PX4;
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 #if !defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
58  struct stat st;
59  // don't try and open px4fmu unless there is a px4io. Otherwise we
60  // can end up opening the same device twice
61  if (stat("/dev/px4io", &st) == 0) {
62  _alt_fd = open("/dev/px4fmu", O_RDWR);
63  if (_alt_fd == -1) {
64  hal.console->printf("RCOutput: failed to open /dev/px4fmu");
65  }
66  }
67 #endif
68 
69  // ensure not to write zeros to disabled channels
70  for (uint8_t i=0; i < PX4_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 PX4RCOutput::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 3 groups of servos.
126 
127  Group 0: channels 0 1
128  Group 1: channels 4 5 6 7
129  Group 2: channels 2 3
130 
131  Channels within a group must be set to the same rate.
132 
133  For the moment we never set the channels above 8 to more than
134  50Hz
135  */
136  if (freq_hz > 50 || freq_hz == 1) {
137  // we are setting high rates on the given channels
138  rate_mask |= chmask & 0xFF;
139  if (rate_mask & 0x3) {
140  rate_mask |= 0x3;
141  }
142  if (rate_mask & 0xc) {
143  rate_mask |= 0xc;
144  }
145  if (rate_mask & 0xF0) {
146  rate_mask |= 0xF0;
147  }
148  } else {
149  // we are setting low rates on the given channels
150  if (chmask & 0x3) {
151  rate_mask &= ~0x3;
152  }
153  if (chmask & 0xc) {
154  rate_mask &= ~0xc;
155  }
156  if (chmask & 0xf0) {
157  rate_mask &= ~0xf0;
158  }
159  }
160 
161  if (ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, rate_mask) != 0) {
162  hal.console->printf("RCOutput: Unable to set alt rate mask to 0x%x\n", (unsigned)rate_mask);
163  }
164 
166  ioctl(fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
167  }
168 }
169 
170 /*
171  set output frequency
172  */
173 void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
174 {
175  if (freq_hz > 50 && (_output_mode == MODE_PWM_ONESHOT || _output_mode == MODE_PWM_ONESHOT125)) {
176  // rate is irrelevent in oneshot
177  return;
178  }
179 
180  // re-fetch servo count as it might have changed due to a change in BRD_PWM_COUNT
181  if (_pwm_fd != -1 && ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count) != 0) {
182  hal.console->printf("RCOutput: Unable to get servo count\n");
183  return;
184  }
185 
186  // greater than 400 doesn't give enough room at higher periods for
187  // the down pulse
188  if (freq_hz > 400 && _output_mode != MODE_PWM_BRUSHED) {
189  freq_hz = 400;
190  }
191  uint32_t primary_mask = chmask & ((1UL<<_servo_count)-1);
192  uint32_t alt_mask = chmask >> _servo_count;
193  if (primary_mask && _pwm_fd != -1) {
194  set_freq_fd(_pwm_fd, primary_mask, freq_hz, _rate_mask_main);
195  }
196  if (alt_mask && _alt_fd != -1) {
197  set_freq_fd(_alt_fd, alt_mask, freq_hz, _rate_mask_alt);
198  }
199 }
200 
201 uint16_t PX4RCOutput::get_freq(uint8_t ch)
202 {
203  if (ch < _servo_count) {
204  if (_rate_mask_main & (1U<<ch)) {
205  return _freq_hz;
206  }
207  } else if (_alt_fd != -1) {
208  if (_rate_mask_alt & (1U<<(ch-_servo_count))) {
209  return _freq_hz;
210  }
211  }
212  return 50;
213 }
214 
215 void PX4RCOutput::enable_ch(uint8_t ch)
216 {
217  if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
218  return;
219  }
220  if (ch >= 8 && !(_enabled_channels & (1U<<ch))) {
221  // this is the first enable of an auxiliary channel - setup
222  // aux channels now. This delayed setup makes it possible to
223  // use BRD_PWM_COUNT to setup the number of PWM channels.
225  }
226  _enabled_channels |= (1U<<ch);
227  if (_period[ch] == PWM_IGNORE_THIS_CHANNEL) {
228  _period[ch] = 0;
229  _last_sent[ch] = 0;
230  }
231 }
232 
233 void PX4RCOutput::disable_ch(uint8_t ch)
234 {
235  if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
236  return;
237  }
238 
239  _enabled_channels &= ~(1U<<ch);
241 }
242 
243 void PX4RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
244 {
245  struct pwm_output_values pwm_values;
246  memset(&pwm_values, 0, sizeof(pwm_values));
247  for (uint8_t i=0; i<_servo_count; i++) {
248  if ((1UL<<i) & chmask) {
249  pwm_values.values[i] = period_us;
250  }
251  pwm_values.channel_count++;
252  }
253  int ret = ioctl(_pwm_fd, PWM_SERVO_SET_DISARMED_PWM, (long unsigned int)&pwm_values);
254  if (ret != OK) {
255  hal.console->printf("Failed to setup disarmed PWM for 0x%08x to %u\n", (unsigned)chmask, period_us);
256  }
257 }
258 
259 void PX4RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
260 {
261  struct pwm_output_values pwm_values;
262  memset(&pwm_values, 0, sizeof(pwm_values));
263  for (uint8_t i=0; i<_servo_count; i++) {
264  if ((1UL<<i) & chmask) {
265  pwm_values.values[i] = period_us;
266  }
267  pwm_values.channel_count++;
268  }
269  int ret = ioctl(_pwm_fd, PWM_SERVO_SET_FAILSAFE_PWM, (long unsigned int)&pwm_values);
270  if (ret != OK) {
271  hal.console->printf("Failed to setup failsafe PWM for 0x%08x to %u\n", (unsigned)chmask, period_us);
272  }
273 }
274 
276 {
279  return true;
280 }
281 
283 {
286 }
287 
289 {
290  // check if there is a pending saftey_state change. If so (timer != 0) then set it.
291  uint32_t now = AP_HAL::millis();
293  now - _safety_state_request_last_ms >= 100) {
298  // current != requested, set it
299  ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_ON, 0);
302  // current != requested, set it
303  ioctl(_pwm_fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
305  }
306  }
307  // also update safety button options if needed
308  if (now - _last_safety_options_check_ms > 1000) {
311  if (boardconfig) {
312  uint16_t desired_options = 0;
313  uint16_t options = boardconfig->get_safety_button_options();
315  desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_OFF;
316  }
318  desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_ON;
319  }
321  desired_options |= PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_OFF | PWM_SERVO_SET_SAFETY_OPTION_DISABLE_BUTTON_ON;
322  }
323  if (_last_safety_options != desired_options) {
324  if (ioctl(_pwm_fd, PWM_SERVO_SET_SAFETY_OPTIONS, desired_options) == OK) {
325  _last_safety_options = desired_options;
326  }
327  }
328  }
329  }
330 }
331 
333 {
337  }
338 }
339 
340 void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
341 {
342  if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
343  return;
344  }
345  if (!(_enabled_channels & (1U<<ch))) {
346  // not enabled
347  return;
348  }
349  if (ch >= _max_channel) {
350  _max_channel = ch + 1;
351  }
352 
354  if (((ch < _servo_count) && ((1U<<ch) & _rate_mask_main)) ||
355  ((ch >= _servo_count) && ((1U<<(ch-_servo_count)) & _rate_mask_alt))) {
356  // we treat oneshot125 very simply on HAL_PX4, with 1us
357  // resolution. Correctly handling it would use a 125 nsec
358  // step size, to give the full 1000 steps
359  period_us /= 8;
360  }
361  }
362 
363  // keep unscaled value
364  _last_sent[ch] = period_us;
365 
367  // map from the PWM range to 0 t0 100% duty cycle. For 16kHz
368  // this ends up being 0 to 500 pulse width in units of
369  // 125usec.
370  if (period_us <= _esc_pwm_min) {
371  period_us = 0;
372  } else if (period_us >= _esc_pwm_max) {
373  period_us = _period_max;
374  } else {
375  uint32_t pdiff = period_us - _esc_pwm_min;
376  period_us = pdiff*_period_max/(_esc_pwm_max - _esc_pwm_min);
377  }
378  }
379 
380  /*
381  only mark an update is needed if there has been a change, or we
382  are in oneshot mode. In oneshot mode we always need to send the
383  output
384  */
385  if (period_us != _period[ch] ||
388  _period[ch] = period_us;
389  _need_update = true;
390  }
391 }
392 
393 uint16_t PX4RCOutput::read(uint8_t ch)
394 {
395  if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
396  return 0;
397  }
398  // if px4io has given us a value for this channel use that,
399  // otherwise use the value we last sent. This makes it easier to
400  // observe the behaviour of failsafe in px4io
401  for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
402  if (_outputs[i].pwm_sub >= 0 &&
403  ch < _outputs[i].outputs.noutputs &&
404  _outputs[i].outputs.output[ch] > 0) {
405  return _outputs[i].outputs.output[ch];
406  }
407  }
408  return _period[ch];
409 }
410 
411 void PX4RCOutput::read(uint16_t* period_us, uint8_t len)
412 {
413  for (uint8_t i=0; i<len; i++) {
414  period_us[i] = read(i);
415  }
416 }
417 
418 uint16_t PX4RCOutput::read_last_sent(uint8_t ch)
419 {
420  if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
421  return 0;
422  }
423 
424  return _last_sent[ch];
425 }
426 
427 void PX4RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
428 {
429  for (uint8_t i=0; i<len; i++) {
430  period_us[i] = read_last_sent(i);
431  }
432 }
433 
434 /*
435  update actuator armed state
436  */
438 {
439  if (_armed.armed == arm) {
440  // already armed;
441  return;
442  }
443 
444  _armed.timestamp = hrt_absolute_time();
445  _armed.armed = arm;
446  if (arm) {
447  // this latches ready_to_arm to true once set once. Otherwise
448  // we have a race condition with px4io safety switch update
449  _armed.ready_to_arm = true;
450  }
451  _armed.lockdown = false;
452  _armed.force_failsafe = false;
453 
454  if (_actuator_armed_pub == nullptr) {
455  _actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed);
456  } else {
457  orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed);
458  }
459 }
460 
462 {
463  uint32_t now = AP_HAL::micros();
464 
465  if ((_enabled_channels & ((1U<<_servo_count)-1)) == 0) {
466  // no channels enabled
467  _arm_actuators(false);
468  goto update_pwm;
469  }
470 
471  // always send at least at 20Hz, otherwise the IO board may think
472  // we are dead
473  if (now - _last_output > 50000) {
474  _need_update = true;
475  }
476 
477  // check for PWM count changing. This can happen then the user changes BRD_PWM_COUNT
478  if (now - _last_config_us > 1000000) {
479  if (_pwm_fd != -1) {
480  ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count);
481  }
482  if (_alt_fd != -1) {
483  ioctl(_alt_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_alt_servo_count);
484  }
485  _last_config_us = now;
486  }
487 
488  if (_need_update && _pwm_fd != -1) {
489  _need_update = false;
490  perf_begin(_perf_rcout);
492  if (_sbus_enabled) {
493  to_send = _max_channel;
494  }
495  if (to_send > 0) {
496  for (int i=to_send-1; i >= 0; i--) {
497  if (_period[i] == PWM_IGNORE_THIS_CHANNEL) {
498  to_send = i;
499  } else {
500  break;
501  }
502  }
503  }
504  if (to_send > 0) {
505  _arm_actuators(true);
506 
507  ::write(_pwm_fd, _period, to_send*sizeof(_period[0]));
508  }
509  if (_max_channel > _servo_count) {
510  // maybe send updates to alt_fd
511  if (_alt_fd != -1 && _alt_servo_count > 0) {
512  uint8_t n = _max_channel - _servo_count;
513  if (n > _alt_servo_count) {
514  n = _alt_servo_count;
515  }
516  if (n > 0) {
517  ::write(_alt_fd, &_period[_servo_count], n*sizeof(_period[0]));
518  }
519  }
520  }
521 
522  perf_end(_perf_rcout);
523  _last_output = now;
524  }
525 
526 update_pwm:
527  for (uint8_t i=0; i<ORB_MULTI_MAX_INSTANCES; i++) {
528  bool rc_updated = false;
529  if (_outputs[i].pwm_sub >= 0 &&
530  orb_check(_outputs[i].pwm_sub, &rc_updated) == 0 &&
531  rc_updated) {
532  orb_copy(ORB_ID(actuator_outputs), _outputs[i].pwm_sub, &_outputs[i].outputs);
533  }
534  }
535 
536 }
537 
539 {
540 #if RCOUT_DEBUG_LATENCY
541  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
542  hal.gpio->write(55, 1);
543 #endif
544  _corking = true;
545 }
546 
548 {
549 #if RCOUT_DEBUG_LATENCY
550  hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
551  hal.gpio->write(55, 0);
552 #endif
553  if (_corking) {
554  _corking = false;
557  // run timer immediately in oneshot mode
558  _send_outputs();
559  }
560  }
561 }
562 
564 {
566  /* in oneshot mode the timer does nothing as the outputs are
567  * sent from push() */
568  _send_outputs();
569  }
570 
572 }
573 
574 /*
575  enable sbus output
576  */
578 {
579  int fd = open("/dev/px4io", 0);
580  if (fd == -1) {
581  return false;
582  }
583  for (uint8_t tries=0; tries<10; tries++) {
584  if (ioctl(fd, SBUS_SET_PROTO_VERSION, 1) != 0) {
585  continue;
586  }
587  if (ioctl(fd, PWM_SERVO_SET_SBUS_RATE, rate_hz) != 0) {
588  continue;
589  }
590  close(fd);
591  _sbus_enabled = true;
592  return true;
593  }
594  close(fd);
595  return false;
596 }
597 
598 /*
599  setup output mode
600  */
601 void PX4RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
602 {
603  if (_output_mode == mode) {
604  // no change
605  return;
606  }
607  if (mode == MODE_PWM_ONESHOT || mode == MODE_PWM_ONESHOT125) {
608  // when using oneshot we don't want the regular pulses. The
609  // best we can do with the current PX4Firmware code is ask for
610  // 1Hz. This does still produce pulses, but the trigger calls
611  // mean the timer is constantly reset, so no pulses are
612  // produced except when triggered by push() when the main loop
613  // is running
615  if (_alt_fd != -1) {
617  }
618  }
619  _output_mode = mode;
620  switch (_output_mode) {
621  case MODE_PWM_ONESHOT:
622  case MODE_PWM_ONESHOT125:
623  ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);
624  if (_alt_fd != -1) {
625  ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
626  }
627  break;
628  case MODE_PWM_DSHOT150:
629  case MODE_PWM_DSHOT300:
630  case MODE_PWM_DSHOT600:
631  case MODE_PWM_DSHOT1200:
632  case MODE_PWM_NONE:
633  // treat as normal PWM for now
634  hal.console->printf("DShot not supported\n");
635  FALLTHROUGH;
636  case MODE_PWM_NORMAL:
637  ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
638  if (_alt_fd != -1) {
639  ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 0);
640  }
641  break;
642  case MODE_PWM_BRUSHED:
643  // setup an 8MHz clock. This has the effect of scaling all outputs by 8x
644  ioctl(_pwm_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
645  if (_alt_fd != -1) {
646  ioctl(_alt_fd, PWM_SERVO_SET_UPDATE_CLOCK, 8);
647  }
648  break;
649  }
650 }
651 
652 
653 // set default output update rate
654 void PX4RCOutput::set_default_rate(uint16_t rate_hz)
655 {
656  if (rate_hz != _default_rate_hz) {
657  // set servo update rate for first 8 pwm channels
658  ioctl(_pwm_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
659  if (_alt_fd != -1) {
660  // set servo update rate for auxiliary channels
661  ioctl(_alt_fd, PWM_SERVO_SET_DEFAULT_UPDATE_RATE, rate_hz);
662  }
663  _default_rate_hz = rate_hz;
664  }
665 }
666 
667 #endif // CONFIG_HAL_BOARD
bool get_soft_armed() const
Definition: Util.h:15
void timer_tick(void) override
Definition: RCOutput.cpp:563
uint16_t _last_sent[PX4_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:58
actuator_armed_s _armed
Definition: RCOutput.h:77
void set_output_mode(uint16_t mask, enum output_mode mode) override
Definition: RCOutput.cpp:601
void set_freq(uint32_t chmask, uint16_t freq_hz) override
Definition: RCOutput.cpp:173
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
#define FALLTHROUGH
Definition: AP_Common.h:50
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t _rate_mask_alt
Definition: RCOutput.h:68
static AP_BoardConfig * get_instance(void)
bool _sbus_enabled
Definition: RCOutput.h:61
void _arm_actuators(bool arm)
Definition: RCOutput.cpp:437
perf_counter_t _perf_rcout
Definition: RCOutput.h:62
uint16_t read_last_sent(uint8_t ch) override
Definition: RCOutput.cpp:418
AP_HAL::Util * util
Definition: HAL.h:115
uint32_t _safety_state_request_last_ms
Definition: RCOutput.h:90
bool enable_px4io_sbus_out(uint16_t rate_hz) override
Definition: RCOutput.cpp:577
void disable_ch(uint8_t ch) override
Definition: RCOutput.cpp:233
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCOutput.cpp:10
void write(uint8_t ch, uint16_t period_us) override
Definition: RCOutput.cpp:340
virtual void write(uint8_t pin, uint8_t value)=0
bool force_safety_on(void) override
Definition: RCOutput.cpp:275
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz, uint32_t &rate_mask)
Definition: RCOutput.cpp:98
enum output_mode _output_mode
Definition: RCOutput.h:87
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint16_t _last_safety_options
Definition: RCOutput.h:72
void force_safety_pending_requests(void)
Definition: RCOutput.cpp:288
unsigned _alt_servo_count
Definition: RCOutput.h:66
uint32_t _last_safety_options_check_ms
Definition: RCOutput.h:71
void force_safety_off(void) override
Definition: RCOutput.cpp:282
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:259
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS]
Definition: RCOutput.h:55
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
uint32_t _last_config_us
Definition: RCOutput.h:64
struct PX4::PX4RCOutput::@107 _outputs[ORB_MULTI_MAX_INSTANCES]
volatile bool _need_update
Definition: RCOutput.h:60
uint16_t _default_rate_hz
Definition: RCOutput.h:92
virtual void pinMode(uint8_t pin, uint8_t output)=0
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
uint16_t _esc_pwm_min
Definition: RCOutput.h:80
void set_default_rate(uint16_t rate_hz) override
Definition: RCOutput.cpp:654
unsigned _servo_count
Definition: RCOutput.h:65
uint16_t _esc_pwm_max
Definition: RCOutput.h:81
uint16_t read(uint8_t ch) override
Definition: RCOutput.cpp:393
orb_advert_t _actuator_armed_pub
Definition: RCOutput.h:79
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
void _init_alt_channels(void)
Definition: RCOutput.cpp:77
actuator_outputs_s outputs
Definition: RCOutput.h:75
uint32_t _last_output
Definition: RCOutput.h:63
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
AP_HAL::GPIO * gpio
Definition: HAL.h:111
void _send_outputs(void)
Definition: RCOutput.cpp:461
uint32_t _rate_mask_main
Definition: RCOutput.h:67
uint32_t _period_max
Definition: RCOutput.h:70
enum AP_HAL::Util::safety_state _safety_state_request
Definition: RCOutput.h:89
void init() override
Definition: RCOutput.cpp:28
uint16_t _enabled_channels
Definition: RCOutput.h:69
uint16_t _freq_hz
Definition: RCOutput.h:54
void enable_ch(uint8_t ch) override
Definition: RCOutput.cpp:215
#define PX4_NUM_OUTPUT_CHANNELS
Definition: RCOutput.h:8
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define PWM_IGNORE_THIS_CHANNEL
Definition: RCOutput.h:14
uint16_t get_safety_button_options(void)
uint16_t get_freq(uint8_t ch) override
Definition: RCOutput.cpp:201
volatile uint8_t _max_channel
Definition: RCOutput.h:59
uint32_t micros()
Definition: system.cpp:152
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override
Definition: RCOutput.cpp:243
void force_safety_no_wait(void) override
Definition: RCOutput.cpp:332