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_VRBRAIN
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 VRBRAIN;
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 
29 {
30  pthread_mutex_lock(&rcin_mutex);
31  bool valid = _rcin.timestamp_last_signal != _last_read;
32  if (_rcin.rc_failsafe) {
33  // don't consider input valid if we are in RC failsafe.
34  valid = false;
35  }
36  if (_override_valid) {
37  // if we have RC overrides active, then always consider it valid
38  valid = true;
39  }
40  _last_read = _rcin.timestamp_last_signal;
41  _override_valid = false;
42  pthread_mutex_unlock(&rcin_mutex);
43  if (_rcin.input_source != last_input_source) {
44  gcs().send_text(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", input_source_name(_rcin.input_source));
45  last_input_source = _rcin.input_source;
46  }
47  return valid;
48 }
49 
51 {
52  pthread_mutex_lock(&rcin_mutex);
53  uint8_t n = _rcin.channel_count;
54  pthread_mutex_unlock(&rcin_mutex);
55  return n;
56 }
57 
58 uint16_t VRBRAINRCInput::read(uint8_t ch)
59 {
60  if (ch >= RC_INPUT_MAX_CHANNELS) {
61  return 0;
62  }
63  pthread_mutex_lock(&rcin_mutex);
64  if (_override[ch]) {
65  uint16_t v = _override[ch];
66  pthread_mutex_unlock(&rcin_mutex);
67  return v;
68  }
69  if (ch >= _rcin.channel_count) {
70  pthread_mutex_unlock(&rcin_mutex);
71  return 0;
72  }
73  uint16_t v = _rcin.values[ch];
74  pthread_mutex_unlock(&rcin_mutex);
75  return v;
76 }
77 
78 uint8_t VRBRAINRCInput::read(uint16_t* periods, uint8_t len)
79 {
80  if (len > RC_INPUT_MAX_CHANNELS) {
82  }
83  for (uint8_t i = 0; i < len; i++){
84  periods[i] = read(i);
85  }
86  return len;
87 }
88 
89 bool VRBRAINRCInput::set_override(uint8_t channel, int16_t override) {
90  if (override < 0) {
91  return false; /* -1: no change. */
92  }
93  if (channel >= RC_INPUT_MAX_CHANNELS) {
94  return false;
95  }
96  _override[channel] = override;
97  if (override != 0) {
98  _override_valid = true;
99  return true;
100  }
101  return false;
102 }
103 
105 {
106  for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
107  set_override(i, 0);
108  }
109 }
110 
111 const char *VRBRAINRCInput::input_source_name(uint8_t id) const
112 {
113  switch(id) {
114  case input_rc_s::RC_INPUT_SOURCE_UNKNOWN: return "UNKNOWN";
115  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM: return "PX4FMU_PPM";
116  case input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM: return "PX4IO_PPM";
117  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SPEKTRUM: return "PX4IO_SPEKTRUM";
118  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SBUS: return "PX4IO_SBUS";
119  case input_rc_s::RC_INPUT_SOURCE_PX4IO_ST24: return "PX4IO_ST24";
120  case input_rc_s::RC_INPUT_SOURCE_MAVLINK: return "MAVLINK";
121  case input_rc_s::RC_INPUT_SOURCE_QURT: return "QURT";
122  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SPEKTRUM: return "PX4FMU_SPEKTRUM";
123  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS: return "PX4FMU_SBUS";
124  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_ST24: return "PX4FMU_ST24";
125  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SUMD: return "PX4FMU_SUMD";
126  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM: return "PX4FMU_DSM";
127  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SUMD: return "PX4IO_SUMD";
128  case input_rc_s::RC_INPUT_SOURCE_PX4FMU_SRXL: return "PX4FMU_SRXL";
129  case input_rc_s::RC_INPUT_SOURCE_PX4IO_SRXL: return "PX4IO_SRXL";
130  default: return "ERROR";
131  }
132 }
133 
134 
136 {
137  perf_begin(_perf_rcin);
138  bool rc_updated = false;
139  if (orb_check(_rc_sub, &rc_updated) == 0 && rc_updated) {
140  pthread_mutex_lock(&rcin_mutex);
141  orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
142  if (_rcin.rssi != 0 || _rssi != -1) {
143  // always zero means not supported
144  _rssi = _rcin.rssi;
145  }
146  pthread_mutex_unlock(&rcin_mutex);
147  }
148  // note, we rely on the vehicle code checking new_input()
149  // and a timeout for the last valid input to handle failsafe
150  perf_end(_perf_rcin);
151 }
152 
153 bool VRBRAINRCInput::rc_bind(int dsmMode)
154 {
155 
156 
157 
158 
159 
160 
161 
162 
163 
164 
165 
166 
167 
168 
169 
170 
171  return true;
172 }
173 
174 #endif
uint8_t last_input_source
Definition: RCInput.h:44
Interface definition for the various Ground Control System.
perf_counter_t _perf_rcin
Definition: RCInput.h:40
uint8_t num_channels() override
Definition: RCInput.cpp:50
GCS & gcs()
void _timer_tick(void)
Definition: RCInput.cpp:135
static const AP_HAL::HAL & hal
Definition: Device.cpp:29
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:89
bool rc_bind(int dsmMode) override
Definition: RCInput.cpp:153
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:58
void clear_overrides() override
Definition: RCInput.cpp:104
bool new_input() override
Definition: RCInput.cpp:28
float v
Definition: Printf.cpp:15
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
pthread_mutex_t rcin_mutex
Definition: RCInput.h:41
uint16_t _override[RC_INPUT_MAX_CHANNELS]
Definition: RCInput.h:35
const char * input_source_name(uint8_t id) const
Definition: RCInput.cpp:111
#define RC_INPUT_MAX_CHANNELS
Definition: RCInput.h:38
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
struct rc_input_values _rcin
Definition: RCInput.h:36
void init() override
Definition: RCInput.cpp:17