PX4 Firmware
PX4 Autopilot Software http://px4.io
linux_pwm_out.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015-2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include <errno.h>
35 #include <stdint.h>
36 #include <stdlib.h>
37 #include <string.h>
38 
39 #include <math.h>
40 
41 #include <px4_platform_common/tasks.h>
42 #include <px4_platform_common/getopt.h>
43 #include <px4_platform_common/posix.h>
44 
45 #include <uORB/Subscription.hpp>
51 
52 #include <drivers/drv_hrt.h>
53 #include <drivers/drv_mixer.h>
54 #include <lib/mixer/MixerGroup.hpp>
55 #include <lib/mixer/mixer_load.h>
56 #include <parameters/param.h>
58 #include <perf/perf_counter.h>
59 
60 #include "common.h"
61 #include "navio_sysfs.h"
62 #include "PCA9685.h"
63 #include "ocpoc_mmap.h"
64 #include "bbblue_pwm_rc.h"
65 
66 namespace linux_pwm_out
67 {
68 static px4_task_t _task_handle = -1;
69 volatile bool _task_should_exit = false;
70 static bool _is_running = false;
71 
72 static char _device[64] = "/sys/class/pwm/pwmchip0";
73 static char _protocol[64] = "navio";
74 static int _max_num_outputs = 8; ///< maximum number of outputs the driver should use
75 static char _mixer_filename[64] = "ROMFS/px4fmu_common/mixers/quad_x.main.mix";
76 
77 // subscriptions
78 int _controls_subs[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
79 int _armed_sub = -1;
80 
81 // publications
84 
86 
87 // topic structures
88 actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
89 orb_id_t _controls_topics[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
92 
93 // polling
94 uint8_t _poll_fds_num = 0;
95 px4_pollfd_struct_t _poll_fds[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
96 
97 // control groups related
98 uint32_t _groups_required = 0;
99 uint32_t _groups_subscribed = 0;
100 
102 
103 // esc parameters
105 int32_t _pwm_min;
106 int32_t _pwm_max;
107 
109 
110 static void usage();
111 
112 static void start();
113 
114 static void stop();
115 
116 static void task_main_trampoline(int argc, char *argv[]);
117 
118 static void subscribe();
119 
120 static void task_main(int argc, char *argv[]);
121 
122 static void update_params(Mixer::Airmode &airmode);
123 
124 /* mixer initialization */
125 int initialize_mixer(const char *mixer_filename);
126 int mixer_control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
127 
128 
129 int mixer_control_callback(uintptr_t handle,
130  uint8_t control_group,
131  uint8_t control_index,
132  float &input)
133 {
134  const actuator_controls_s *controls = (actuator_controls_s *)handle;
135  input = controls[control_group].control[control_index];
136 
137  return 0;
138 }
139 
140 
142 {
143  // multicopter air-mode
144  param_t param_handle = param_find("MC_AIRMODE");
145 
146  if (param_handle != PARAM_INVALID) {
147  param_get(param_handle, (int32_t *)&airmode);
148  }
149 }
150 
151 
152 int initialize_mixer(const char *mixer_filename)
153 {
154  char buf[4096];
155  unsigned buflen = sizeof(buf);
156  memset(buf, '\0', buflen);
157 
158  _mixer_group = new MixerGroup();
159 
160  // PX4_INFO("Trying to initialize mixer from config file %s", mixer_filename);
161 
162  if (load_mixer_file(mixer_filename, buf, buflen) == 0) {
163  if (_mixer_group->load_from_buf(mixer_control_callback, (uintptr_t) &_controls, buf, buflen) == 0) {
164  PX4_INFO("Loaded mixer from file %s", mixer_filename);
165  return 0;
166 
167  } else {
168  PX4_ERR("Unable to parse from mixer config file %s", mixer_filename);
169  }
170 
171  } else {
172  PX4_ERR("Unable to load config file %s", mixer_filename);
173  }
174 
175  if (_mixer_group->count() <= 0) {
176  PX4_ERR("Mixer initialization failed");
177  return -1;
178  }
179 
180  return 0;
181 }
182 
183 
184 void subscribe()
185 {
186  memset(_controls, 0, sizeof(_controls));
187  memset(_poll_fds, 0, sizeof(_poll_fds));
188 
189  /* set up ORB topic names */
190  _controls_topics[0] = ORB_ID(actuator_controls_0);
191  _controls_topics[1] = ORB_ID(actuator_controls_1);
192  _controls_topics[2] = ORB_ID(actuator_controls_2);
193  _controls_topics[3] = ORB_ID(actuator_controls_3);
194 
195  // Subscribe for orb topics
196  for (uint8_t i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
197  if (_groups_required & (1 << i)) {
198  PX4_DEBUG("subscribe to actuator_controls_%d", i);
199  _controls_subs[i] = orb_subscribe(_controls_topics[i]);
200 
201  } else {
202  _controls_subs[i] = -1;
203  }
204 
205  if (_controls_subs[i] >= 0) {
206  _poll_fds[_poll_fds_num].fd = _controls_subs[i];
207  _poll_fds[_poll_fds_num].events = POLLIN;
208  _poll_fds_num++;
209  }
210 
211  _armed_sub = orb_subscribe(ORB_ID(actuator_armed));
212 
213  }
214 }
215 
216 void task_main(int argc, char *argv[])
217 {
218  _is_running = true;
219 
220  _perf_control_latency = perf_alloc(PC_ELAPSED, "linux_pwm_out control latency");
221 
222  // Set up mixer
223  if (initialize_mixer(_mixer_filename) < 0) {
224  PX4_ERR("Mixer initialization failed.");
225  return;
226  }
227 
228  PWMOutBase *pwm_out;
229 
230  if (strcmp(_protocol, "pca9685") == 0) {
231  PX4_INFO("Starting PWM output in PCA9685 mode");
232  pwm_out = new PCA9685();
233 
234  } else if (strcmp(_protocol, "ocpoc_mmap") == 0) {
235  PX4_INFO("Starting PWM output in ocpoc_mmap mode");
236  pwm_out = new OcpocMmapPWMOut(_max_num_outputs);
237 
238 #ifdef __DF_BBBLUE
239 
240  } else if (strcmp(_protocol, "bbblue_rc") == 0) {
241  PX4_INFO("Starting PWM output in bbblue_rc mode");
242  pwm_out = new BBBlueRcPWMOut(_max_num_outputs);
243 #endif
244 
245  } else { /* navio */
246  PX4_INFO("Starting PWM output in Navio mode");
247  pwm_out = new NavioSysfsPWMOut(_device, _max_num_outputs);
248  }
249 
250  if (pwm_out->init() != 0) {
251  PX4_ERR("PWM output init failed");
252  delete pwm_out;
253  return;
254  }
255 
256  _mixer_group->groups_required(_groups_required);
257 
258  // subscribe and set up polling
259  subscribe();
260 
262  update_params(airmode);
263  uORB::Subscription parameter_update_sub{ORB_ID(parameter_update)};
264 
265  int rc_channels_sub = -1;
266 
267  // Start disarmed
268  _armed.armed = false;
269  _armed.prearmed = false;
270 
271  output_limit_init(&_pwm_limit);
272 
273  while (!_task_should_exit) {
274 
275  bool updated;
276  orb_check(_armed_sub, &updated);
277 
278  if (updated) {
279  orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed);
280  }
281 
282  if (_mixer_group) {
283  _mixer_group->set_airmode(airmode);
284  }
285 
286  int pret = px4_poll(_poll_fds, _poll_fds_num, 10);
287 
288  /* Timed out, do a periodic check for _task_should_exit. */
289  if (pret == 0 && !_armed.in_esc_calibration_mode) {
290  continue;
291  }
292 
293  /* This is undesirable but not much we can do. */
294  if (pret < 0) {
295  PX4_WARN("poll error %d, %d", pret, errno);
296  /* sleep a bit before next try */
297  usleep(10000);
298  continue;
299  }
300 
301  /* get controls for required topics */
302  unsigned poll_id = 0;
303 
304  for (uint8_t i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
305  if (_controls_subs[i] >= 0) {
306  if (_poll_fds[poll_id].revents & POLLIN) {
307  orb_copy(_controls_topics[i], _controls_subs[i], &_controls[i]);
308  }
309 
310  poll_id++;
311  }
312  }
313 
314  if (_armed.in_esc_calibration_mode) {
315  if (rc_channels_sub == -1) {
316  // only subscribe when really needed: esc calibration is not something we use regularily
317  rc_channels_sub = orb_subscribe(ORB_ID(rc_channels));
318  }
319 
321  int ret = orb_copy(ORB_ID(rc_channels), rc_channels_sub, &rc_channels);
322  _controls[0].control[0] = 0.f;
323  _controls[0].control[1] = 0.f;
324  _controls[0].control[2] = 0.f;
325  int channel = rc_channels.function[rc_channels_s::RC_CHANNELS_FUNCTION_THROTTLE];
326 
327  if (ret == 0 && channel >= 0 && channel < (int)(sizeof(rc_channels.channels) / sizeof(rc_channels.channels[0]))) {
328  _controls[0].control[3] = rc_channels.channels[channel];
329 
330  } else {
331  _controls[0].control[3] = 1.f;
332  }
333 
334  /* Switch off the PWM limit ramp for the calibration. */
335  _pwm_limit.state = OUTPUT_LIMIT_STATE_ON;
336  }
337 
338  if (_mixer_group != nullptr) {
339  /* do mixing */
340  _outputs.noutputs = _mixer_group->mix(_outputs.output, actuator_outputs_s::NUM_ACTUATOR_OUTPUTS);
341 
342  /* disable unused ports by setting their output to NaN */
343  for (size_t i = _outputs.noutputs; i < _outputs.NUM_ACTUATOR_OUTPUTS; i++) {
344  _outputs.output[i] = NAN;
345  }
346 
347  const uint16_t reverse_mask = 0;
348  uint16_t disarmed_pwm[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS];
349  uint16_t min_pwm[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS];
350  uint16_t max_pwm[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS];
351 
352  for (unsigned int i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) {
353  disarmed_pwm[i] = _pwm_disarmed;
354  min_pwm[i] = _pwm_min;
355  max_pwm[i] = _pwm_max;
356  }
357 
358  uint16_t pwm[actuator_outputs_s::NUM_ACTUATOR_OUTPUTS];
359 
360  // TODO FIXME: pre-armed seems broken
361  output_limit_calc(_armed.armed,
362  false/*_armed.prearmed*/,
363  _outputs.noutputs,
364  reverse_mask,
365  disarmed_pwm,
366  min_pwm,
367  max_pwm,
368  _outputs.output,
369  pwm,
370  &_pwm_limit);
371 
372  if (_armed.lockdown || _armed.manual_lockdown) {
373  pwm_out->send_output_pwm(disarmed_pwm, _outputs.noutputs);
374 
375  } else if (_armed.in_esc_calibration_mode) {
376 
377  uint16_t pwm_value;
378 
379  if (_controls[0].control[3] > 0.5f) { // use throttle to decide which value to use
380  pwm_value = _pwm_max;
381 
382  } else {
383  pwm_value = _pwm_min;
384  }
385 
386  for (uint32_t i = 0; i < _outputs.noutputs; ++i) {
387  pwm[i] = pwm_value;
388  }
389 
390  pwm_out->send_output_pwm(pwm, _outputs.noutputs);
391 
392  } else {
393  pwm_out->send_output_pwm(pwm, _outputs.noutputs);
394  }
395 
396  _outputs.timestamp = hrt_absolute_time();
397 
398  if (_outputs_pub != nullptr) {
399  orb_publish(ORB_ID(actuator_outputs), _outputs_pub, &_outputs);
400 
401  } else {
402  _outputs_pub = orb_advertise(ORB_ID(actuator_outputs), &_outputs);
403  }
404 
405  // use first valid timestamp_sample for latency tracking
406  for (int i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
407  const bool required = _groups_required & (1 << i);
408  const hrt_abstime &timestamp_sample = _controls[i].timestamp_sample;
409 
410  if (required && (timestamp_sample > 0)) {
411  perf_set_elapsed(_perf_control_latency, _outputs.timestamp - timestamp_sample);
412  break;
413  }
414  }
415 
416  } else {
417  PX4_ERR("Could not mix output! Exiting...");
418  _task_should_exit = true;
419  }
420 
421  // check for parameter updates
422  if (parameter_update_sub.updated()) {
423  // clear update
424  parameter_update_s pupdate;
425  parameter_update_sub.copy(&pupdate);
426 
427  // update parameters from storage
428  update_params(airmode);
429  }
430  }
431 
432  delete pwm_out;
433 
434  for (uint8_t i = 0; i < actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS; i++) {
435  if (_controls_subs[i] >= 0) {
436  orb_unsubscribe(_controls_subs[i]);
437  }
438  }
439 
440  if (_armed_sub != -1) {
441  orb_unsubscribe(_armed_sub);
442  _armed_sub = -1;
443  }
444 
445  if (rc_channels_sub != -1) {
446  orb_unsubscribe(rc_channels_sub);
447  }
448 
449  perf_free(_perf_control_latency);
450 
451  _is_running = false;
452 
453 }
454 
455 void task_main_trampoline(int argc, char *argv[])
456 {
457  task_main(argc, argv);
458 }
459 
460 void start()
461 {
462  _task_should_exit = false;
463 
464  /* start the task */
465  _task_handle = px4_task_spawn_cmd("pwm_out_main",
466  SCHED_DEFAULT,
467  SCHED_PRIORITY_MAX,
468  1500,
469  (px4_main_t)&task_main_trampoline,
470  nullptr);
471 
472  if (_task_handle < 0) {
473  PX4_ERR("task start failed");
474  return;
475  }
476 
477 }
478 
479 void stop()
480 {
481  _task_should_exit = true;
482 
483  while (_is_running) {
484  usleep(200000);
485  PX4_INFO(".");
486  }
487 
488  _task_handle = -1;
489 }
490 
491 void usage()
492 {
493  PX4_INFO("usage: pwm_out start [-d pwmdevice] [-m mixerfile] [-p protocol]");
494  PX4_INFO(" -d pwmdevice : sysfs device for pwm generation (only for Navio)");
495  PX4_INFO(" (default /sys/class/pwm/pwmchip0)");
496  PX4_INFO(" -m mixerfile : path to mixerfile");
497  PX4_INFO(" (default ROMFS/px4fmu_common/mixers/quad_x.main.mix)");
498  PX4_INFO(" -p protocol : driver output protocol (navio|pca9685|ocpoc_mmap|bbblue_rc)");
499  PX4_INFO(" (default is navio)");
500  PX4_INFO(" -n num_outputs : maximum number of outputs the driver should use");
501  PX4_INFO(" (default is 8)");
502  PX4_INFO(" pwm_out stop");
503  PX4_INFO(" pwm_out status");
504 }
505 
506 } // namespace linux_pwm_out
507 
508 /* driver 'main' command */
509 extern "C" __EXPORT int linux_pwm_out_main(int argc, char *argv[]);
510 
511 int linux_pwm_out_main(int argc, char *argv[])
512 {
513  int ch;
514  int myoptind = 1;
515  const char *myoptarg = nullptr;
516 
517  char *verb = nullptr;
518 
519  if (argc >= 2) {
520  verb = argv[1];
521 
522  } else {
523  return 1;
524  }
525 
526  while ((ch = px4_getopt(argc, argv, "d:m:p:n:", &myoptind, &myoptarg)) != EOF) {
527  switch (ch) {
528  case 'd':
529  strncpy(linux_pwm_out::_device, myoptarg, sizeof(linux_pwm_out::_device));
530  break;
531 
532  case 'm':
534  break;
535 
536  case 'p':
537  strncpy(linux_pwm_out::_protocol, myoptarg, sizeof(linux_pwm_out::_protocol));
538  break;
539 
540  case 'n': {
541  unsigned long max_num = strtoul(myoptarg, nullptr, 10);
542 
543  if (max_num <= 0) {
544  max_num = 8;
545  }
546 
547  if (max_num > actuator_outputs_s::NUM_ACTUATOR_OUTPUTS) {
548  max_num = actuator_outputs_s::NUM_ACTUATOR_OUTPUTS;
549  }
550 
552  }
553  break;
554  }
555  }
556 
557  /** gets the parameters for the esc's pwm */
561 
562  /*
563  * Start/load the driver.
564  */
565  if (!strcmp(verb, "start")) {
567  PX4_WARN("pwm_out already running");
568  return 1;
569  }
570 
572  }
573 
574  else if (!strcmp(verb, "stop")) {
576  PX4_WARN("pwm_out is not running");
577  return 1;
578  }
579 
581  }
582 
583  else if (!strcmp(verb, "status")) {
584  PX4_WARN("pwm_out is %s", linux_pwm_out::_is_running ? "running" : "not running");
585  return 0;
586 
587  } else {
589  return 1;
590  }
591 
592  return 0;
593 }
int load_from_buf(Mixer::ControlCallback control_cb, uintptr_t cb_handle, const char *buf, unsigned &buflen)
Adds mixers to the group based on a text description in a buffer.
Definition: MixerGroup.cpp:173
#define PARAM_INVALID
Handle returned when a parameter cannot be found.
Definition: param.h:103
static char _protocol[64]
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
Definition: uORB.cpp:90
static int _max_num_outputs
maximum number of outputs the driver should use
class NavioSysfsPWMOut PWM output class for Navio Sysfs
Definition: navio_sysfs.h:45
void output_limit_calc(const bool armed, const bool pre_armed, const unsigned num_channels, const uint16_t reverse_mask, const uint16_t *disarmed_output, const uint16_t *min_output, const uint16_t *max_output, const float *output, uint16_t *effective_output, output_limit_t *limit)
class OcpocMmapPWMOut PWM output class for Aerotenna OcPoC via mmap
Definition: ocpoc_mmap.h:45
measure the time elapsed performing an event
Definition: perf_counter.h:56
actuator_armed_s _armed
orb_advert_t _outputs_pub
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
Definition: parameters.cpp:589
static px4_task_t _task_handle
class BBBlueRcPWMOut PWM output class for BeagleBone Blue with Robotics Cape Library ...
Definition: bbblue_pwm_rc.h:48
static void stop()
Main class that exports features for PCA9685 chip.
Definition: PCA9685.h:72
actuator_outputs_s _outputs
px4_pollfd_struct_t _poll_fds[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
Definition: I2C.hpp:51
static void task_main_trampoline(int argc, char *argv[])
int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout)
void perf_set_elapsed(perf_counter_t handle, int64_t elapsed)
Register a measurement.
orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data)
Definition: uORB.cpp:43
orb_id_t _controls_topics[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
unsigned count() const
Count the mixers in the group.
Definition: MixerGroup.hpp:79
static void task_main(int argc, char *argv[])
uint8_t _poll_fds_num
High-resolution timer with callouts and timekeeping.
virtual int send_output_pwm(const uint16_t *pwm, int num_outputs)=0
Global flash based parameter store.
static bool _is_running
orb_advert_t _rc_pub
Mixer ioctl interfaces.
int orb_subscribe(const struct orb_metadata *meta)
Definition: uORB.cpp:75
int mixer_control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
bool in_esc_calibration_mode
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
enum output_limit_state state
Definition: output_limit.h:67
static void start()
Header common to all counters.
void perf_free(perf_counter_t handle)
Free a counter.
#define perf_alloc(a, b)
Definition: px4io.h:59
int _controls_subs[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
int orb_unsubscribe(int handle)
Definition: uORB.cpp:85
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
uint32_t _groups_required
class PWMOutBase common abstract PWM output base class
Definition: common.h:45
static char _device[64]
Airmode
Definition: Mixer.hpp:139
int load_mixer_file(const char *fname, char *buf, unsigned maxlen)
static void update_params(Mixer::Airmode &airmode)
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
static void subscribe()
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
Definition: parameters.cpp:370
__EXPORT int linux_pwm_out_main(int argc, char *argv[])
volatile bool _task_should_exit
void groups_required(uint32_t &groups)
Definition: MixerGroup.cpp:165
output_limit_t _pwm_limit
static char _mixer_filename[64]
Object metadata.
Definition: uORB.h:50
void set_airmode(Mixer::Airmode airmode)
Definition: MixerGroup.cpp:131
int orb_check(int handle, bool *updated)
Definition: uORB.cpp:95
static void usage()
void output_limit_init(output_limit_t *limit)
MixerGroup * _mixer_group
unsigned mix(float *outputs, unsigned space)
Definition: MixerGroup.cpp:53
Group of mixers, built up from single mixers and processed in order when mixing.
Definition: MixerGroup.hpp:42
uint32_t _groups_subscribed
float channels[18]
Definition: rc_channels.h:82
perf_counter_t _perf_control_latency
int initialize_mixer(const char *mixer_filename)
Library for output limiting (PWM for example)
int8_t function[27]
Definition: rc_channels.h:85
11 bits per channel * 16 channels = 22 bytes.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
uint32_t param_t
Parameter handle.
Definition: param.h:98
Performance measuring tools.
int32_t _pwm_disarmed