APM:Libraries
AP_RCProtocol.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 
18 #include "AP_RCProtocol.h"
19 #include "AP_RCProtocol_PPMSum.h"
20 #include "AP_RCProtocol_DSM.h"
21 #include "AP_RCProtocol_SBUS.h"
22 #include "AP_RCProtocol_SBUS_NI.h"
23 
25 {
30 }
31 
32 void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
33 {
34  uint32_t now = AP_HAL::millis();
35  // first try current protocol
37  backend[_detected_protocol]->process_pulse(width_s0, width_s1);
39  _new_input = true;
41  }
42  return;
43  }
44 
45  // otherwise scan all protocols
46  for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
47  if (backend[i] != nullptr) {
48  backend[i]->process_pulse(width_s0, width_s1);
49  if (backend[i]->new_input()) {
50  _new_input = true;
53  }
54  }
55  }
56 }
57 
59 {
60  bool ret = _new_input;
61  _new_input = false;
62 
63  // run update function on backends
64  for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
65  if (backend[i] != nullptr) {
66  backend[i]->update();
67  }
68  }
69  return ret;
70 }
71 
73 {
76  }
77  return 0;
78 }
79 
80 uint16_t AP_RCProtocol::read(uint8_t chan)
81 {
83  return backend[_detected_protocol]->read(chan);
84  }
85  return 0;
86 }
87 
88 /*
89  ask for bind start on supported receivers (eg spektrum satellite)
90  */
92 {
93  for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
94  if (backend[i] != nullptr) {
95  backend[i]->start_bind();
96  }
97  }
98 }
void start_bind(void)
virtual void start_bind(void)
uint8_t num_channels()
uint32_t millis()
Definition: system.cpp:157
virtual void update(void)
AP_RCProtocol_Backend * backend[NONE]
Definition: AP_RCProtocol.h:44
void process_pulse(uint32_t width_s0, uint32_t width_s1)
uint16_t read(uint8_t chan)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint32_t _last_input_ms
Definition: AP_RCProtocol.h:46
virtual void process_pulse(uint32_t width_s0, uint32_t width_s1)=0
uint16_t read(uint8_t chan)
enum rcprotocol_t _detected_protocol
Definition: AP_RCProtocol.h:43