APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3 
4 #include "RCInput.h"
5 
6 using namespace HALSITL;
7 
8 extern const AP_HAL::HAL& hal;
9 
11 {
13 }
14 
16 {
17  if (_sitlState->new_rc_input) {
18  _sitlState->new_rc_input = false;
19  return true;
20  }
21  return false;
22 }
23 
24 uint16_t RCInput::read(uint8_t ch)
25 {
26  if (ch >= SITL_RC_INPUT_CHANNELS) {
27  return 0;
28  }
29  if (_override[ch]) {
30  return _override[ch];
31  }
32  return _sitlState->pwm_input[ch];
33 }
34 
35 uint8_t RCInput::read(uint16_t* periods, uint8_t len)
36 {
37  if (len > SITL_RC_INPUT_CHANNELS) {
39  }
40  for (uint8_t i=0; i < len; i++) {
41  periods[i] = read(i);
42  }
43  return len;
44 }
45 
46 bool RCInput::set_override(uint8_t channel, int16_t override)
47 {
48  if (override < 0) {
49  return false; /* -1: no change. */
50  }
51  if (channel < SITL_RC_INPUT_CHANNELS) {
52  _override[channel] = static_cast<uint16_t>(override);
53  if (override != 0) {
54  return true;
55  }
56  }
57  return false;
58 }
59 
61 {
62  memset(_override, 0, sizeof(_override));
63 }
64 #endif
uint16_t _override[SITL_RC_INPUT_CHANNELS]
Definition: RCInput.h:28
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:24
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]
Definition: SITL_State.h:48
#define SITL_RC_INPUT_CHANNELS
Definition: RCInput.h:6
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCInput.cpp:10
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:46
void init() override
Definition: RCInput.cpp:10
bool new_input() override
Definition: RCInput.cpp:15
void clear_overrides() override
Definition: RCInput.cpp:60
SITL_State * _sitlState
Definition: RCInput.h:25