APM:Libraries
AP_RCProtocol_Backend.h
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 #pragma once
19 
20 #include "AP_RCProtocol.h"
21 
23 {
24  friend class AP_RCProtcol;
25 
26 public:
28  virtual void process_pulse(uint32_t width_s0, uint32_t width_s1) = 0;
29  uint16_t read(uint8_t chan);
30  bool new_input();
31  uint8_t num_channels();
32 
33  // support for receivers that have FC initiated bind support
34  virtual void start_bind(void) {}
35 
36  // allow for backends that need regular polling
37  virtual void update(void) {}
38 
39 protected:
40  void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe);
41 
42 private:
44  unsigned int rc_input_count;
45  unsigned int last_rc_input_count;
46 
48  uint8_t _num_channels;
49 };
AP_RCProtocol_Backend(AP_RCProtocol &_frontend)
virtual void start_bind(void)
#define MAX_RCIN_CHANNELS
Definition: AP_RCProtocol.h:21
virtual void update(void)
uint16_t read(uint8_t chan)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual void process_pulse(uint32_t width_s0, uint32_t width_s1)=0
void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe)
uint16_t _pwm_values[MAX_RCIN_CHANNELS]