APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include "RCInput.h"
18 #include "hal.h"
19 #include "hwdef/common/ppm.h"
20 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
21 
22 #if HAL_WITH_IO_MCU
24 #include <AP_IOMCU/AP_IOMCU.h>
25 extern AP_IOMCU iomcu;
26 #endif
27 
28 #define SIG_DETECT_TIMEOUT_US 500000
29 using namespace ChibiOS;
30 extern const AP_HAL::HAL& hal;
32 {
33 #if HAL_USE_ICU == TRUE
34  //attach timer channel on which the signal will be received
35  sig_reader.attach_capture_timer(&RCIN_ICU_TIMER, RCIN_ICU_CHANNEL, STM32_RCIN_DMA_STREAM, STM32_RCIN_DMA_CHANNEL);
36  rcin_prot.init();
37 #endif
38 
39 #if HAL_USE_EICU == TRUE
40  sig_reader.init(&RCININT_EICU_TIMER, RCININT_EICU_CHANNEL);
41  rcin_prot.init();
42 #endif
43 
44  _init = true;
45 }
46 
48 {
49  if (!_init) {
50  return false;
51  }
53  return false;
54  }
56 
57  if (_override_valid) {
58  // if we have RC overrides active, then always consider it valid
59  valid = true;
60  }
62  _override_valid = false;
63  rcin_mutex.give();
64 
65 #if HAL_RCINPUT_WITH_AP_RADIO
66  if (!_radio_init) {
67  _radio_init = true;
68  radio = AP_Radio::instance();
69  if (radio) {
70  radio->init();
71  }
72  }
73 #endif
74  return valid;
75 }
76 
78 {
79  if (!_init) {
80  return 0;
81  }
82  return _num_channels;
83 }
84 
85 uint16_t RCInput::read(uint8_t channel)
86 {
87  if (!_init) {
88  return 0;
89  }
90  if (channel >= RC_INPUT_MAX_CHANNELS) {
91  return 0;
92  }
94  if (_override[channel]) {
95  uint16_t v = _override[channel];
96  rcin_mutex.give();
97  return v;
98  }
99  if (channel >= _num_channels) {
100  rcin_mutex.give();
101  return 0;
102  }
103  uint16_t v = _rc_values[channel];
104  rcin_mutex.give();
105 #if HAL_RCINPUT_WITH_AP_RADIO
106  if (radio && channel == 0) {
107  // hook to allow for update of radio on main thread, for mavlink sends
108  radio->update();
109  }
110 #endif
111  return v;
112 }
113 
114 uint8_t RCInput::read(uint16_t* periods, uint8_t len)
115 {
116  if (!_init) {
117  return false;
118  }
119 
120  if (len > RC_INPUT_MAX_CHANNELS) {
121  len = RC_INPUT_MAX_CHANNELS;
122  }
123  for (uint8_t i = 0; i < len; i++){
124  periods[i] = read(i);
125  }
126  return len;
127 }
128 
129 bool RCInput::set_override(uint8_t channel, int16_t override)
130 {
131  if (!_init) {
132  return false;
133  }
134 
135  if (override < 0) {
136  return false; /* -1: no change. */
137  }
138  if (channel >= RC_INPUT_MAX_CHANNELS) {
139  return false;
140  }
141  _override[channel] = override;
142  if (override != 0) {
143  _override_valid = true;
144  return true;
145  }
146  return false;
147 }
148 
150 {
151  for (uint8_t i = 0; i < RC_INPUT_MAX_CHANNELS; i++) {
152  set_override(i, 0);
153  }
154 }
155 
156 
158 {
159  if (!_init) {
160  return;
161  }
162 #if HAL_USE_ICU == TRUE || HAL_USE_EICU == TRUE
163  uint32_t width_s0, width_s1;
164 
165  while(sig_reader.read(width_s0, width_s1)) {
166  rcin_prot.process_pulse(width_s0, width_s1);
167  }
168 
169  if (rcin_prot.new_input()) {
173  for (uint8_t i=0; i<_num_channels; i++) {
174  _rc_values[i] = rcin_prot.read(i);
175  }
176  rcin_mutex.give();
177  }
178 #endif
179 
180 #if HAL_RCINPUT_WITH_AP_RADIO
181  if (radio && radio->last_recv_us() != last_radio_us) {
182  last_radio_us = radio->last_recv_us();
184  _rcin_timestamp_last_signal = last_radio_us;
185  _num_channels = radio->num_channels();
186  for (uint8_t i=0; i<_num_channels; i++) {
187  _rc_values[i] = radio->read(i);
188  }
189  rcin_mutex.give();
190  }
191 #endif
192 
193 #if HAL_WITH_IO_MCU
196  iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS)) {
197  _rcin_timestamp_last_signal = last_iomcu_us;
198  }
199  rcin_mutex.give();
200 #endif
201 
202 
203  // note, we rely on the vehicle code checking new_input()
204  // and a timeout for the last valid input to handle failsafe
205 }
206 
207 /*
208  start a bind operation, if supported
209  */
210 bool RCInput::rc_bind(int dsmMode)
211 {
212 #if HAL_USE_ICU == TRUE
213  // ask AP_RCProtocol to start a bind
215 #endif
216 
217 #if HAL_RCINPUT_WITH_AP_RADIO
218  if (radio) {
219  radio->start_recv_bind();
220  }
221 #endif
222  return true;
223 }
224 #endif //#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
bool attach_capture_timer(ICUDriver *icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel)
void start_bind(void)
ChibiOS::SoftSigReader sig_reader
Definition: RCInput.h:79
void _timer_tick(void)
Definition: RCInput.cpp:157
bool _override_valid
Definition: RCInput.h:66
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
uint64_t _last_read
Definition: RCInput.h:65
void init() override
Definition: RCInput.cpp:31
uint16_t _override[RC_INPUT_MAX_CHANNELS]
Definition: RCInput.h:62
uint16_t _rc_values[RC_INPUT_MAX_CHANNELS]
Definition: RCInput.h:63
uint8_t num_channels()
bool rc_bind(int dsmMode) override
Definition: RCInput.cpp:210
static bool io_enabled(void)
bool new_input() override
Definition: RCInput.cpp:47
static AP_Radio * instance(void)
Definition: AP_Radio.h:89
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:129
bool read(uint32_t &widths0, uint32_t &widths1)
uint8_t num_channels() override
Definition: RCInput.cpp:77
void clear_overrides() override
Definition: RCInput.cpp:149
uint8_t _num_channels
Definition: RCInput.h:67
Semaphore rcin_mutex
Definition: RCInput.h:68
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:85
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:32
void process_pulse(uint32_t width_s0, uint32_t width_s1)
float v
Definition: Printf.cpp:15
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCInput.cpp:10
#define RC_INPUT_MAX_CHANNELS
Definition: RCInput.h:38
AP_RCProtocol rcin_prot
Definition: RCInput.h:80
uint32_t _rcin_timestamp_last_signal
Definition: RCInput.h:70
uint16_t read(uint8_t chan)
uint32_t micros()
Definition: system.cpp:152