PX4 Firmware
PX4 Autopilot Software http://px4.io
controls.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-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 /**
35  * @file controls.c
36  *
37  * R/C inputs and servo outputs.
38  *
39  * @author Lorenz Meier <lorenz@px4.io>
40  */
41 
42 #include <px4_platform_common/px4_config.h>
43 #include <stdbool.h>
44 
45 #include <drivers/drv_hrt.h>
46 #include <drivers/drv_rc_input.h>
47 #include <perf/perf_counter.h>
48 #include <systemlib/ppm_decode.h>
49 #include <rc/st24.h>
50 #include <rc/sumd.h>
51 #include <rc/sbus.h>
52 #include <rc/dsm.h>
53 
54 #include "px4io.h"
55 
56 #define RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */
57 #define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
58 
59 static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
60 static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated);
61 
65 
66 static int _dsm_fd = -1;
67 int _sbus_fd = -1;
68 
69 static uint16_t rc_value_override = 0;
70 
71 #ifdef ADC_RSSI
72 static unsigned _rssi_adc_counts = 0;
73 #endif
74 
75 /* receive signal strenght indicator (RSSI). 0 = no connection, 100 (RC_INPUT_RSSI_MAX): perfect connection */
76 /* Note: this is static because RC-provided telemetry does not occur every tick */
77 static uint16_t _rssi = 0;
78 
79 bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated)
80 {
81  perf_begin(c_gather_dsm);
82  uint8_t n_bytes = 0;
83  uint8_t *bytes;
84  bool dsm_11_bit;
85  int8_t spektrum_rssi;
86  *dsm_updated = dsm_input(_dsm_fd, r_raw_rc_values, &r_raw_rc_count, &dsm_11_bit, &n_bytes, &bytes,
87  &spektrum_rssi, PX4IO_RC_INPUT_CHANNELS);
88 
89  if (*dsm_updated) {
90 
91  if (dsm_11_bit) {
93 
94  } else {
96  }
97 
100 
101  if (spektrum_rssi >= 0 && spektrum_rssi <= 100) {
102 
103  /* ensure ADC RSSI is disabled */
105 
106  *rssi = spektrum_rssi;
107  }
108  }
109 
110  perf_end(c_gather_dsm);
111 
112  /* get data from FD and attempt to parse with DSM and ST24 libs */
113  uint8_t st24_rssi, lost_count;
114  uint16_t st24_channel_count = 0;
115 
116  *st24_updated = false;
117 
118  for (unsigned i = 0; i < n_bytes; i++) {
119  /* set updated flag if one complete packet was parsed */
120  st24_rssi = RC_INPUT_RSSI_MAX;
121  *st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &lost_count,
122  &st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS));
123  }
124 
125  if (*st24_updated && lost_count == 0) {
126 
127  /* ensure ADC RSSI is disabled */
129 
130  *rssi = st24_rssi;
131  r_raw_rc_count = st24_channel_count;
132 
136  }
137 
138 
139  /* get data from FD and attempt to parse with SUMD libs */
140  uint8_t sumd_rssi, sumd_rx_count;
141  uint16_t sumd_channel_count = 0;
142  bool sumd_failsafe_state;
143 
144  *sumd_updated = false;
145 
146  for (unsigned i = 0; i < n_bytes; i++) {
147  /* set updated flag if one complete packet was parsed */
148  sumd_rssi = RC_INPUT_RSSI_MAX;
149  *sumd_updated |= (OK == sumd_decode(bytes[i], &sumd_rssi, &sumd_rx_count,
150  &sumd_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS, &sumd_failsafe_state));
151  }
152 
153  if (*sumd_updated) {
154 
155  /* not setting RSSI since SUMD does not provide one */
156  r_raw_rc_count = sumd_channel_count;
157 
160 
161  if (sumd_failsafe_state) {
163 
164  } else {
166  }
167  }
168 
169  return (*dsm_updated | *st24_updated | *sumd_updated);
170 }
171 
172 void
174 {
175  /* no channels */
176  r_raw_rc_count = 0;
179 
180  /* DSM input (USART1) */
181  _dsm_fd = dsm_init("/dev/ttyS0");
182 
183  /* S.bus input (USART3) */
184  _sbus_fd = sbus_init("/dev/ttyS2", false);
185 
186  /* default to a 1:1 input map, all enabled */
187  for (unsigned i = 0; i < PX4IO_RC_INPUT_CHANNELS; i++) {
188  unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
189 
197  }
198 
199  c_gather_dsm = perf_alloc(PC_ELAPSED, "c_gather_dsm");
200  c_gather_sbus = perf_alloc(PC_ELAPSED, "c_gather_sbus");
201  c_gather_ppm = perf_alloc(PC_ELAPSED, "c_gather_ppm");
202 }
203 
204 void
206 {
207 
208  /*
209  * Gather R/C control inputs from supported sources.
210  *
211  * Note that if you're silly enough to connect more than
212  * one control input source, they're going to fight each
213  * other. Don't do that.
214  */
215 
216 #ifdef ADC_RSSI
217 
219  unsigned counts = adc_measure(ADC_RSSI);
220 
221  if (counts != 0xffff) {
222  /* low pass*/
223  _rssi_adc_counts = (_rssi_adc_counts * 0.998f) + (counts * 0.002f);
224  /* use 1:1 scaling on 3.3V, 12-Bit ADC input */
225  unsigned mV = _rssi_adc_counts * 3300 / 4095;
226  /* scale to 0..100 (RC_INPUT_RSSI_MAX == 100) */
227  _rssi = (mV * RC_INPUT_RSSI_MAX / 3300);
228 
229  if (_rssi > RC_INPUT_RSSI_MAX) {
231  }
232  }
233  }
234 
235 #endif
236 
237  /* zero RSSI if signal is lost */
239  _rssi = 0;
240  }
241 
242  perf_begin(c_gather_sbus);
243 
244  bool sbus_failsafe, sbus_frame_drop;
245  bool sbus_updated = sbus_input(_sbus_fd, r_raw_rc_values, &r_raw_rc_count, &sbus_failsafe, &sbus_frame_drop,
247 
248  if (sbus_updated) {
250 
251  unsigned sbus_rssi = RC_INPUT_RSSI_MAX;
252 
253  if (sbus_frame_drop) {
255  sbus_rssi = RC_INPUT_RSSI_MAX / 2;
256 
257  } else {
259  }
260 
261  if (sbus_failsafe) {
263 
264  } else {
266  }
267 
268  /* set RSSI to an emulated value if ADC RSSI is off */
269  if (!(r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI)) {
270  _rssi = sbus_rssi;
271  }
272 
273  }
274 
275  perf_end(c_gather_sbus);
276 
277  /*
278  * XXX each S.bus frame will cause a PPM decoder interrupt
279  * storm (lots of edges). It might be sensible to actually
280  * disable the PPM decoder completely if we have S.bus signal.
281  */
282  perf_begin(c_gather_ppm);
284 
285  if (ppm_updated) {
286 
290  }
291 
292  perf_end(c_gather_ppm);
293 
294  bool dsm_updated = false, st24_updated = false, sumd_updated = false;
295 
297  perf_begin(c_gather_dsm);
298 
299  (void)dsm_port_input(&_rssi, &dsm_updated, &st24_updated, &sumd_updated);
300 
301  if (dsm_updated) {
303  }
304 
305  if (st24_updated) {
307  }
308 
309  if (sumd_updated) {
311  }
312 
313  perf_end(c_gather_dsm);
314  }
315 
316  /* limit number of channels to allowable data size */
319  }
320 
321  /* store RSSI */
323 
324  /*
325  * In some cases we may have received a frame, but input has still
326  * been lost.
327  */
328  bool rc_input_lost = false;
329 
330  /*
331  * If we received a new frame from any of the RC sources, process it.
332  */
333  if (dsm_updated || sbus_updated || ppm_updated || st24_updated || sumd_updated) {
334 
335  /* record a bitmask of channels assigned */
336  unsigned assigned_channels = 0;
337 
338  /* update RC-received timestamp */
340 
341  /* update RC-received timestamp */
343 
344  /* map raw inputs to mapped inputs */
345  /* XXX mapping should be atomic relative to protocol */
346  for (unsigned i = 0; i < r_raw_rc_count; i++) {
347 
348  /* map the input channel */
349  uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
350 
352 
353  uint16_t raw = r_raw_rc_values[i];
354 
355  int16_t scaled;
356 
357  /*
358  * 1) Constrain to min/max values, as later processing depends on bounds.
359  */
360  if (raw < conf[PX4IO_P_RC_CONFIG_MIN]) {
361  raw = conf[PX4IO_P_RC_CONFIG_MIN];
362  }
363 
364  if (raw > conf[PX4IO_P_RC_CONFIG_MAX]) {
365  raw = conf[PX4IO_P_RC_CONFIG_MAX];
366  }
367 
368  /*
369  * 2) Scale around the mid point differently for lower and upper range.
370  *
371  * This is necessary as they don't share the same endpoints and slope.
372  *
373  * First normalize to 0..1 range with correct sign (below or above center),
374  * then scale to 20000 range (if center is an actual center, -10000..10000,
375  * if parameters only support half range, scale to 10000 range, e.g. if
376  * center == min 0..10000, if center == max -10000..0).
377  *
378  * As the min and max bounds were enforced in step 1), division by zero
379  * cannot occur, as for the case of center == min or center == max the if
380  * statement is mutually exclusive with the arithmetic NaN case.
381  *
382  * DO NOT REMOVE OR ALTER STEP 1!
383  */
384  if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
385  scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(
387 
388  } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
389  scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(
391 
392  } else {
393  /* in the configured dead zone, output zero */
394  scaled = 0;
395  }
396 
397  /* invert channel if requested */
399  scaled = -scaled;
400  }
401 
402  /* and update the scaled/mapped version */
403  unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
404 
405  if (mapped < PX4IO_CONTROL_CHANNELS) {
406 
407  /* invert channel if pitch - pulling the lever down means pitching up by convention */
408  if (mapped == 1) {
409  /* roll, pitch, yaw, throttle, override is the standard order */
410  scaled = -scaled;
411  }
412 
413  if (mapped == 3 && r_setup_rc_thr_failsafe) {
414  /* throttle failsafe detection */
415  if (((raw < conf[PX4IO_P_RC_CONFIG_MIN]) && (raw < r_setup_rc_thr_failsafe)) ||
416  ((raw > conf[PX4IO_P_RC_CONFIG_MAX]) && (raw > r_setup_rc_thr_failsafe))) {
418 
419  } else {
421  }
422  }
423 
424  r_rc_values[mapped] = SIGNED_TO_REG(scaled);
425  assigned_channels |= (1 << mapped);
426 
427  } else if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH) {
428  /* pick out override channel, indicated by special mapping */
430  }
431  }
432  }
433 
434  /* set un-assigned controls to zero */
435  for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) {
436  if (!(assigned_channels & (1 << i))) {
437  r_rc_values[i] = 0;
438  }
439  }
440 
441  /* set RC OK flag, as we got an update */
444 
445  /* if we have enough channels (5) to control the vehicle, the mapping is ok */
446  if (assigned_channels > 4) {
448 
449  } else {
451  }
452 
453  /*
454  * Export the valid channel bitmap
455  */
456  r_rc_valid = assigned_channels;
457  }
458 
459  /*
460  * If we haven't seen any new control data in 200ms, assume we
461  * have lost input.
462  */
463  if (!rc_input_lost && hrt_elapsed_time_atomic(&system_state.rc_channels_timestamp_received) > 200000) {
464  rc_input_lost = true;
465 
466  /* clear the input-kind flags here */
468  PX4IO_P_STATUS_FLAGS_RC_PPM |
470  PX4IO_P_STATUS_FLAGS_RC_SBUS |
473 
474  }
475 
476  /*
477  * Handle losing RC input
478  */
479 
480  /* if we are in failsafe, clear the override flag */
483  }
484 
485  /* this kicks in if the receiver is gone, but there is not on failsafe (indicated by separate flag) */
486  if (rc_input_lost) {
487  /* Clear the RC input status flag, clear manual override flag */
491 
492  /* flag raw RC as lost */
494 
495  /* Mark all channels as invalid, as we just lost the RX */
496  r_rc_valid = 0;
497 
498  /* Set raw channel count to zero */
499  r_raw_rc_count = 0;
500 
501  /* Set the RC_LOST alarm */
503  }
504 
505  /*
506  * Check for manual override.
507  *
508  * Firstly, manual override must be enabled, RC input available and a mixer loaded.
509  */
510  if (/* condition 1: Override is always allowed */
512  /* condition 2: We have valid RC control inputs from the user */
514  /* condition 3: The system didn't go already into failsafe mode with fixed outputs */
515  !(r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE) &&
516  /* condition 4: RC handling wasn't generally disabled */
518  /* condition 5: We have a valid mixer to map RC inputs to actuator outputs */
520 
521  bool override = false;
522 
523  /*
524  * Check mapped channel 5 (can be any remote channel,
525  * depends on RC_MAP_OVER parameter);
526  * If the value is 'high' then the pilot has
527  * requested override.
528  *
529  */
530  if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
532  override = true;
533  }
534 
535  /*
536  * If the FMU is dead then enable override if we have a mixer
537  * and we want to immediately override (instead of using the RC channel
538  * as in the case above.
539  *
540  * Also, do not enter manual override if we asked for termination
541  * failsafe and FMU is lost.
542  */
546  override = true;
547  }
548 
549  if (override) {
551 
552  } else {
554  }
555 
556  } else {
558  }
559 }
560 
561 static bool
562 ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
563 {
564  bool result = false;
565 
566  if (!(num_values) || !(values) || !(frame_len)) {
567  return result;
568  }
569 
570  /* avoid racing with PPM updates */
571  irqstate_t state = px4_enter_critical_section();
572 
573  /*
574  * If we have received a new PPM frame within the last 200ms, accept it
575  * and then invalidate it.
576  */
577  if (hrt_elapsed_time(&ppm_last_valid_decode) < 200000) {
578 
579  /* PPM data exists, copy it */
580  *num_values = ppm_decoded_channels;
581 
582  if (*num_values > PX4IO_RC_INPUT_CHANNELS) {
583  *num_values = PX4IO_RC_INPUT_CHANNELS;
584  }
585 
586  for (unsigned i = 0; ((i < *num_values) && (i < PPM_MAX_CHANNELS)); i++) {
587  values[i] = ppm_buffer[i];
588  }
589 
590  /* clear validity */
592 
593  /* store PPM frame length */
594  *frame_len = ppm_frame_length;
595 
596  /* good if we got any channels */
597  result = (*num_values > 0);
598  }
599 
600  px4_leave_critical_section(state);
601 
602  return result;
603 }
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count, bool *failsafe)
Decoder for SUMD/SUMH protocol.
Definition: sumd.cpp:111
#define PX4IO_P_STATUS_FLAGS_FMU_OK
Definition: protocol.h:113
#define r_status_alarms
Definition: px4io.h:108
R/C input interface.
static unsigned _rssi_adc_counts
Definition: controls.c:72
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE
Definition: protocol.h:276
static int _dsm_fd
Definition: controls.c:66
RC protocol definition for Spektrum RC.
RC protocol definition for Graupner HoTT transmitter.
#define SIGNED_TO_REG(_signed)
Definition: protocol.h:76
int _sbus_fd
Definition: controls.c:67
measure the time elapsed performing an event
Definition: perf_counter.h:56
__EXPORT uint16_t ppm_frame_length
length of the decoded PPM frame (includes gap)
static enum @74 state
bool dsm_input(int fd, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, uint8_t *n_bytes, uint8_t **bytes, int8_t *rssi, unsigned max_values)
Called periodically to check for input data from the DSM UART.
Definition: dsm.cpp:593
#define r_setup_rc_thr_failsafe
Definition: px4io.h:122
#define r_raw_rc_values
Definition: px4io.h:111
#define PX4IO_P_STATUS_FLAGS_RC_SBUS
Definition: protocol.h:112
void controls_init(void)
R/C receiver handling.
Definition: controls.c:173
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK
Definition: protocol.h:186
#define PX4IO_RC_INPUT_CHANNELS
Definition: px4io.h:68
static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated, bool *sumd_updated)
Definition: controls.c:79
#define PX4IO_P_STATUS_ALARMS_RC_LOST
Definition: protocol.h:130
#define r_setup_features
Definition: px4io.h:117
#define r_setup_arming
Definition: px4io.h:118
#define r_raw_rc_flags
Definition: px4io.h:112
High-resolution timer with callouts and timekeeping.
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
Definition: controls.c:562
void atomic_modify_clear(volatile uint16_t *target, uint16_t modification)
Definition: px4io.c:102
#define PX4IO_P_RC_CONFIG_MAX
highest input value
Definition: protocol.h:270
#define RC_CHANNEL_LOW_THRESH
Definition: controls.c:57
volatile uint64_t rc_channels_timestamp_valid
Definition: px4io.h:146
__EXPORT hrt_abstime ppm_last_valid_decode
timestamp of the last valid decode
RC protocol definition for Yuneec ST24 transmitter.
Header common to all counters.
#define r_rc_values
Definition: px4io.h:114
static perf_counter_t c_gather_dsm
Definition: controls.c:62
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED
Definition: protocol.h:190
#define perf_alloc(a, b)
Definition: px4io.h:59
static uint16_t _rssi
Definition: controls.c:77
void atomic_modify_or(volatile uint16_t *target, uint16_t modification)
Definition: px4io.c:95
#define PX4IO_P_STATUS_FLAGS_MIXER_OK
Definition: protocol.h:115
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
#define r_status_flags
Definition: px4io.h:107
#define PX4IO_P_RC_CONFIG_DEADZONE
band around center that is ignored
Definition: protocol.h:271
void perf_end(perf_counter_t handle)
End a performance event.
#define PX4IO_CONTROL_CHANNELS
Definition: px4io.h:66
#define ADC_RSSI
Definition: px4io.h:181
#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH
magic value for mode switch
Definition: protocol.h:273
#define PX4IO_P_STATUS_FLAGS_OVERRIDE
Definition: protocol.h:108
#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP
Definition: protocol.h:150
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11
Definition: protocol.h:152
#define PX4IO_P_RAW_RC_FLAGS_RC_OK
Definition: protocol.h:154
#define PPM_MAX_CHANNELS
Maximum number of channels that we will decode.
Definition: ppm_decode.h:47
#define RC_INPUT_RSSI_MAX
Maximum RSSI value.
Definition: drv_rc_input.h:64
#define PX4IO_P_RC_CONFIG_ASSIGNMENT
mapped input value
Definition: protocol.h:272
General defines and structures for the PX4IO module firmware.
__EXPORT unsigned ppm_decoded_channels
count of decoded channels
struct sys_state_s system_state
Definition: px4io.c:67
int dsm_init(const char *device)
Initialize the DSM receive functionality.
Definition: dsm.cpp:293
#define PX4IO_P_RC_CONFIG_STRIDE
spacing between channel config data
Definition: protocol.h:277
int sbus_init(const char *device, bool singlewire)
Definition: sbus.cpp:138
#define PX4IO_P_RC_CONFIG_CENTER
center input value
Definition: protocol.h:269
uint16_t r_page_rc_input_config[]
PAGE 103.
Definition: registers.c:224
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED
Definition: protocol.h:275
static uint16_t rc_value_override
Definition: controls.c:69
#define PX4IO_P_STATUS_FLAGS_RC_OK
Definition: protocol.h:109
#define PX4IO_P_STATUS_FLAGS_RC_ST24
Definition: protocol.h:121
static perf_counter_t c_gather_sbus
Definition: controls.c:63
int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Decoder for ST24 protocol.
Definition: st24.cpp:98
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK
Definition: protocol.h:153
RC protocol definition for S.BUS.
#define r_rc_valid
Definition: px4io.h:113
#define PX4IO_P_SETUP_FEATURES_ADC_RSSI
enable ADC RSSI parsing
Definition: protocol.h:180
__BEGIN_DECLS __EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS]
decoded PPM channel values
#define PX4IO_P_STATUS_FLAGS_RC_SUMD
Definition: protocol.h:122
#define PX4IO_P_RAW_RC_NRSSI
Definition: protocol.h:156
#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE
Definition: protocol.h:194
#define OK
Definition: uavcan_main.cpp:71
#define REG_TO_SIGNED(_reg)
Definition: protocol.h:75
#define PX4IO_P_RAW_RC_DATA
Definition: protocol.h:157
#define r_raw_rc_count
Definition: px4io.h:110
static perf_counter_t c_gather_ppm
Definition: controls.c:64
void controls_tick()
Definition: controls.c:205
bool sbus_input(int sbus_fd, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels)
Definition: sbus.cpp:282
uint16_t r_page_raw_rc_input[]
PAGE 4.
Definition: registers.c:115
#define PX4IO_P_RC_CONFIG_MIN
lowest input value
Definition: protocol.h:268
#define PX4IO_P_RC_CONFIG_OPTIONS
channel options bitmask
Definition: protocol.h:274
volatile uint64_t rc_channels_timestamp_received
Definition: px4io.h:145
void perf_begin(perf_counter_t handle)
Begin a performance event.
uint16_t adc_measure(unsigned channel)
Definition: adc.c:137
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE
Definition: protocol.h:151
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
#define PX4IO_P_STATUS_FLAGS_RC_PPM
Definition: protocol.h:110
Performance measuring tools.
PPM input decoder.
#define PX4IO_P_STATUS_FLAGS_RC_DSM
Definition: protocol.h:111
#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE
Definition: protocol.h:193
__EXPORT hrt_abstime hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.