Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/rc_out.cpp
9436 views
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
#include <AP_HAL/AP_HAL.h>
16
#if AP_PERIPH_RC_OUT_ENABLED
17
#include "AP_Periph.h"
18
#if AP_SIM_ENABLED
19
#include <dronecan_msgs.h>
20
#endif
21
22
// magic value from UAVCAN driver packet
23
// dsdl/uavcan/equipment/esc/1030.RawCommand.uavcan
24
// Raw ESC command normalized into [-8192, 8191]
25
#define UAVCAN_ESC_MAX_VALUE 8191
26
27
#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum
28
#ifndef SERVO_OUT_MOTOR_MAX
29
#define SERVO_OUT_MOTOR_MAX 32 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12, SRV_Channel::k_motor13 ... SRV_Channel::k_motor32
30
#endif
31
32
extern const AP_HAL::HAL &hal;
33
34
void AP_Periph_FW::rcout_init()
35
{
36
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
37
// start up with safety enabled. This disables the pwm output until we receive an packet from the rempte system
38
hal.rcout->force_safety_on();
39
#else
40
hal.rcout->force_safety_off();
41
#endif
42
43
#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
44
if (g.esc_telem_port >= 0) {
45
serial_manager.set_protocol_and_baud(g.esc_telem_port, AP_SerialManager::SerialProtocol_ESCTelemetry, 115200);
46
}
47
#endif
48
49
#if HAL_PWM_COUNT > 0
50
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
51
servo_channels.set_default_function(i, SRV_Channel::Function(SRV_Channel::k_rcin1 + i));
52
}
53
#endif
54
55
for (uint8_t i=0; i<SERVO_OUT_RCIN_MAX; i++) {
56
SRV_Channels::set_angle(SRV_Channel::Function(SRV_Channel::k_rcin1 + i), 1000);
57
}
58
59
uint32_t esc_mask = 0;
60
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
61
SRV_Channels::set_range(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
62
uint8_t chan;
63
if (SRV_Channels::find_channel(SRV_Channels::get_motor_function(i), chan)) {
64
esc_mask |= 1U << chan;
65
}
66
}
67
68
// run this once and at 1Hz to configure aux and esc ranges
69
rcout_init_1Hz();
70
71
#if HAL_DSHOT_ENABLED
72
hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());
73
#endif
74
75
// run PWM ESCs at configured rate
76
hal.rcout->set_freq(esc_mask, g.esc_rate.get());
77
78
// setup ESCs with the desired PWM type, allowing for DShot
79
AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
80
81
// run DShot at 1kHz
82
hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400);
83
#if HAL_WITH_ESC_TELEM
84
esc_telem_update_period_ms = 1000 / constrain_int32(g.esc_telem_rate.get(), 1, 1000);
85
#endif
86
}
87
88
void AP_Periph_FW::rcout_init_1Hz()
89
{
90
// this runs at 1Hz to allow for run-time param changes
91
AP::srv().enable_aux_servos();
92
93
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
94
servo_channels.set_esc_scaling_for(SRV_Channels::get_motor_function(i));
95
}
96
}
97
98
void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels)
99
{
100
if (rc == nullptr) {
101
return;
102
}
103
104
const uint8_t channel_count = MIN(num_channels, SERVO_OUT_MOTOR_MAX);
105
for (uint8_t i=0; i<channel_count; i++) {
106
// we don't support motor reversal yet on ESCs in AP_Periph
107
SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), MAX(0,rc[i]));
108
}
109
110
rcout_has_new_data_to_update = true;
111
}
112
113
void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_value)
114
{
115
#if HAL_PWM_COUNT > 0
116
const SRV_Channel::Function function = SRV_Channel::Function(SRV_Channel::k_rcin1 + actuator_id - 1);
117
SRV_Channels::set_output_norm(function, command_value);
118
119
// Add to mask of channels that will be cleared if no commands are received
120
actuator.mask |= SRV_Channels::get_output_channel_mask(function);
121
122
rcout_has_new_data_to_update = true;
123
#if AP_SIM_ENABLED
124
sim_update_actuator(actuator_id);
125
#endif
126
#endif
127
}
128
129
void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value)
130
{
131
#if HAL_PWM_COUNT > 0
132
const SRV_Channel::Function function = SRV_Channel::Function(SRV_Channel::k_rcin1 + actuator_id - 1);
133
SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5));
134
135
// Add to mask of channels that will be cleared if no commands are received
136
actuator.mask |= SRV_Channels::get_output_channel_mask(function);
137
138
rcout_has_new_data_to_update = true;
139
#if AP_SIM_ENABLED
140
sim_update_actuator(actuator_id);
141
#endif
142
#endif
143
}
144
145
void AP_Periph_FW::rcout_handle_safety_state(uint8_t safety_state)
146
{
147
if (safety_state == 255) {
148
hal.rcout->force_safety_off();
149
} else {
150
hal.rcout->force_safety_on();
151
}
152
rcout_has_new_data_to_update = true;
153
}
154
155
void AP_Periph_FW::rcout_update()
156
{
157
uint32_t now_ms = AP_HAL::millis();
158
159
// Timeout for ESC commands
160
const uint16_t esc_timeout_ms = g.esc_command_timeout_ms >= 0 ? g.esc_command_timeout_ms : 0; // Don't allow negative timeouts!
161
const bool has_esc_rawcommand_timed_out = esc_timeout_ms != 0 && ((now_ms - last_esc_raw_command_ms) >= esc_timeout_ms);
162
if (last_esc_num_channels > 0 && has_esc_rawcommand_timed_out) {
163
// If we've seen ESCs previously, and a timeout has occurred, then zero the outputs
164
int16_t esc_output[last_esc_num_channels];
165
memset(esc_output, 0, sizeof(esc_output));
166
rcout_esc(esc_output, last_esc_num_channels);
167
168
// Don't need to run again until new commands have been received
169
last_esc_num_channels = 0;
170
}
171
172
// Timeout for servo actuator commands
173
const uint16_t servo_timeout_ms = g.servo_command_timeout_ms >= 0 ? g.servo_command_timeout_ms : 0; // Don't allow negative timeouts!
174
const bool has_servo_timed_out = servo_timeout_ms != 0 && ((now_ms - actuator.last_command_ms) >= servo_timeout_ms);
175
if (has_servo_timed_out && (actuator.mask != 0)) {
176
#if HAL_PWM_COUNT > 0
177
// Output 0 PWM for each channel in the mask
178
for (uint8_t i = 0; i < HAL_PWM_COUNT; i++) {
179
if (((1U<<i) & actuator.mask) != 0) {
180
SRV_Channels::set_output_pwm_chan(i, 0);
181
}
182
}
183
184
// register that the output has been changed
185
rcout_has_new_data_to_update = true;
186
#endif
187
188
// Don't need to run again until new commands have been received
189
actuator.mask = 0;
190
}
191
192
if (!rcout_has_new_data_to_update) {
193
return;
194
}
195
rcout_has_new_data_to_update = false;
196
197
auto &srv = AP::srv();
198
SRV_Channels::calc_pwm();
199
srv.cork();
200
SRV_Channels::output_ch_all();
201
srv.push();
202
#if HAL_WITH_ESC_TELEM
203
if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) {
204
last_esc_telem_update_ms = now_ms;
205
esc_telem_update();
206
}
207
#if AP_EXTENDED_ESC_TELEM_ENABLED
208
esc_telem_extended_update(now_ms);
209
#endif
210
#endif
211
}
212
213
#if AP_SIM_ENABLED
214
/*
215
update simulation of servos, sending actuator status
216
*/
217
void AP_Periph_FW::sim_update_actuator(uint8_t actuator_id)
218
{
219
sim_actuator.mask |= 1U << (actuator_id - 1);
220
221
// send status at 10Hz
222
const uint32_t period_ms = 100;
223
const uint32_t now_ms = AP_HAL::millis();
224
225
if (now_ms - sim_actuator.last_send_ms < period_ms) {
226
return;
227
}
228
sim_actuator.last_send_ms = now_ms;
229
230
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
231
if ((sim_actuator.mask & (1U<<i)) == 0) {
232
continue;
233
}
234
const SRV_Channel::Function function = SRV_Channel::Function(SRV_Channel::k_rcin1 + i);
235
uavcan_equipment_actuator_Status pkt {};
236
pkt.actuator_id = i + 1;
237
// assume 45 degree angle for simulation
238
pkt.position = radians(SRV_Channels::get_output_norm(function) * 45);
239
pkt.force = 0;
240
pkt.speed = 0;
241
pkt.power_rating_pct = UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN;
242
243
uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];
244
uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !canfdout());
245
246
canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,
247
UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,
248
CANARD_TRANSFER_PRIORITY_LOW,
249
&buffer[0],
250
total_size);
251
}
252
}
253
#endif // AP_SIM_ENABLED
254
255
#endif // AP_PERIPH_RC_OUT_ENABLED
256
257