APM:Libraries
RC_Channels.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 /*
17  * RC_Channels.cpp - class containing an array of RC_Channel objects
18  *
19  */
20 
21 #include <stdlib.h>
22 #include <cmath>
23 
24 #include <AP_HAL/AP_HAL.h>
25 extern const AP_HAL::HAL& hal;
26 
27 #include <AP_Math/AP_Math.h>
28 
29 #include "RC_Channel.h"
30 
32 
34  // @Group: 1_
35  // @Path: RC_Channel.cpp
36  AP_SUBGROUPINFO(obj_channels[0], "1_", 1, RC_Channels, RC_Channel),
37 
38  // @Group: 2_
39  // @Path: RC_Channel.cpp
40  AP_SUBGROUPINFO(obj_channels[1], "2_", 2, RC_Channels, RC_Channel),
41 
42  // @Group: 3_
43  // @Path: RC_Channel.cpp
44  AP_SUBGROUPINFO(obj_channels[2], "3_", 3, RC_Channels, RC_Channel),
45 
46  // @Group: 4_
47  // @Path: RC_Channel.cpp
48  AP_SUBGROUPINFO(obj_channels[3], "4_", 4, RC_Channels, RC_Channel),
49 
50  // @Group: 5_
51  // @Path: RC_Channel.cpp
52  AP_SUBGROUPINFO(obj_channels[4], "5_", 5, RC_Channels, RC_Channel),
53 
54  // @Group: 6_
55  // @Path: RC_Channel.cpp
56  AP_SUBGROUPINFO(obj_channels[5], "6_", 6, RC_Channels, RC_Channel),
57 
58  // @Group: 7_
59  // @Path: RC_Channel.cpp
60  AP_SUBGROUPINFO(obj_channels[6], "7_", 7, RC_Channels, RC_Channel),
61 
62  // @Group: 8_
63  // @Path: RC_Channel.cpp
64  AP_SUBGROUPINFO(obj_channels[7], "8_", 8, RC_Channels, RC_Channel),
65 
66  // @Group: 9_
67  // @Path: RC_Channel.cpp
68  AP_SUBGROUPINFO(obj_channels[8], "9_", 9, RC_Channels, RC_Channel),
69 
70  // @Group: 10_
71  // @Path: RC_Channel.cpp
72  AP_SUBGROUPINFO(obj_channels[9], "10_", 10, RC_Channels, RC_Channel),
73 
74  // @Group: 11_
75  // @Path: RC_Channel.cpp
76  AP_SUBGROUPINFO(obj_channels[10], "11_", 11, RC_Channels, RC_Channel),
77 
78  // @Group: 12_
79  // @Path: RC_Channel.cpp
80  AP_SUBGROUPINFO(obj_channels[11], "12_", 12, RC_Channels, RC_Channel),
81 
82  // @Group: 13_
83  // @Path: RC_Channel.cpp
84  AP_SUBGROUPINFO(obj_channels[12], "13_", 13, RC_Channels, RC_Channel),
85 
86  // @Group: 14_
87  // @Path: RC_Channel.cpp
88  AP_SUBGROUPINFO(obj_channels[13], "14_", 14, RC_Channels, RC_Channel),
89 
90  // @Group: 15_
91  // @Path: RC_Channel.cpp
92  AP_SUBGROUPINFO(obj_channels[14], "15_", 15, RC_Channels, RC_Channel),
93 
94  // @Group: 16_
95  // @Path: RC_Channel.cpp
96  AP_SUBGROUPINFO(obj_channels[15], "16_", 16, RC_Channels, RC_Channel),
97 
99 };
100 
101 
102 /*
103  channels group object constructor
104  */
106 {
108 
109  // set defaults from the parameter table
111 
112  // setup ch_in on channels
113  for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
114  channels[i].ch_in = i;
115  }
116 }
117 
118 uint16_t RC_Channels::get_radio_in(const uint8_t chan)
119 {
120  if (chan >= NUM_RC_CHANNELS) {
121  return 0;
122  }
123  return channels[chan].get_radio_in();
124 }
125 
126 uint8_t RC_Channels::get_radio_in(uint16_t *chans, const uint8_t num_channels)
127 {
128  uint8_t read_channels = MIN(num_channels, NUM_RC_CHANNELS);
129  for (uint8_t i = 0; i < read_channels; i++) {
130  chans[i] = channels[i].get_radio_in();
131  }
132 
133  // clear any excess channels we couldn't read
134  if (read_channels < num_channels) {
135  memset(&chans[NUM_RC_CHANNELS], 0, sizeof(uint16_t) * (num_channels - read_channels));
136  }
137 
138  return read_channels;
139 }
140 
141 /*
142  call read() and set_pwm() on all channels if there is new data
143  */
144 bool
146 {
147  if (!hal.rcin->new_input()) {
148  return false;
149  }
150 
151  for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
152  channels[i].set_pwm(channels[i].read());
153  }
154 
155  return true;
156 }
157 
159 {
160  return MIN(NUM_RC_CHANNELS, hal.rcin->num_channels());
161 }
162 
164 {
165  return hal.rcin->get_rssi();
166 }
167 
169 {
170  hal.rcin->clear_overrides();
171 }
172 
173 bool RC_Channels::set_override(const uint8_t chan, const int16_t value)
174 {
175  if (chan < NUM_RC_CHANNELS) {
176  return hal.rcin->set_override(chan, value);
177  }
178  return false;
179 }
180 
181 bool RC_Channels::receiver_bind(const int dsmMode)
182 {
183  return hal.rcin->rc_bind(dsmMode);
184 }
static uint8_t get_valid_channel_count(void)
virtual uint8_t num_channels()=0
virtual bool set_override(uint8_t channel, int16_t override)=0
virtual void clear_overrides()=0
int16_t get_radio_in() const
Definition: RC_Channel.h:79
virtual bool new_input(void)=0
void set_pwm(int16_t pwm)
Definition: RC_Channel.cpp:113
static const struct AP_Param::GroupInfo var_info[]
Definition: RC_Channel.h:143
static bool receiver_bind(const int dsmMode)
RC_Channel obj_channels[NUM_RC_CHANNELS]
Definition: RC_Channel.h:163
#define MIN(a, b)
Definition: usb_conf.h:215
virtual int16_t get_rssi(void)
Definition: RCInput.h:36
#define NUM_RC_CHANNELS
Definition: RC_Channel.h:11
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
Definition: RC_Channel.h:15
virtual bool rc_bind(int dsmMode)
Definition: RCInput.h:53
RC_Channels(void)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static RC_Channel * channels
Definition: RC_Channel.h:162
static bool read_input(void)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
static int16_t get_receiver_rssi(void)
static uint16_t get_radio_in(const uint8_t chan)
float value
static void clear_overrides(void)
uint8_t ch_in
Definition: RC_Channel.h:124
AP_HAL::RCInput * rcin
Definition: HAL.h:112
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
static bool set_override(const uint8_t chan, const int16_t value)
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214