APM:Libraries
SRV_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  SRV_Channel.cpp - object to separate input and output channel
17  ranges, trim and reversal
18  */
19 
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_Math/AP_Math.h>
22 #include <AP_Vehicle/AP_Vehicle.h>
23 #include "SRV_Channel.h"
24 
25 #if HAL_WITH_UAVCAN
26 #include <AP_UAVCAN/AP_UAVCAN.h>
28 #endif
29 
30 extern const AP_HAL::HAL& hal;
31 
36 
37 #if HAL_SUPPORT_RCOUT_SERIAL
38 AP_BLHeli *SRV_Channels::blheli_ptr;
39 #endif
40 
42 
47 
49  // @Group: 1_
50  // @Path: SRV_Channel.cpp
51  AP_SUBGROUPINFO(obj_channels[0], "1_", 1, SRV_Channels, SRV_Channel),
52 
53  // @Group: 2_
54  // @Path: SRV_Channel.cpp
55  AP_SUBGROUPINFO(obj_channels[1], "2_", 2, SRV_Channels, SRV_Channel),
56 
57  // @Group: 3_
58  // @Path: SRV_Channel.cpp
59  AP_SUBGROUPINFO(obj_channels[2], "3_", 3, SRV_Channels, SRV_Channel),
60 
61  // @Group: 4_
62  // @Path: SRV_Channel.cpp
63  AP_SUBGROUPINFO(obj_channels[3], "4_", 4, SRV_Channels, SRV_Channel),
64 
65  // @Group: 5_
66  // @Path: SRV_Channel.cpp
67  AP_SUBGROUPINFO(obj_channels[4], "5_", 5, SRV_Channels, SRV_Channel),
68 
69  // @Group: 6_
70  // @Path: SRV_Channel.cpp
71  AP_SUBGROUPINFO(obj_channels[5], "6_", 6, SRV_Channels, SRV_Channel),
72 
73  // @Group: 7_
74  // @Path: SRV_Channel.cpp
75  AP_SUBGROUPINFO(obj_channels[6], "7_", 7, SRV_Channels, SRV_Channel),
76 
77  // @Group: 8_
78  // @Path: SRV_Channel.cpp
79  AP_SUBGROUPINFO(obj_channels[7], "8_", 8, SRV_Channels, SRV_Channel),
80 
81  // @Group: 9_
82  // @Path: SRV_Channel.cpp
83  AP_SUBGROUPINFO(obj_channels[8], "9_", 9, SRV_Channels, SRV_Channel),
84 
85  // @Group: 10_
86  // @Path: SRV_Channel.cpp
87  AP_SUBGROUPINFO(obj_channels[9], "10_", 10, SRV_Channels, SRV_Channel),
88 
89  // @Group: 11_
90  // @Path: SRV_Channel.cpp
91  AP_SUBGROUPINFO(obj_channels[10], "11_", 11, SRV_Channels, SRV_Channel),
92 
93  // @Group: 12_
94  // @Path: SRV_Channel.cpp
95  AP_SUBGROUPINFO(obj_channels[11], "12_", 12, SRV_Channels, SRV_Channel),
96 
97  // @Group: 13_
98  // @Path: SRV_Channel.cpp
99  AP_SUBGROUPINFO(obj_channels[12], "13_", 13, SRV_Channels, SRV_Channel),
100 
101  // @Group: 14_
102  // @Path: SRV_Channel.cpp
103  AP_SUBGROUPINFO(obj_channels[13], "14_", 14, SRV_Channels, SRV_Channel),
104 
105  // @Group: 15_
106  // @Path: SRV_Channel.cpp
107  AP_SUBGROUPINFO(obj_channels[14], "15_", 15, SRV_Channels, SRV_Channel),
108 
109  // @Group: 16_
110  // @Path: SRV_Channel.cpp
111  AP_SUBGROUPINFO(obj_channels[15], "16_", 16, SRV_Channels, SRV_Channel),
112 
113  // @Param: _AUTO_TRIM
114  // @DisplayName: Automatic servo trim
115  // @Description: This enables automatic servo trim in flight. Servos will be trimed in stabilized flight modes when the aircraft is close to level. Changes to servo trim will be saved every 10 seconds and will persist between flights.
116  // @Values: 0:Disable,1:Enable
117  // @User: Advanced
118  AP_GROUPINFO_FRAME("_AUTO_TRIM", 17, SRV_Channels, auto_trim, 0, AP_PARAM_FRAME_PLANE),
119 
120  // @Param: _RATE
121  // @DisplayName: Servo default output rate
122  // @Description: This sets the default output rate in Hz for all outputs.
123  // @Range: 25 400
124  // @User: Advanced
125  // @Units: Hz
126  AP_GROUPINFO("_RATE", 18, SRV_Channels, default_rate, 50),
127 
128  // @Group: _VOLZ_
129  // @Path: ../AP_Volz_Protocol/AP_Volz_Protocol.cpp
130  AP_SUBGROUPINFO(volz, "_VOLZ_", 19, SRV_Channels, AP_Volz_Protocol),
131 
132  // @Group: _SBUS_
133  // @Path: ../AP_SBusOut/AP_SBusOut.cpp
134  AP_SUBGROUPINFO(sbus, "_SBUS_", 20, SRV_Channels, AP_SBusOut),
135 
136 #if HAL_SUPPORT_RCOUT_SERIAL
137  // @Group: _BLH_
138  // @Path: ../AP_BLHeli/AP_BLHeli.cpp
139  AP_SUBGROUPINFO(blheli, "_BLH_", 21, SRV_Channels, AP_BLHeli),
140 #endif
141 
143 };
144 
145 /*
146  constructor
147  */
149 {
150  instance = this;
152 
153  // set defaults from the parameter table
155 
156  // setup ch_num on channels
157  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
158  channels[i].ch_num = i;
159  }
160 
161  volz_ptr = &volz;
162  sbus_ptr = &sbus;
163 #if HAL_SUPPORT_RCOUT_SERIAL
164  blheli_ptr = &blheli;
165 #endif
166 }
167 
168 /*
169  save adjusted trims
170  */
172 {
173  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
174  if (trimmed_mask & (1U<<i)) {
175  channels[i].servo_trim.set_and_save(channels[i].servo_trim.get());
176  }
177  }
178  trimmed_mask = 0;
179 }
180 
182 {
183  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
184  channels[i].set_output_pwm(channels[i].servo_trim);
185  }
186 }
187 
189 {
190  for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
191  hal.rcout->set_failsafe_pwm(1U<<channels[i].ch_num, channels[i].servo_trim);
192  }
193 }
194 
195 /*
196  run calc_pwm for all channels
197  */
199 {
200  for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
201  channels[i].calc_pwm(functions[channels[i].function].output_scaled);
202  }
203 }
204 
205 // set output value for a specific function channel as a pwm value
207 {
208  if (chan < NUM_SERVO_CHANNELS) {
209  channels[chan].set_output_pwm(value);
210  }
211 }
212 
213 /*
214  wrapper around hal.rcout->cork()
215  */
217 {
218  hal.rcout->cork();
219 }
220 
221 /*
222  wrapper around hal.rcout->push()
223  */
225 {
226  hal.rcout->push();
227 
228  // give volz library a chance to update
229  volz_ptr->update();
230 
231  // give sbus library a chance to update
232  sbus_ptr->update();
233 
234 #if HAL_SUPPORT_RCOUT_SERIAL
235  // give blheli telemetry a chance to update
236  blheli_ptr->update_telemetry();
237 #endif
238 
239 #if HAL_WITH_UAVCAN
240  // push outputs to UAVCAN
241  uint8_t can_num_ifaces = AP_BoardConfig_CAN::get_can_num_ifaces();
242  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS && i < can_num_ifaces; i++) {
243  AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i);
244  if (ap_uavcan == nullptr) {
245  continue;
246  }
247  ap_uavcan->SRV_push_servos();
248  }
249 #endif // HAL_WITH_UAVCAN
250 }
void SRV_push_servos(void)
This must be the last enum value (only add new values before this one)
Definition: SRV_Channel.h:124
static struct SRV_Channels::srv_function functions[SRV_Channel::k_nr_aux_servo_functions]
static uint16_t disabled_mask
Definition: SRV_Channel.h:457
static AP_SBusOut * sbus_ptr
Definition: SRV_Channel.h:450
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint8_t ch_num
Definition: SRV_Channel.h:214
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_Int16 servo_trim
Definition: SRV_Channel.h:199
static bool initialised
Definition: SRV_Channel.h:438
static bool disabled_passthrough
Definition: SRV_Channel.h:433
static void push()
SRV_Channel obj_channels[NUM_SERVO_CHANNELS]
Definition: SRV_Channel.h:459
static SRV_Channel * channels
Definition: SRV_Channel.h:441
static void set_output_pwm_chan(uint8_t chan, uint16_t value)
static AP_UAVCAN * get_uavcan(uint8_t iface)
AP_SBusOut sbus
Definition: SRV_Channel.h:449
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
Definition: RCOutput.h:86
virtual void cork()=0
SRV_Channel::servo_mask_t trimmed_mask
Definition: SRV_Channel.h:435
virtual void push()=0
static const struct AP_Param::GroupInfo var_info[]
Definition: SRV_Channel.h:258
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
static void setup_failsafe_trim_all(void)
static Bitmask function_mask
Definition: SRV_Channel.h:437
static void output_trim_all(void)
void update()
Definition: AP_SBusOut.cpp:82
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
#define AP_PARAM_FRAME_PLANE
Definition: AP_Param.h:79
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
float value
static void cork()
void save_trim(void)
AP_Volz_Protocol volz
Definition: SRV_Channel.h:445
static SRV_Channels * instance
Definition: SRV_Channel.h:442
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
static void calc_pwm(void)
#define NUM_SERVO_CHANNELS
Definition: SRV_Channel.h:24
void set_output_pwm(uint16_t pwm)
void calc_pwm(int16_t output_scaled)
#define AP_GROUPEND
Definition: AP_Param.h:121
static AP_Volz_Protocol * volz_ptr
Definition: SRV_Channel.h:446
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214