APM:Libraries
RCInput_Multi.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  this is a driver for multiple RCInput methods on one board
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 
21 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
22  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
23 #include "RCInput_Multi.h"
24 
25 extern const AP_HAL::HAL& hal;
26 
27 using namespace Linux;
28 
29 // constructor
30 RCInput_Multi::RCInput_Multi(uint8_t _num_inputs, ...) :
31  num_inputs(_num_inputs)
32 {
33  va_list ap;
34  inputs = new RCInput*[num_inputs];
35  if (inputs == nullptr) {
36  AP_HAL::panic("failed to allocated RCInput array");
37  }
38  va_start(ap, _num_inputs);
39  for (uint8_t i=0; i<num_inputs; i++) {
40  inputs[i] = va_arg(ap, RCInput *);
41  if (inputs[i] == nullptr) {
42  AP_HAL::panic("Bad RCInput object");
43  }
44  }
45  va_end(ap);
46 }
47 
49 {
50  for (uint8_t i=0; i<num_inputs; i++) {
51  inputs[i]->init();
52  }
53 }
54 
56 {
57  for (uint8_t i=0; i<num_inputs; i++) {
58  inputs[i]->_timer_tick();
59  if (inputs[i]->new_input()) {
63  }
64  }
65 }
66 
67 #endif // CONFIG_HAL_BOARD_SUBTYPE
68 
void _timer_tick(void) override
virtual void init()
Definition: RCInput.cpp:33
std::atomic< unsigned int > rc_input_count
Definition: RCInput.h:55
uint8_t num_channels()
Definition: RCInput.cpp:46
bool new_input()
Definition: RCInput.cpp:37
void init() override
virtual void _timer_tick()
Definition: RCInput.h:34
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:58
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
RCInput_Multi(uint8_t num_inputs,...)
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
uint8_t _num_channels
Definition: RCInput.h:59
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140