APM:Libraries
AP_RCProtocol_Backend.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_Math/AP_Math.h>
20 
22  frontend(_frontend),
23  rc_input_count(0),
24  last_rc_input_count(0),
25  _num_channels(0)
26 {}
27 
29 {
30  bool ret = rc_input_count != last_rc_input_count;
31  if (ret) {
33  }
34  return ret;
35 }
36 
38 {
39  return _num_channels;
40 }
41 
43 {
44  return _pwm_values[chan];
45 }
46 
47 /*
48  provide input from a backend
49  */
50 void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool in_failsafe)
51 {
52  num_values = MIN(num_values, MAX_RCIN_CHANNELS);
53  memcpy(_pwm_values, values, num_values*sizeof(uint16_t));
54  _num_channels = num_values;
55  if (!in_failsafe) {
57  }
58 }
AP_RCProtocol_Backend(AP_RCProtocol &_frontend)
#define MIN(a, b)
Definition: usb_conf.h:215
#define MAX_RCIN_CHANNELS
Definition: AP_RCProtocol.h:21
uint16_t read(uint8_t chan)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe)
uint16_t _pwm_values[MAX_RCIN_CHANNELS]