APM:Libraries
AP_RCProtocol.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 #pragma once
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Common/AP_Common.h>
20 
21 #define MAX_RCIN_CHANNELS 16
22 #define MIN_RCIN_CHANNELS 5
23 
26 public:
28  PPM = 0,
31  DSM,
32  NONE //last enum always is None
33  };
34  void init();
35  void process_pulse(uint32_t width_s0, uint32_t width_s1);
37  uint8_t num_channels();
38  uint16_t read(uint8_t chan);
39  bool new_input();
40  void start_bind(void);
41 
42 private:
45  bool _new_input = false;
46  uint32_t _last_input_ms;
47 };
48 
49 #include "AP_RCProtocol_Backend.h"
enum rcprotocol_t protocol_detected()
Definition: AP_RCProtocol.h:36
void start_bind(void)
uint8_t num_channels()
AP_RCProtocol_Backend * backend[NONE]
Definition: AP_RCProtocol.h:44
void process_pulse(uint32_t width_s0, uint32_t width_s1)
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint32_t _last_input_ms
Definition: AP_RCProtocol.h:46
uint16_t read(uint8_t chan)
enum rcprotocol_t _detected_protocol
Definition: AP_RCProtocol.h:43