CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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