APM:Libraries
RCInput.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 "RCInput.h"
5 #include <fcntl.h>
6 #include <unistd.h>
7 #include <drivers/drv_pwm_output.h>
8 #include <drivers/drv_hrt.h>
9 #include <uORB/uORB.h>
10 
11 #include <GCS_MAVLink/GCS.h>
12 
13 using namespace PX4;
14 
15 extern const AP_HAL::HAL& hal;
16 
18 {
19  _perf_rcin = perf_alloc(PC_ELAPSED, "APM_rcin");
20  _rc_sub = orb_subscribe(ORB_ID(input_rc));
21  if (_rc_sub == -1) {
22  AP_HAL::panic("Unable to subscribe to input_rc");
23  }
25  pthread_mutex_init(&rcin_mutex, nullptr);
26 
27 #if HAL_RCINPUT_WITH_AP_RADIO
28  radio = AP_Radio::instance();
29  if (radio) {
30  radio->init();
31  }
32 #endif
33 }
34 
36 {
37  pthread_mutex_lock(&rcin_mutex);
38  bool valid = _rcin.timestamp_last_signal != _last_read;
39  if (_rcin.rc_failsafe) {
40  // don't consider input valid if we are in RC failsafe.
41  valid = false;
42  }
43  if (_override_valid) {
44  // if we have RC overrides active, then always consider it valid
45  valid = true;
46  }
47  _last_read = _rcin.timestamp_last_signal;
48  _override_valid = false;
49  pthread_mutex_unlock(&rcin_mutex);
50  if (_rcin.input_source != last_input_source) {
51  gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", input_source_name(_rcin.input_source));
52  last_input_source = _rcin.input_source;
53  }
54  return valid;
55 }
56 
58 {
59  pthread_mutex_lock(&rcin_mutex);
60  uint8_t n = _rcin.channel_count;
61  pthread_mutex_unlock(&rcin_mutex);
62  return n;
63 }
64 
65 uint16_t PX4RCInput::read(uint8_t ch)
66 {
67  if (ch >= RC_INPUT_MAX_CHANNELS) {
68  return 0;
69  }
70  pthread_mutex_lock(&rcin_mutex);
71  if (_override[ch]) {
72  uint16_t v = _override[ch];
73  pthread_mutex_unlock(&rcin_mutex);
74  return v;
75  }
76  if (ch >= _rcin.channel_count) {
77  pthread_mutex_unlock(&rcin_mutex);
78  return 0;
79  }
80  uint16_t v = _rcin.values[ch];
81  pthread_mutex_unlock(&rcin_mutex);
82 
83 #if HAL_RCINPUT_WITH_AP_RADIO
84  if (radio && ch == 0) {
85  // hook to allow for update of radio on main thread, for mavlink sends
86  radio->update();
87  }
88 #endif
89 
90  return v;
91 }
92 
93 uint8_t PX4RCInput::read(uint16_t* periods, uint8_t len)
94 {
95  if (len > RC_INPUT_MAX_CHANNELS) {
97  }
98  for (uint8_t i = 0; i < len; i++){
99  periods[i] = read(i);
100  }
101  return len;
102 }
103 
104 bool PX4RCInput::set_override(uint8_t channel, int16_t override) {
105  if (override < 0) {
106  return false; /* -1: no change. */
107  }
108  if (channel >= RC_INPUT_MAX_CHANNELS) {
109  return false;
110  }
111  _override[channel] = override;
112  if (override != 0) {
113  _override_valid = true;
114  return true;
115  }
116  return false;
117 }
118 
120 {
121  for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
122  set_override(i, 0);
123  }
124 }
125 
126 const char *PX4RCInput::input_source_name(uint8_t id) const
127 {
128  switch(id) {
129  case input_rc_s::RC_INPUT_SOURCE_UNKNOWN: return "UNKNOWN";
130  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM: return "PX4FMU_PPM";
131  case input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM: return "PX4IO_PPM";
132  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SPEKTRUM: return "PX4IO_SPEKTRUM";
133  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SBUS: return "PX4IO_SBUS";
134  case input_rc_s::RC_INPUT_SOURCE_PX4IO_ST24: return "PX4IO_ST24";
135  case input_rc_s::RC_INPUT_SOURCE_MAVLINK: return "MAVLINK";
136  case input_rc_s::RC_INPUT_SOURCE_QURT: return "QURT";
137  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SPEKTRUM: return "PX4FMU_SPEKTRUM";
138  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS: return "PX4FMU_SBUS";
139  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_ST24: return "PX4FMU_ST24";
140  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SUMD: return "PX4FMU_SUMD";
141  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM: return "PX4FMU_DSM";
142  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SUMD: return "PX4IO_SUMD";
143  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SRXL: return "PX4FMU_SRXL";
144  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SRXL: return "PX4IO_SRXL";
145  default: return "ERROR";
146  }
147 }
148 
149 
151 {
152  perf_begin(_perf_rcin);
153  bool rc_updated = false;
154  if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
155  pthread_mutex_lock(&rcin_mutex);
156  orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
157  if (_rcin.rssi != 0 || _rssi != -1) {
158  // always zero means not supported
159  _rssi = _rcin.rssi;
160  }
161  pthread_mutex_unlock(&rcin_mutex);
162  }
163 
164 #if HAL_RCINPUT_WITH_AP_RADIO
165  if (radio && radio->last_recv_us() != last_radio_us) {
166  last_radio_us = radio->last_recv_us();
167  pthread_mutex_lock(&rcin_mutex);
168  _rcin.timestamp_last_signal = last_radio_us;
169  _rcin.channel_count = radio->num_channels();
170  for (uint8_t i=0; i<_rcin.channel_count; i++) {
171  _rcin.values[i] = radio->read(i);
172  }
173  pthread_mutex_unlock(&rcin_mutex);
174  }
175 #endif
176 
177  // note, we rely on the vehicle code checking new_input()
178  // and a timeout for the last valid input to handle failsafe
179  perf_end(_perf_rcin);
180 }
181 
182 bool PX4RCInput::rc_bind(int dsmMode)
183 {
184  int fd = open("/dev/px4io", 0);
185  if (fd == -1) {
186  fd = open("/dev/px4fmu", 0);
187  }
188  if (fd == -1) {
189  hal.console->printf("RCInput: failed to open /dev/px4io or /dev/px4fmu\n");
190  return false;
191  }
192 
193 #if HAL_RCINPUT_WITH_AP_RADIO
194  if (radio) {
195  radio->start_recv_bind();
196  }
197 #endif
198 
199  uint32_t mode = (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES);
200  int ret = ioctl(fd, DSM_BIND_START, mode);
201  close(fd);
202  if (ret != 0) {
203  hal.console->printf("RCInput: Unable to start DSM bind\n");
204  return false;
205  }
206  return true;
207 }
208 
209 #endif
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
Interface definition for the various Ground Control System.
const char * input_source_name(uint8_t id) const
Definition: RCInput.cpp:126
GCS & gcs()
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:104
bool rc_bind(int dsmMode) override
Definition: RCInput.cpp:182
uint8_t last_input_source
Definition: RCInput.h:45
static AP_Radio * instance(void)
Definition: AP_Radio.h:89
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint16_t _override[RC_INPUT_MAX_CHANNELS]
Definition: RCInput.h:36
uint64_t _last_read
Definition: RCInput.h:39
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
void init() override
Definition: RCInput.cpp:17
struct rc_input_values _rcin
Definition: RCInput.h:37
pthread_mutex_t rcin_mutex
Definition: RCInput.h:42
float v
Definition: Printf.cpp:15
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
bool new_input() override
Definition: RCInput.cpp:35
uint8_t num_channels() override
Definition: RCInput.cpp:57
int16_t _rssi
Definition: RCInput.h:43
bool _override_valid
Definition: RCInput.h:40
void clear_overrides() override
Definition: RCInput.cpp:119
perf_counter_t _perf_rcin
Definition: RCInput.h:41
#define RC_INPUT_MAX_CHANNELS
Definition: RCInput.h:38
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:65
void _timer_tick(void)
Definition: RCInput.cpp:150
static const AP_HAL::HAL & hal
Definition: Device.cpp:29