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/libraries/AP_ESC_Telem/AP_ESC_Telem.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
16
#include "AP_ESC_Telem.h"
17
#include <AP_HAL/AP_HAL.h>
18
#include <GCS_MAVLink/GCS.h>
19
#include <AP_Logger/AP_Logger.h>
20
21
#if HAL_WITH_ESC_TELEM
22
23
#include <AP_BoardConfig/AP_BoardConfig.h>
24
#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>
25
26
#include <AP_Math/AP_Math.h>
27
28
//#define ESC_TELEM_DEBUG
29
30
#define ESC_RPM_CHECK_TIMEOUT_US 210000UL // timeout for motor running validity
31
32
extern const AP_HAL::HAL& hal;
33
34
// table of user settable parameters
35
const AP_Param::GroupInfo AP_ESC_Telem::var_info[] = {
36
37
// @Param: _MAV_OFS
38
// @DisplayName: ESC Telemetry mavlink offset
39
// @Description: Offset to apply to ESC numbers when reporting as ESC_TELEMETRY packets over MAVLink. This allows high numbered motors to be displayed as low numbered ESCs for convenience on GCS displays. A value of 4 would send ESC on output 5 as ESC number 1 in ESC_TELEMETRY packets
40
// @Increment: 1
41
// @Range: 0 31
42
// @User: Standard
43
AP_GROUPINFO("_MAV_OFS", 1, AP_ESC_Telem, mavlink_offset, 0),
44
45
AP_GROUPEND
46
};
47
48
AP_ESC_Telem::AP_ESC_Telem()
49
{
50
if (_singleton) {
51
AP_HAL::panic("Too many AP_ESC_Telem instances");
52
}
53
_singleton = this;
54
#if !defined(IOMCU_FW)
55
AP_Param::setup_object_defaults(this, var_info);
56
#endif
57
}
58
59
// return the average motor RPM
60
float AP_ESC_Telem::get_average_motor_rpm(uint32_t servo_channel_mask) const
61
{
62
float rpm_avg = 0.0f;
63
uint8_t valid_escs = 0;
64
65
// average the rpm of each motor
66
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
67
if (BIT_IS_SET(servo_channel_mask,i)) {
68
float rpm;
69
if (get_rpm(i, rpm)) {
70
rpm_avg += rpm;
71
valid_escs++;
72
}
73
}
74
}
75
76
if (valid_escs > 0) {
77
rpm_avg /= valid_escs;
78
}
79
80
return rpm_avg;
81
}
82
83
// return all the motor frequencies in Hz for dynamic filtering
84
uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) const
85
{
86
uint8_t valid_escs = 0;
87
88
// average the rpm of each motor as reported by BLHeli and convert to Hz
89
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS && valid_escs < nfreqs; i++) {
90
float rpm;
91
if (get_rpm(i, rpm)) {
92
freqs[valid_escs++] = rpm * (1.0f / 60.0f);
93
} else if (was_rpm_data_ever_reported(_rpm_data[i])) {
94
// if we have ever received data on an ESC, mark it as valid but with no data
95
// this prevents large frequency shifts when ESCs disappear
96
freqs[valid_escs++] = 0.0f;
97
}
98
}
99
100
return MIN(valid_escs, nfreqs);
101
}
102
103
// get mask of ESCs that sent valid telemetry and/or rpm data in the last
104
// ESC_TELEM_DATA_TIMEOUT_MS/ESC_RPM_DATA_TIMEOUT_US
105
uint32_t AP_ESC_Telem::get_active_esc_mask() const {
106
uint32_t ret = 0;
107
const uint32_t now = AP_HAL::millis();
108
uint32_t now_us = AP_HAL::micros();
109
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
110
if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {
111
// have never seen telem from this ESC
112
continue;
113
}
114
if (_telem_data[i].stale(now)
115
&& !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {
116
continue;
117
}
118
ret |= (1U << i);
119
}
120
return ret;
121
}
122
123
// return an active ESC for the purposes of reporting (e.g. in the OSD)
124
uint8_t AP_ESC_Telem::get_max_rpm_esc() const
125
{
126
uint32_t ret = 0;
127
float max_rpm = 0;
128
const uint32_t now = AP_HAL::millis();
129
const uint32_t now_us = AP_HAL::micros();
130
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
131
if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {
132
// have never seen telem from this ESC
133
continue;
134
}
135
if (_telem_data[i].stale(now)
136
&& !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {
137
continue;
138
}
139
if (_rpm_data[i].rpm > max_rpm) {
140
max_rpm = _rpm_data[i].rpm;
141
ret = i;
142
}
143
}
144
return ret;
145
}
146
147
// return number of active ESCs present
148
uint8_t AP_ESC_Telem::get_num_active_escs() const {
149
uint32_t active = get_active_esc_mask();
150
return __builtin_popcount(active);
151
}
152
153
// return the whether all the motors in servo_channel_mask are running
154
bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const
155
{
156
const uint32_t now = AP_HAL::micros();
157
158
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
159
if (BIT_IS_SET(servo_channel_mask, i)) {
160
const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i];
161
// we choose a relatively strict measure of health so that failsafe actions can rely on the results
162
if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_CHECK_TIMEOUT_US)) {
163
return false;
164
}
165
if (rpmdata.rpm < min_rpm) {
166
return false;
167
}
168
if ((max_rpm > 0) && (rpmdata.rpm > max_rpm)) {
169
return false;
170
}
171
}
172
}
173
return true;
174
}
175
176
// is telemetry active for the provided channel mask
177
bool AP_ESC_Telem::is_telemetry_active(uint32_t servo_channel_mask) const
178
{
179
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
180
if (BIT_IS_SET(servo_channel_mask, i)) {
181
// no data received
182
if (get_last_telem_data_ms(i) == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {
183
return false;
184
}
185
}
186
}
187
return true;
188
}
189
190
// get an individual ESC's slewed rpm if available, returns true on success
191
bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const
192
{
193
if (esc_index >= ESC_TELEM_MAX_ESCS) {
194
return false;
195
}
196
197
const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];
198
199
if (is_zero(rpmdata.update_rate_hz)) {
200
return false;
201
}
202
203
const uint32_t now = AP_HAL::micros();
204
if (rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) {
205
const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f));
206
rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew);
207
208
#if AP_SCRIPTING_ENABLED
209
if ((1U<<esc_index) & rpm_scale_mask) {
210
rpm *= rpm_scale_factor[esc_index];
211
}
212
#endif
213
214
return true;
215
}
216
return false;
217
}
218
219
// get an individual ESC's raw rpm if available, returns true on success
220
bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const
221
{
222
if (esc_index >= ESC_TELEM_MAX_ESCS) {
223
return false;
224
}
225
226
const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];
227
228
const uint32_t now = AP_HAL::micros();
229
230
if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) {
231
return false;
232
}
233
234
rpm = rpmdata.rpm;
235
return true;
236
}
237
238
// get an individual ESC's temperature in centi-degrees if available, returns true on success
239
bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const
240
{
241
if (esc_index >= ESC_TELEM_MAX_ESCS) {
242
return false;
243
}
244
245
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
246
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL)) {
247
return false;
248
}
249
temp = telemdata.temperature_cdeg;
250
return true;
251
}
252
253
// get an individual motor's temperature in centi-degrees if available, returns true on success
254
bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const
255
{
256
if (esc_index >= ESC_TELEM_MAX_ESCS) {
257
return false;
258
}
259
260
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
261
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL)) {
262
return false;
263
}
264
temp = telemdata.motor_temp_cdeg;
265
return true;
266
}
267
268
// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC
269
bool AP_ESC_Telem::get_highest_temperature(int16_t& temp) const
270
{
271
uint8_t valid_escs = 0;
272
273
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
274
int16_t temp_temp;
275
if (get_temperature(i, temp_temp)) {
276
temp = MAX(temp, temp_temp);
277
valid_escs++;
278
}
279
}
280
281
return valid_escs > 0;
282
}
283
284
// get an individual ESC's current in Ampere if available, returns true on success
285
bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const
286
{
287
if (esc_index >= ESC_TELEM_MAX_ESCS) {
288
return false;
289
}
290
291
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
292
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CURRENT)) {
293
return false;
294
}
295
amps = telemdata.current;
296
return true;
297
}
298
299
// get an individual ESC's voltage in Volt if available, returns true on success
300
bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const
301
{
302
if (esc_index >= ESC_TELEM_MAX_ESCS) {
303
return false;
304
}
305
306
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
307
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)) {
308
return false;
309
}
310
volts = telemdata.voltage;
311
return true;
312
}
313
314
// get an individual ESC's energy consumption in milli-Ampere.hour if available, returns true on success
315
bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah) const
316
{
317
if (esc_index >= ESC_TELEM_MAX_ESCS) {
318
return false;
319
}
320
321
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
322
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION)) {
323
return false;
324
}
325
consumption_mah = telemdata.consumption_mah;
326
return true;
327
}
328
329
// get an individual ESC's usage time in seconds if available, returns true on success
330
bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_index, uint32_t& usage_s) const
331
{
332
if (esc_index >= ESC_TELEM_MAX_ESCS) {
333
return false;
334
}
335
336
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
337
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::USAGE)) {
338
return false;
339
}
340
usage_s = telemdata.usage_s;
341
return true;
342
}
343
344
#if AP_EXTENDED_ESC_TELEM_ENABLED
345
// get an individual ESC's input duty cycle if available, returns true on success
346
bool AP_ESC_Telem::get_input_duty(uint8_t esc_index, uint8_t& input_duty) const
347
{
348
if (esc_index >= ESC_TELEM_MAX_ESCS) {
349
return false;
350
}
351
352
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
353
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY)) {
354
return false;
355
}
356
input_duty = telemdata.input_duty;
357
return true;
358
}
359
360
// get an individual ESC's output duty cycle if available, returns true on success
361
bool AP_ESC_Telem::get_output_duty(uint8_t esc_index, uint8_t& output_duty) const
362
{
363
if (esc_index >= ESC_TELEM_MAX_ESCS) {
364
return false;
365
}
366
367
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
368
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY)) {
369
return false;
370
}
371
output_duty = telemdata.output_duty;
372
return true;
373
}
374
375
// get an individual ESC's status flags if available, returns true on success
376
bool AP_ESC_Telem::get_flags(uint8_t esc_index, uint32_t& flags) const
377
{
378
if (esc_index >= ESC_TELEM_MAX_ESCS) {
379
return false;
380
}
381
382
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
383
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::FLAGS)) {
384
return false;
385
}
386
flags = telemdata.flags;
387
return true;
388
}
389
390
// get an individual ESC's percentage of output power if available, returns true on success
391
bool AP_ESC_Telem::get_power_percentage(uint8_t esc_index, uint8_t& power_percentage) const
392
{
393
if (esc_index >= ESC_TELEM_MAX_ESCS) {
394
return false;
395
}
396
397
const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];
398
if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE)) {
399
return false;
400
}
401
power_percentage = telemdata.power_percentage;
402
return true;
403
}
404
#endif // AP_EXTENDED_ESC_TELEM_ENABLED
405
406
// send ESC telemetry messages over MAVLink
407
void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)
408
{
409
#if HAL_GCS_ENABLED
410
if (!_have_data) {
411
// we've never had any data
412
return;
413
}
414
415
const uint32_t now = AP_HAL::millis();
416
const uint32_t now_us = AP_HAL::micros();
417
418
// loop through groups of 4 ESCs
419
const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1);
420
421
// ensure we send out partially-full groups:
422
const uint8_t num_idx = (ESC_TELEM_MAX_ESCS + 3) / 4;
423
424
for (uint8_t idx = 0; idx < num_idx; idx++) {
425
const uint8_t i = (next_idx + idx) % num_idx;
426
427
// return if no space in output buffer to send mavlink messages
428
if (!HAVE_PAYLOAD_SPACE((mavlink_channel_t)mav_chan, ESC_TELEMETRY_1_TO_4)) {
429
// not enough mavlink buffer space, start at this index next time
430
next_idx = i;
431
return;
432
}
433
434
bool all_stale = true;
435
for (uint8_t j=0; j<4; j++) {
436
const uint8_t esc_id = (i * 4 + j) + esc_offset;
437
if (esc_id < ESC_TELEM_MAX_ESCS &&
438
(!_telem_data[esc_id].stale(now) ||
439
rpm_data_within_timeout(_rpm_data[esc_id], now_us, ESC_RPM_DATA_TIMEOUT_US))) {
440
all_stale = false;
441
break;
442
}
443
}
444
if (all_stale) {
445
// skip this group of ESCs if no data to send
446
continue;
447
}
448
449
450
// arrays to hold output
451
mavlink_esc_telemetry_1_to_4_t s {};
452
453
// fill in output arrays
454
for (uint8_t j = 0; j < 4; j++) {
455
const uint8_t esc_id = (i * 4 + j) + esc_offset;
456
if (esc_id >= ESC_TELEM_MAX_ESCS) {
457
continue;
458
}
459
volatile AP_ESC_Telem_Backend::TelemetryData const &telemdata = _telem_data[esc_id];
460
461
s.temperature[j] = telemdata.temperature_cdeg / 100;
462
s.voltage[j] = constrain_float(telemdata.voltage * 100.0f, 0, UINT16_MAX);
463
s.current[j] = constrain_float(telemdata.current * 100.0f, 0, UINT16_MAX);
464
s.totalcurrent[j] = constrain_float(telemdata.consumption_mah, 0, UINT16_MAX);
465
float rpmf;
466
if (get_rpm(esc_id, rpmf)) {
467
s.rpm[j] = constrain_float(rpmf, 0, UINT16_MAX);
468
}
469
s.count[j] = telemdata.count;
470
}
471
472
// make sure a msg hasn't been extended
473
static_assert(MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN &&
474
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN &&
475
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN &&
476
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN &&
477
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN &&
478
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN &&
479
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN &&
480
MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN,
481
"telem messages not compatible");
482
483
const mavlink_channel_t chan = (mavlink_channel_t)mav_chan;
484
// send messages
485
switch (i) {
486
case 0:
487
mavlink_msg_esc_telemetry_1_to_4_send_struct(chan, &s);
488
break;
489
case 1:
490
mavlink_msg_esc_telemetry_5_to_8_send_struct(chan, (const mavlink_esc_telemetry_5_to_8_t *)&s);
491
break;
492
case 2:
493
mavlink_msg_esc_telemetry_9_to_12_send_struct(chan, (const mavlink_esc_telemetry_9_to_12_t *)&s);
494
break;
495
case 3:
496
mavlink_msg_esc_telemetry_13_to_16_send_struct(chan, (const mavlink_esc_telemetry_13_to_16_t *)&s);
497
break;
498
#if ESC_TELEM_MAX_ESCS > 16
499
case 4:
500
mavlink_msg_esc_telemetry_17_to_20_send_struct(chan, (const mavlink_esc_telemetry_17_to_20_t *)&s);
501
break;
502
case 5:
503
mavlink_msg_esc_telemetry_21_to_24_send_struct(chan, (const mavlink_esc_telemetry_21_to_24_t *)&s);
504
break;
505
case 6:
506
mavlink_msg_esc_telemetry_25_to_28_send_struct(chan, (const mavlink_esc_telemetry_25_to_28_t *)&s);
507
break;
508
case 7:
509
mavlink_msg_esc_telemetry_29_to_32_send_struct(chan, (const mavlink_esc_telemetry_29_to_32_t *)&s);
510
break;
511
#endif
512
}
513
}
514
// we checked for all sends without running out of buffer space,
515
// start at zero next time
516
next_idx = 0;
517
518
#endif // HAL_GCS_ENABLED
519
}
520
521
// record an update to the telemetry data together with timestamp
522
// this should be called by backends when new telemetry values are available
523
void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask)
524
{
525
// rpm and telemetry data are not protected by a semaphore even though updated from different threads
526
// all data is per-ESC and only written from the update thread and read by the user thread
527
// each element is a primitive type and the timestamp is only updated at the end, thus a caller
528
// can only get slightly more up-to-date information that perhaps they were expecting or might
529
// read data that has just gone stale - both of these are safe and avoid the overhead of locking
530
531
if (esc_index >= ESC_TELEM_MAX_ESCS || data_mask == 0) {
532
return;
533
}
534
535
_have_data = true;
536
volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[esc_index];
537
538
#if AP_TEMPERATURE_SENSOR_ENABLED
539
// always allow external data. Block "internal" if external has ever its ever been set externally then ignore normal "internal" updates
540
const bool has_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL) ||
541
((data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) && !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL));
542
543
const bool has_motor_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL) ||
544
((data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE) && !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL));
545
#else
546
const bool has_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);
547
const bool has_motor_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE);
548
#endif
549
550
if (has_temperature) {
551
telemdata.temperature_cdeg = new_data.temperature_cdeg;
552
}
553
if (has_motor_temperature) {
554
telemdata.motor_temp_cdeg = new_data.motor_temp_cdeg;
555
}
556
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) {
557
telemdata.voltage = new_data.voltage;
558
}
559
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::CURRENT) {
560
telemdata.current = new_data.current;
561
}
562
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION) {
563
telemdata.consumption_mah = new_data.consumption_mah;
564
}
565
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::USAGE) {
566
telemdata.usage_s = new_data.usage_s;
567
}
568
569
#if AP_EXTENDED_ESC_TELEM_ENABLED
570
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY) {
571
telemdata.input_duty = new_data.input_duty;
572
}
573
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY) {
574
telemdata.output_duty = new_data.output_duty;
575
}
576
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) {
577
telemdata.flags = new_data.flags;
578
}
579
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE) {
580
telemdata.power_percentage = new_data.power_percentage;
581
}
582
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
583
584
#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
585
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS) {
586
telemdata.edt2_status = merge_edt2_status(telemdata.edt2_status, new_data.edt2_status);
587
}
588
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS) {
589
telemdata.edt2_stress = merge_edt2_stress(telemdata.edt2_stress, new_data.edt2_stress);
590
}
591
#endif
592
593
telemdata.count++;
594
telemdata.types |= data_mask;
595
telemdata.last_update_ms = AP_HAL::millis();
596
}
597
598
// record an update to the RPM together with timestamp, this allows the notch values to be slewed
599
// this should be called by backends when new telemetry values are available
600
void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate)
601
{
602
if (esc_index >= ESC_TELEM_MAX_ESCS) {
603
return;
604
}
605
606
_have_data = true;
607
608
const uint32_t now = MAX(1U ,AP_HAL::micros()); // don't allow a value of 0 in, as we use this as a flag in places
609
volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];
610
const auto last_update_us = rpmdata.last_update_us;
611
612
rpmdata.prev_rpm = rpmdata.rpm;
613
rpmdata.rpm = new_rpm;
614
rpmdata.update_rate_hz = 1.0e6f / constrain_uint32((now - last_update_us), 100, 1000000U*10U); // limit the update rate 0.1Hz to 10KHz
615
rpmdata.last_update_us = now;
616
rpmdata.error_rate = error_rate;
617
rpmdata.data_valid = true;
618
619
#ifdef ESC_TELEM_DEBUG
620
hal.console->printf("RPM: rate=%.1fhz, rpm=%f)\n", rpmdata.update_rate_hz, new_rpm);
621
#endif
622
}
623
624
#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
625
626
// The following is based on https://github.com/bird-sanctuary/extended-dshot-telemetry.
627
// For the following part we explain the bits of Extended DShot Telemetry v2 status telemetry:
628
// - bits 0-3: the "stress level"
629
// - bit 5: the "error" bit (e.g. the stall event in Bluejay)
630
// - bit 6: the "warning" bit (e.g. the desync event in Bluejay)
631
// - bit 7: the "alert" bit (e.g. the demag event in Bluejay)
632
633
// Since logger can read out telemetry values less frequently than they are updated,
634
// it makes sense to aggregate these status bits, and to collect the maximum observed stress level.
635
// To reduce the logging rate of the EDT2 messages, we will try to log them only once a new frame comes.
636
// To track this, we are going to (ab)use bit 15 of the field: 1 means there is something to write.
637
638
// EDTv2 also features separate "stress" messages.
639
// These come more frequently, and are scaled differently (the allowed range is from 0 to 255),
640
// so we have to log them separately.
641
642
constexpr uint16_t EDT2_TELEM_UPDATED = 0x8000U;
643
constexpr uint16_t EDT2_STRESS_0F_MASK = 0xfU;
644
constexpr uint16_t EDT2_STRESS_FF_MASK = 0xffU;
645
constexpr uint16_t EDT2_ERROR_MASK = 0x20U;
646
constexpr uint16_t EDT2_WARNING_MASK = 0x40U;
647
constexpr uint16_t EDT2_ALERT_MASK = 0x80U;
648
constexpr uint16_t EDT2_ALL_BITS = EDT2_ERROR_MASK | EDT2_WARNING_MASK | EDT2_ALERT_MASK;
649
650
#define EDT2_HAS_NEW_DATA(status) bool((status) & EDT2_TELEM_UPDATED)
651
#define EDT2_STRESS_FROM_STATUS(status) uint8_t((status) & EDT2_STRESS_0F_MASK)
652
#define EDT2_ERROR_BIT_FROM_STATUS(status) bool((status) & EDT2_ERROR_MASK)
653
#define EDT2_WARNING_BIT_FROM_STATUS(status) bool((status) & EDT2_WARNING_MASK)
654
#define EDT2_ALERT_BIT_FROM_STATUS(status) bool((status) & EDT2_ALERT_MASK)
655
#define EDT2_STRESS_FROM_STRESS(stress) uint8_t((stress) & EDT2_STRESS_FF_MASK)
656
657
uint16_t AP_ESC_Telem::merge_edt2_status(uint16_t old_status, uint16_t new_status)
658
{
659
if (EDT2_HAS_NEW_DATA(old_status)) {
660
new_status = uint16_t(
661
(old_status & ~EDT2_STRESS_0F_MASK) | // old status except for the stress is preserved
662
(new_status & EDT2_ALL_BITS) | // all new status bits are included
663
MAX(old_status & EDT2_STRESS_0F_MASK, new_status & EDT2_STRESS_0F_MASK) // the stress is maxed out
664
);
665
}
666
return EDT2_TELEM_UPDATED | new_status;
667
}
668
669
uint16_t AP_ESC_Telem::merge_edt2_stress(uint16_t old_stress, uint16_t new_stress)
670
{
671
if (EDT2_HAS_NEW_DATA(old_stress)) {
672
new_stress = uint16_t(
673
MAX(old_stress & EDT2_STRESS_FF_MASK, new_stress & EDT2_STRESS_FF_MASK) // the stress is maxed out
674
);
675
}
676
return EDT2_TELEM_UPDATED | new_stress;
677
}
678
679
#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
680
681
void AP_ESC_Telem::update()
682
{
683
#if HAL_LOGGING_ENABLED
684
AP_Logger *logger = AP_Logger::get_singleton();
685
const uint64_t now_us64 = AP_HAL::micros64();
686
687
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
688
const volatile AP_ESC_Telem_Backend::RpmData &rpmdata = _rpm_data[i];
689
volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i];
690
// Push received telemetry data into the logging system
691
if (logger && logger->logging_enabled()) {
692
if (telemdata.last_update_ms != _last_telem_log_ms[i]
693
|| rpmdata.last_update_us != _last_rpm_log_us[i]) {
694
695
// Update last log timestamps
696
_last_telem_log_ms[i] = telemdata.last_update_ms;
697
_last_rpm_log_us[i] = rpmdata.last_update_us;
698
699
float rpm = AP::logger().quiet_nanf();
700
get_rpm(i, rpm);
701
float raw_rpm = AP::logger().quiet_nanf();
702
get_raw_rpm(i, raw_rpm);
703
704
// Write ESC status messages
705
// id starts from 0
706
// rpm, raw_rpm is eRPM (in RPM units)
707
// voltage is in Volt
708
// current is in Ampere
709
// esc_temp is in centi-degrees Celsius
710
// current_tot is in milli-Ampere hours
711
// motor_temp is in centi-degrees Celsius
712
// error_rate is in percentage
713
const struct log_Esc pkt{
714
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)),
715
time_us : now_us64,
716
instance : i,
717
rpm : rpm,
718
raw_rpm : raw_rpm,
719
voltage : telemdata.voltage,
720
current : telemdata.current,
721
esc_temp : telemdata.temperature_cdeg,
722
current_tot : telemdata.consumption_mah,
723
motor_temp : telemdata.motor_temp_cdeg,
724
error_rate : rpmdata.error_rate
725
};
726
AP::logger().WriteBlock(&pkt, sizeof(pkt));
727
728
#if AP_EXTENDED_ESC_TELEM_ENABLED
729
// Write ESC extended status messages
730
// id: starts from 0
731
// input duty: duty cycle input to the ESC in percent
732
// output duty: duty cycle output to the motor in percent
733
// status flags: manufacurer-specific status flags
734
const bool has_ext_data = telemdata.types &
735
(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY |
736
AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY |
737
AP_ESC_Telem_Backend::TelemetryType::FLAGS |
738
AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE);
739
if (has_ext_data) {
740
// @LoggerMessage: ESCX
741
// @Description: ESC extended telemetry data
742
// @Field: TimeUS: Time since system startup
743
// @Field: Instance: starts from 0
744
// @Field: inpct: input duty cycle in percent
745
// @Field: outpct: output duty cycle in percent
746
// @Field: flags: manufacturer-specific status flags
747
// @Field: Pwr: Power percentage
748
AP::logger().WriteStreaming("ESCX",
749
"TimeUS,Instance,inpct,outpct,flags,Pwr",
750
"s" "#" "%" "%" "-" "%",
751
"F" "-" "-" "-" "-" "-",
752
"Q" "B" "B" "B" "I" "B",
753
AP_HAL::micros64(),
754
i,
755
telemdata.input_duty,
756
telemdata.output_duty,
757
telemdata.flags,
758
telemdata.power_percentage);
759
}
760
#endif //AP_EXTENDED_ESC_TELEM_ENABLED
761
762
#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
763
// Write an EDTv2 message, if there is any update
764
uint16_t edt2_status = telemdata.edt2_status;
765
uint16_t edt2_stress = telemdata.edt2_stress;
766
if (EDT2_HAS_NEW_DATA(edt2_status | edt2_stress)) {
767
// Could probably be faster/smaller with bitmasking, but not sure
768
uint8_t status = 0;
769
if (EDT2_HAS_NEW_DATA(edt2_stress)) {
770
status |= uint8_t(log_Edt2_Status::HAS_STRESS_DATA);
771
}
772
if (EDT2_HAS_NEW_DATA(edt2_status)) {
773
status |= uint8_t(log_Edt2_Status::HAS_STATUS_DATA);
774
}
775
if (EDT2_ALERT_BIT_FROM_STATUS(edt2_status)) {
776
status |= uint8_t(log_Edt2_Status::ALERT_BIT);
777
}
778
if (EDT2_WARNING_BIT_FROM_STATUS(edt2_status)) {
779
status |= uint8_t(log_Edt2_Status::WARNING_BIT);
780
}
781
if (EDT2_ERROR_BIT_FROM_STATUS(edt2_status)) {
782
status |= uint8_t(log_Edt2_Status::ERROR_BIT);
783
}
784
// An EDT2 status message is:
785
// id: starts from 0
786
// stress: the current stress which comes from edt2_stress
787
// max_stress: the maximum stress which comes from edt2_status
788
// status: the status bits which come from both
789
const struct log_Edt2 pkt_edt2{
790
LOG_PACKET_HEADER_INIT(uint8_t(LOG_EDT2_MSG)),
791
time_us : now_us64,
792
instance : i,
793
stress : EDT2_STRESS_FROM_STRESS(edt2_stress),
794
max_stress : EDT2_STRESS_FROM_STATUS(edt2_status),
795
status : status,
796
};
797
if (AP::logger().WriteBlock_first_succeed(&pkt_edt2, sizeof(pkt_edt2))) {
798
// Only clean the telem_updated bits if the write succeeded.
799
// This is important because, if rate limiting is enabled,
800
// the log-on-change behavior may lose a lot of entries
801
telemdata.edt2_status &= ~EDT2_TELEM_UPDATED;
802
telemdata.edt2_stress &= ~EDT2_TELEM_UPDATED;
803
}
804
}
805
#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
806
}
807
}
808
}
809
#endif // HAL_LOGGING_ENABLED
810
811
const uint32_t now_us = AP_HAL::micros();
812
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
813
// Invalidate RPM data if not received for too long
814
if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) {
815
_rpm_data[i].data_valid = false;
816
}
817
}
818
}
819
820
bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us)
821
{
822
// easy case, has the time window been crossed so it's invalid
823
if ((now_us - instance.last_update_us) > timeout_us) {
824
return false;
825
}
826
// we never got a valid data, to it's invalid
827
if (instance.last_update_us == 0) {
828
return false;
829
}
830
// check if things generally expired on us, this is done to handle time wrapping
831
return instance.data_valid;
832
}
833
834
bool AP_ESC_Telem::was_rpm_data_ever_reported(const volatile AP_ESC_Telem_Backend::RpmData &instance)
835
{
836
return instance.last_update_us > 0;
837
}
838
839
#if AP_SCRIPTING_ENABLED
840
/*
841
set RPM scale factor from script
842
*/
843
void AP_ESC_Telem::set_rpm_scale(const uint8_t esc_index, const float scale_factor)
844
{
845
if (esc_index < ESC_TELEM_MAX_ESCS) {
846
rpm_scale_factor[esc_index] = scale_factor;
847
rpm_scale_mask |= (1U<<esc_index);
848
}
849
}
850
#endif
851
852
AP_ESC_Telem *AP_ESC_Telem::_singleton = nullptr;
853
854
/*
855
* Get the AP_ESC_Telem singleton
856
*/
857
AP_ESC_Telem *AP_ESC_Telem::get_singleton()
858
{
859
return AP_ESC_Telem::_singleton;
860
}
861
862
namespace AP {
863
864
AP_ESC_Telem &esc_telem()
865
{
866
return *AP_ESC_Telem::get_singleton();
867
}
868
869
};
870
871
#endif // HAL_WITH_ESC_TELEM
872
873