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_FETtecOneWire/AP_FETtecOneWire.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
/* Initial protocol implementation was provided by FETtec */
17
/* Strongly modified by Amilcar Lucas, IAV GmbH */
18
19
#include <AP_Math/AP_Math.h>
20
#include <AP_SerialManager/AP_SerialManager.h>
21
#include <SRV_Channel/SRV_Channel.h>
22
#include <GCS_MAVLink/GCS.h>
23
24
#include "AP_FETtecOneWire.h"
25
#if AP_FETTEC_ONEWIRE_ENABLED
26
27
extern const AP_HAL::HAL& hal;
28
29
// Set to 0 when no ESC hardware is available and you want to test the UART send function
30
#ifndef HAL_AP_FETTEC_CONFIGURE_ESCS
31
#define HAL_AP_FETTEC_CONFIGURE_ESCS 1
32
#endif
33
34
#if HAL_AP_FETTEC_HALF_DUPLEX
35
static constexpr uint32_t HALF_DUPLEX_BAUDRATE = 2000000;
36
#endif
37
static constexpr uint32_t FULL_DUPLEX_BAUDRATE = 500000;
38
39
const AP_Param::GroupInfo AP_FETtecOneWire::var_info[] {
40
41
// @Param: MASK
42
// @DisplayName: Servo channel output bitmask
43
// @Description: Servo channel mask specifying FETtec ESC output.
44
// @Bitmask: 0:SERVO1,1:SERVO2,2:SERVO3,3:SERVO4,4:SERVO5,5:SERVO6,6:SERVO7,7:SERVO8,8:SERVO9,9:SERVO10,10:SERVO11,11:SERVO12
45
// @RebootRequired: True
46
// @User: Standard
47
AP_GROUPINFO_FLAGS("MASK", 1, AP_FETtecOneWire, _motor_mask_parameter, 0, AP_PARAM_FLAG_ENABLE),
48
49
// @Param: RVMASK
50
// @DisplayName: Servo channel reverse rotation bitmask
51
// @Description: Servo channel mask to reverse rotation of FETtec ESC outputs.
52
// @Bitmask: 0:SERVO1,1:SERVO2,2:SERVO3,3:SERVO4,4:SERVO5,5:SERVO6,6:SERVO7,7:SERVO8,8:SERVO9,9:SERVO10,10:SERVO11,11:SERVO12
53
// @User: Standard
54
AP_GROUPINFO("RVMASK", 2, AP_FETtecOneWire, _reverse_mask_parameter, 0),
55
56
#if HAL_WITH_ESC_TELEM
57
// @Param: POLES
58
// @DisplayName: Nr. electrical poles
59
// @Description: Number of motor electrical poles
60
// @Range: 2 50
61
// @User: Standard
62
AP_GROUPINFO("POLES", 3, AP_FETtecOneWire, _pole_count_parameter, 14),
63
#endif
64
65
AP_GROUPEND
66
};
67
68
AP_FETtecOneWire *AP_FETtecOneWire::_singleton;
69
70
AP_FETtecOneWire::AP_FETtecOneWire()
71
{
72
AP_Param::setup_object_defaults(this, var_info);
73
74
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
75
if (_singleton != nullptr) {
76
AP_HAL::panic("AP_FETtecOneWire must be singleton");
77
}
78
#endif
79
_singleton = this;
80
}
81
82
/**
83
initialize the serial port
84
85
*/
86
void AP_FETtecOneWire::init_uart()
87
{
88
if (_uart != nullptr) {
89
return;
90
}
91
const AP_SerialManager& serial_manager = AP::serialmanager();
92
_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FETtecOneWire, 0);
93
if (_uart == nullptr) {
94
return; // no serial port available, so nothing to do here
95
}
96
_uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
97
_uart->set_unbuffered_writes(true);
98
99
uint32_t uart_baud { FULL_DUPLEX_BAUDRATE };
100
#if HAL_AP_FETTEC_HALF_DUPLEX
101
if (_uart->get_options() & _uart->OPTION_HDPLEX) { //Half-Duplex is enabled
102
_use_hdplex = true;
103
uart_baud = HALF_DUPLEX_BAUDRATE;
104
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FTW using Half-Duplex");
105
} else {
106
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FTW using Full-Duplex");
107
}
108
#endif
109
110
_uart->begin(uart_baud);
111
}
112
113
/// initialize the device driver: configure serial port, wake-up and configure ESCs
114
void AP_FETtecOneWire::init()
115
{
116
init_uart();
117
if (_uart == nullptr) {
118
return; // no serial port available, so nothing to do here
119
}
120
121
_motor_mask = uint32_t(_motor_mask_parameter); // take a copy that will not change after we leave this function
122
_esc_count = __builtin_popcount(_motor_mask);
123
#if HAL_WITH_ESC_TELEM
124
// OneWire supports telemetry in at most 15 ESCs, because of the 4 bit limitation
125
// on the fast-throttle command. But we are still limited to the
126
// number of ESCs the telem library will collect data for.
127
if (_esc_count == 0 || _motor_mask >= (1U << MIN(15, ESC_TELEM_MAX_ESCS))) {
128
#else
129
// OneWire supports at most 24 ESCs without telemetry
130
if (_esc_count == 0 || _motor_mask >= (1U << MIN(24, NUM_SERVO_CHANNELS))) {
131
#endif
132
_invalid_mask = true;
133
return;
134
}
135
136
// we have a uart and the desired ESC combination id valid, allocate some memory:
137
_escs = NEW_NOTHROW ESC[_esc_count];
138
if (_escs == nullptr) {
139
return;
140
}
141
142
// initialise ESC ids. This enforces that the FETtec ESC ids
143
// inside FETtec ESCs need to be contiguous and start at ID 1
144
// which is required by fast-throttle commands.
145
uint8_t esc_offset = 0; // offset into our device-driver dynamically-allocated array of ESCs
146
uint8_t esc_id = 1; // ESC ids inside FETtec protocol are one-indexed
147
uint8_t servo_chan_offset = 0; // offset into _motor_mask_parameter array
148
for (uint32_t mask = _motor_mask; mask != 0; mask >>= 1, servo_chan_offset++) {
149
if (mask & 0x1) {
150
_escs[esc_offset].servo_ofs = servo_chan_offset;
151
_escs[esc_offset].id = esc_id++;
152
esc_offset++;
153
}
154
}
155
_invalid_mask = false; // mask is good
156
157
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FETtec: allocated %u motors", _esc_count);
158
159
// We expect to be able to send a fast-throttle command in each loop.
160
// 8 bits - OneWire Header
161
// 4 bits - telemetry request
162
// 11 bits - throttle value per ESC
163
// 8 bits - frame CRC
164
const uint16_t net_bit_count = 8 + 4 + (_esc_count * 11) + 8;
165
// 7 dummy for rounding up the division by 8
166
const uint16_t fast_throttle_byte_count = (net_bit_count + 7)/8;
167
uint16_t telemetry_byte_count { 0U };
168
#if HAL_WITH_ESC_TELEM
169
// Telemetry is fetched from each loop in turn.
170
telemetry_byte_count = sizeof(u.packed_tlm) + 1; // assume 9 pause bits between TX and RX
171
_fast_throttle_byte_count = fast_throttle_byte_count;
172
#endif
173
uint32_t uart_baud { FULL_DUPLEX_BAUDRATE };
174
#if HAL_AP_FETTEC_HALF_DUPLEX
175
if (_use_hdplex == true) { //Half-Duplex is enabled
176
uart_baud = HALF_DUPLEX_BAUDRATE;
177
}
178
#endif
179
_min_fast_throttle_period_us = (fast_throttle_byte_count + telemetry_byte_count) * 9 * 1000000 / uart_baud + 300; // 300us extra reserve
180
181
// tell SRV_Channels about ESC capabilities
182
// this is a bit soonish because we have not seen the ESCs on the bus yet,
183
// but saves us having to use a state variable to ensure doing this latter just once
184
SRV_Channels::set_digital_outputs(_motor_mask, 0);
185
186
_init_done = true;
187
}
188
189
/**
190
transmits data to ESCs
191
@param bytes bytes to transmit
192
@param length number of bytes to transmit
193
@return false there's no space in the UART for this message
194
*/
195
bool AP_FETtecOneWire::transmit(const uint8_t* bytes, const uint8_t length)
196
{
197
const uint32_t now = AP_HAL::micros();
198
if (now - _last_transmit_us < _min_fast_throttle_period_us) {
199
// in case the SRV_Channels::push() is running at very high rates, limit the period
200
// this function gets executed because FETtec needs a time gap between frames
201
// this also prevents one loop to do multiple actions, like reinitialize an ESC and sending a fast-throttle command without a gap.
202
_period_too_short++;
203
return false;
204
}
205
_last_transmit_us = now;
206
if (length > _uart->txspace()) {
207
return false;
208
}
209
210
_uart->write(bytes, length);
211
#if HAL_AP_FETTEC_HALF_DUPLEX
212
if (_use_hdplex) {
213
_ignore_own_bytes += length;
214
}
215
#endif
216
return true;
217
}
218
219
/**
220
transmits a config request to ESCs
221
@param bytes bytes to transmit
222
@param length number of bytes to transmit
223
@return false if vehicle is armed or if transmit(bytes, length) would return false
224
*/
225
bool AP_FETtecOneWire::transmit_config_request(const uint8_t* bytes, const uint8_t length)
226
{
227
if (hal.util->get_soft_armed()) {
228
return false;
229
}
230
return transmit(bytes, length);
231
}
232
233
/// shifts data to start of buffer based on magic header bytes
234
void AP_FETtecOneWire::move_frame_source_in_receive_buffer(const uint8_t search_start_pos)
235
{
236
uint8_t i;
237
for (i=search_start_pos; i<_receive_buf_used; i++) {
238
// FIXME: full-duplex should add MASTER here as we see our own data
239
if ((FrameSource)u.receive_buf[i] == FrameSource::BOOTLOADER ||
240
(FrameSource)u.receive_buf[i] == FrameSource::ESC) {
241
break;
242
}
243
}
244
consume_bytes(i);
245
}
246
247
/// cut n bytes from start of buffer
248
void AP_FETtecOneWire::consume_bytes(const uint8_t n)
249
{
250
if (n == 0) {
251
return;
252
}
253
// assure the length of the memmove is positive
254
if (_receive_buf_used < n) {
255
return;
256
}
257
memmove(u.receive_buf, &u.receive_buf[n], _receive_buf_used-n);
258
_receive_buf_used = _receive_buf_used - n;
259
}
260
261
/// returns true if the first message in the buffer is OK
262
bool AP_FETtecOneWire::buffer_contains_ok(const uint8_t length)
263
{
264
if (length != sizeof(u.packed_ok)) {
265
_message_invalid_in_state_count++;
266
return false;
267
}
268
if ((MsgType)u.packed_ok.msg.msgid != MsgType::OK) {
269
return false;
270
}
271
return true;
272
}
273
274
void AP_FETtecOneWire::handle_message(ESC &esc, const uint8_t length)
275
{
276
// only accept messages from the bootloader when we could
277
// legitimately get a message from the bootloader. Swipes the OK
278
// message for convenience
279
const FrameSource frame_source = (FrameSource)u.packed_ok.frame_source;
280
if (frame_source != FrameSource::ESC) {
281
if (esc.state != ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE) {
282
return;
283
}
284
}
285
286
switch (esc.state) {
287
case ESCState::UNINITIALISED:
288
case ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE:
289
return;
290
case ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE:
291
// "OK" is the only valid response
292
if (!buffer_contains_ok(length)) {
293
return;
294
}
295
switch (frame_source) {
296
case FrameSource::MASTER:
297
// probably half-duplex; should be caught before we get here
298
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
299
break;
300
case FrameSource::BOOTLOADER:
301
esc.set_state(ESCState::WANT_SEND_START_FW);
302
esc.is_awake = true;
303
break;
304
case FrameSource::ESC:
305
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
306
esc.set_state(ESCState::WANT_SEND_REQ_TYPE);
307
#else
308
#if HAL_WITH_ESC_TELEM
309
esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);
310
#else
311
esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);
312
#endif
313
#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
314
esc.is_awake = true;
315
break;
316
}
317
break;
318
319
case ESCState::WANT_SEND_START_FW:
320
return;
321
case ESCState::WAITING_OK_FOR_START_FW:
322
if (buffer_contains_ok(length)) {
323
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
324
esc.set_state(ESCState::WANT_SEND_REQ_TYPE);
325
#else
326
#if HAL_WITH_ESC_TELEM
327
esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);
328
#else
329
esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);
330
#endif
331
#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
332
}
333
break;
334
335
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
336
case ESCState::WANT_SEND_REQ_TYPE:
337
return;
338
case ESCState::WAITING_ESC_TYPE:
339
if (length != sizeof(u.packed_esc_type)) {
340
_message_invalid_in_state_count++;
341
return;
342
}
343
esc.type = u.packed_esc_type.msg.type;
344
esc.set_state(ESCState::WANT_SEND_REQ_SW_VER);
345
break;
346
347
case ESCState::WANT_SEND_REQ_SW_VER:
348
return;
349
case ESCState::WAITING_SW_VER:
350
if (length != sizeof(u.packed_sw_ver)) {
351
_message_invalid_in_state_count++;
352
return;
353
}
354
esc.firmware_version = u.packed_sw_ver.msg.version;
355
esc.firmware_subversion = u.packed_sw_ver.msg.subversion;
356
esc.set_state(ESCState::WANT_SEND_REQ_SN);
357
break;
358
359
case ESCState::WANT_SEND_REQ_SN:
360
return;
361
case ESCState::WAITING_SN:
362
if (length != sizeof(u.packed_sn)) {
363
_message_invalid_in_state_count++;
364
return;
365
}
366
static_assert(ARRAY_SIZE(u.packed_sn.msg.sn) == ARRAY_SIZE(esc.serial_number), "Serial number array length missmatch");
367
memcpy(esc.serial_number, u.packed_sn.msg.sn, ARRAY_SIZE(u.packed_sn.msg.sn));
368
#if HAL_WITH_ESC_TELEM
369
esc.set_state(ESCState::WANT_SEND_SET_TLM_TYPE);
370
#else
371
esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);
372
#endif
373
break;
374
#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
375
376
#if HAL_WITH_ESC_TELEM
377
case ESCState::WANT_SEND_SET_TLM_TYPE:
378
return;
379
case ESCState::WAITING_SET_TLM_TYPE_OK:
380
if (buffer_contains_ok(length)) {
381
esc.set_state(ESCState::WANT_SEND_SET_FAST_COM_LENGTH);
382
}
383
break;
384
#endif
385
386
case ESCState::WANT_SEND_SET_FAST_COM_LENGTH:
387
return;
388
case ESCState::WAITING_SET_FAST_COM_LENGTH_OK:
389
if (buffer_contains_ok(length)) {
390
esc.set_state(ESCState::RUNNING);
391
}
392
break;
393
case ESCState::RUNNING:
394
// we only expect telemetry messages in this state
395
#if HAL_WITH_ESC_TELEM
396
if (!esc.telem_expected) {
397
esc.unexpected_telem++;
398
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
399
AP_HAL::panic("unexpected telemetry");
400
#endif
401
return;
402
}
403
esc.telem_expected = false;
404
return handle_message_telem(esc);
405
#else
406
return;
407
#endif // HAL_WITH_ESC_TELEM
408
409
}
410
}
411
412
#if HAL_WITH_ESC_TELEM
413
void AP_FETtecOneWire::handle_message_telem(ESC &esc)
414
{
415
// the following two methods are coming from AP_ESC_Telem:
416
const TLM &tlm = u.packed_tlm.msg;
417
418
// update rpm and error rate
419
float error_rate_pct = 0;
420
if (_fast_throttle_cmd_count > _esc_count) {
421
error_rate_pct = (tlm.tx_err_count-esc.error_count_at_throttle_count_overflow)*(float)100/(float)_fast_throttle_cmd_count;
422
} else {
423
// the telemetry is requested in a round-robin, sequential fashion
424
// so the in the first _esc_count times all ESCs get to initialize this
425
esc.error_count_at_throttle_count_overflow = tlm.tx_err_count;
426
}
427
update_rpm(esc.servo_ofs,
428
tlm.rpm*(100*2/_pole_count_parameter),
429
error_rate_pct);
430
431
// update power and temperature telem data
432
TelemetryData t {};
433
t.temperature_cdeg = tlm.temp * 100;
434
t.voltage = tlm.voltage * 0.01f;
435
t.current = tlm.current * 0.01f;
436
t.consumption_mah = tlm.consumption_mah;
437
update_telem_data(
438
esc.servo_ofs,
439
t,
440
TelemetryType::TEMPERATURE|
441
TelemetryType::VOLTAGE|
442
TelemetryType::CURRENT|
443
TelemetryType::CONSUMPTION);
444
445
esc.last_telem_us = AP_HAL::micros();
446
}
447
#endif // HAL_WITH_ESC_TELEM
448
449
// reads data from the UART, calling handle_message on any message found
450
void AP_FETtecOneWire::read_data_from_uart()
451
{
452
/*
453
a frame looks like:
454
byte 1 = frame header (0x02 = bootloader, 0x03 = ESC firmware)
455
byte 2 = sender ID (5bit)
456
byte 3 & 4 = frame type (always 0x00, 0x00 used for bootloader. here just for compatibility)
457
byte 5 = frame length over all bytes
458
byte 6 - X = answer type, followed by the payload
459
byte X+1 = 8bit CRC
460
*/
461
462
#if HAL_AP_FETTEC_HALF_DUPLEX
463
//ignore own bytes
464
if (_use_hdplex) {
465
while (_ignore_own_bytes > 0 && _uart->available()) {
466
_ignore_own_bytes--;
467
_uart->read();
468
}
469
}
470
#endif
471
472
uint32_t bytes_to_read = MIN(_uart->available(), 128U);
473
uint32_t last_bytes_to_read = 0;
474
while (bytes_to_read &&
475
bytes_to_read != last_bytes_to_read) {
476
last_bytes_to_read = bytes_to_read;
477
478
// read as much from the uart as we can:
479
const uint8_t space = ARRAY_SIZE(u.receive_buf) - _receive_buf_used;
480
const uint32_t nbytes = _uart->read(&u.receive_buf[_receive_buf_used], space);
481
_receive_buf_used += nbytes;
482
bytes_to_read -= nbytes;
483
484
move_frame_source_in_receive_buffer();
485
486
// borrow the "OK" message to retrieve the frame length from the buffer:
487
const uint8_t frame_length = u.packed_ok.frame_length;
488
if (_receive_buf_used < frame_length) {
489
continue;
490
}
491
492
if (crc8_dvb_update(0, u.receive_buf, frame_length-1) != u.receive_buf[frame_length-1]) {
493
// bad message; shift away this frame_source byte to try to find
494
// another message
495
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
496
AP_HAL::panic("bad message");
497
#endif
498
crc_rec_err_cnt++;
499
move_frame_source_in_receive_buffer(1);
500
continue;
501
}
502
503
// borrow the "OK" message to retrieve the frame_source from the buffer:
504
const FrameSource frame_source = (FrameSource)u.packed_ok.frame_source;
505
if (frame_source == FrameSource::MASTER) {
506
// this is our own message - we'd best be running in
507
// half-duplex or we're in trouble!
508
consume_bytes(frame_length);
509
continue;
510
}
511
512
// borrow the "OK" message to retrieve the esc id from the buffer:
513
const uint8_t esc_id = u.packed_ok.esc_id;
514
bool handled = false;
515
// FIXME: we could scribble down the last ESC we sent a
516
// message to here and use it rather than doing this linear
517
// search:
518
for (uint8_t i=0; i<_esc_count; i++) {
519
auto &esc = _escs[i];
520
if (esc.id != esc_id) {
521
continue;
522
}
523
handle_message(esc, frame_length);
524
handled = true;
525
break;
526
}
527
if (!handled) {
528
_unknown_esc_message++;
529
}
530
531
consume_bytes(frame_length);
532
}
533
}
534
535
/**
536
packs a single fast-throttle command frame containing the throttle for all configured OneWire ESCs.
537
@param motor_values a 16bit array containing the throttle values that should be sent to the motors. 0-2000 where 1001-2000 is positive rotation and 0-999 reversed rotation
538
@param esc_id_to_request_telem_from the ESC to request telemetry from
539
*/
540
void AP_FETtecOneWire::pack_fast_throttle_command(const uint16_t *motor_values, uint8_t *fast_throttle_command, const uint8_t length, const uint8_t esc_id_to_request_telem_from)
541
{
542
// byte 1:
543
// bit 0,1,2,3 = ESC ID, Bit 4 = MSB bit of first ESC (11bit) throttle value, bit 5,6,7 = frame header
544
// so AAAABCCC
545
// A = ID from the ESC telemetry is requested from. ESC ID == 0 means no request.
546
// B = MSB from first throttle value
547
// C = frame header
548
fast_throttle_command[0] = esc_id_to_request_telem_from << 4; // 0 here means no telemetry request
549
fast_throttle_command[0] |= ((motor_values[0] >> 10) & 0x01) << 3;
550
fast_throttle_command[0] |= (uint8_t)FrameSource::MASTER;
551
552
// byte 2:
553
// AAABBBBB
554
// A = next 3 bits from (11bit) throttle value
555
// B = 5bit target ID
556
fast_throttle_command[1] = (((motor_values[0] >> 7) & 0x07)) << 5;
557
fast_throttle_command[1] |= 0x1F; // All IDs
558
559
// following bytes are the rest 7 bit of the first (11bit) throttle value,
560
// and all bits from all other throttle values, followed by the CRC byte
561
uint8_t mot = 0;
562
uint8_t bits_remaining_in_this_pwm = 7;
563
for (uint8_t out_byte_offset = 2; out_byte_offset<length; out_byte_offset++) {
564
if (bits_remaining_in_this_pwm >= 8) {
565
// const uint8_t mask = 0xFF << (11-bits_remaining_in_this_pwm);
566
fast_throttle_command[out_byte_offset] = (motor_values[mot] >> (bits_remaining_in_this_pwm-8)) & 0xFF;
567
bits_remaining_in_this_pwm -= 8;
568
} else {
569
const uint8_t mask = (1U<<bits_remaining_in_this_pwm)-1;
570
const uint8_t bits_to_copy_from_second_pwm = 8-bits_remaining_in_this_pwm;
571
fast_throttle_command[out_byte_offset] = (motor_values[mot] & mask) << bits_to_copy_from_second_pwm;
572
// move on to the next motor output
573
mot++;
574
if (mot < _esc_count) {
575
fast_throttle_command[out_byte_offset] |= motor_values[mot] >> (11-bits_to_copy_from_second_pwm);
576
}
577
bits_remaining_in_this_pwm = 11 - bits_to_copy_from_second_pwm;
578
}
579
}
580
581
fast_throttle_command[length-1] =
582
crc8_dvb_update(0, fast_throttle_command, length-1);
583
}
584
585
void AP_FETtecOneWire::escs_set_values(const uint16_t* motor_values)
586
{
587
uint8_t esc_id_to_request_telem_from = 0;
588
#if HAL_WITH_ESC_TELEM
589
ESC &esc_to_req_telem_from = _escs[_esc_ofs_to_request_telem_from++];
590
if (_esc_ofs_to_request_telem_from >= _esc_count) {
591
_esc_ofs_to_request_telem_from = 0;
592
}
593
esc_id_to_request_telem_from = esc_to_req_telem_from.id;
594
#endif
595
596
uint8_t fast_throttle_command[_fast_throttle_byte_count];
597
pack_fast_throttle_command(motor_values, fast_throttle_command, sizeof(fast_throttle_command), esc_id_to_request_telem_from);
598
599
#if HAL_AP_FETTEC_HALF_DUPLEX
600
// last byte of signal can be used to make sure the first TLM byte is correct, in case of spike corruption
601
// FIXME: use this somehow
602
_last_crc = fast_throttle_command[_fast_throttle_byte_count - 1];
603
#endif
604
605
// No command was yet sent, so no reply is expected and all information
606
// on the receive buffer is either garbage or noise. Discard it
607
_uart->discard_input();
608
_receive_buf_used = 0;
609
610
// send throttle commands to all configured ESCs in a single packet transfer
611
if (transmit(fast_throttle_command, sizeof(fast_throttle_command))) {
612
#if HAL_WITH_ESC_TELEM
613
esc_to_req_telem_from.telem_expected = true; // used to make sure that the returned telemetry comes from this ESC and not another
614
esc_to_req_telem_from.telem_requested = true; // used to check if this ESC is periodically sending telemetry
615
_fast_throttle_cmd_count++;
616
#endif
617
}
618
}
619
620
bool AP_FETtecOneWire::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const
621
{
622
if (_motor_mask_parameter == 0) {
623
return true; // No FETtec ESCs are expected, no need to run further pre-arm checks
624
}
625
626
if (_uart == nullptr) {
627
hal.util->snprintf(failure_msg, failure_msg_len, "No uart");
628
return false;
629
}
630
if (_invalid_mask) {
631
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid motor mask");
632
return false;
633
}
634
#if HAL_WITH_ESC_TELEM
635
if (_pole_count_parameter < 2) {
636
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid pole count %u", uint8_t(_pole_count_parameter));
637
return false;
638
}
639
uint8_t no_telem = 0;
640
const uint32_t now = AP_HAL::micros();
641
#endif
642
643
uint8_t not_running = 0;
644
for (uint8_t i=0; i<_esc_count; i++) {
645
auto &esc = _escs[i];
646
if (esc.state != ESCState::RUNNING) {
647
not_running++;
648
continue;
649
}
650
#if HAL_WITH_ESC_TELEM
651
if (now - esc.last_telem_us > max_telem_interval_us) {
652
no_telem++;
653
}
654
#endif
655
}
656
if (not_running != 0) {
657
hal.util->snprintf(failure_msg, failure_msg_len, "%u of %u ESCs are not running", not_running, _esc_count);
658
return false;
659
}
660
if (!_init_done) {
661
hal.util->snprintf(failure_msg, failure_msg_len, "Not initialised");
662
return false;
663
}
664
#if HAL_WITH_ESC_TELEM
665
if (no_telem != 0) {
666
hal.util->snprintf(failure_msg, failure_msg_len, "%u of %u ESCs are not sending telemetry", no_telem, _esc_count);
667
return false;
668
}
669
#endif
670
671
return true;
672
}
673
674
void AP_FETtecOneWire::configure_escs()
675
{
676
if (_uart->available()) {
677
// don't attempt to configure if we've unread data
678
return;
679
}
680
681
// note that we return as soon as we've transmitted anything in
682
// case we're in one-wire mode
683
for (uint8_t i=0; i<_esc_count; i++) {
684
auto &esc = _escs[i];
685
switch (esc.state) {
686
case ESCState::UNINITIALISED:
687
esc.state = ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE;
688
FALLTHROUGH;
689
case ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE:
690
// probe for bootloader or running firmware
691
if (transmit_config_request(PackedMessage<OK>{esc.id, OK{}})) {
692
esc.is_awake = false; // Assume the ESC is asleep or unavailable
693
esc.set_state(ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE);
694
}
695
return;
696
case ESCState::WAITING_OK_FOR_RUNNING_SW_TYPE:
697
if (!esc.is_awake) {
698
esc.set_state(ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE); // go back to try to wake up the ESC
699
}
700
return;
701
case ESCState::WANT_SEND_START_FW:
702
if (transmit_config_request(PackedMessage<START_FW>{esc.id, START_FW{}})) {
703
esc.set_state(ESCState::WAITING_OK_FOR_START_FW);
704
}
705
return;
706
case ESCState::WAITING_OK_FOR_START_FW:
707
return;
708
#if HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
709
case ESCState::WANT_SEND_REQ_TYPE:
710
if (transmit_config_request(PackedMessage<REQ_TYPE>{esc.id, REQ_TYPE{}})) {
711
esc.set_state(ESCState::WAITING_ESC_TYPE);
712
}
713
return;
714
case ESCState::WAITING_ESC_TYPE:
715
return;
716
case ESCState::WANT_SEND_REQ_SW_VER:
717
if (transmit_config_request(PackedMessage<REQ_SW_VER>{esc.id, REQ_SW_VER{}})) {
718
esc.set_state(ESCState::WAITING_SW_VER);
719
}
720
return;
721
case ESCState::WAITING_SW_VER:
722
return;
723
case ESCState::WANT_SEND_REQ_SN:
724
if (transmit_config_request(PackedMessage<REQ_SN>{esc.id, REQ_SN{}})) {
725
esc.set_state(ESCState::WAITING_SN);
726
}
727
return;
728
case ESCState::WAITING_SN:
729
return;
730
#endif // HAL_AP_FETTEC_ONEWIRE_GET_STATIC_INFO
731
#if HAL_WITH_ESC_TELEM
732
case ESCState::WANT_SEND_SET_TLM_TYPE:
733
if (transmit_config_request(PackedMessage<SET_TLM_TYPE>{esc.id, SET_TLM_TYPE{1}})) {
734
esc.set_state(ESCState::WAITING_SET_TLM_TYPE_OK);
735
}
736
return;
737
case ESCState::WAITING_SET_TLM_TYPE_OK:
738
return;
739
#endif
740
case ESCState::WANT_SEND_SET_FAST_COM_LENGTH:
741
if (transmit_config_request(PackedMessage<SET_FAST_COM_LENGTH>{esc.id,
742
SET_FAST_COM_LENGTH{
743
_fast_throttle_byte_count,
744
_escs[0].id,
745
_esc_count
746
}})) {
747
esc.set_state(ESCState::WAITING_SET_FAST_COM_LENGTH_OK);
748
}
749
return;
750
case ESCState::WAITING_SET_FAST_COM_LENGTH_OK:
751
return;
752
case ESCState::RUNNING:
753
_running_mask |= (1U << esc.servo_ofs);
754
break;
755
}
756
}
757
}
758
759
/// periodically called from SRV_Channels::push()
760
void AP_FETtecOneWire::update()
761
{
762
if (!_init_done) {
763
init();
764
return; // the rest of this function can only run after fully initted
765
}
766
767
// read all data from incoming serial:
768
read_data_from_uart();
769
770
const uint32_t now = AP_HAL::micros();
771
772
#if HAL_WITH_ESC_TELEM
773
if (!hal.util->get_soft_armed()) {
774
775
_reverse_mask = _reverse_mask_parameter; // update this only when disarmed
776
777
// if we haven't seen an ESC in a while, the user might
778
// have power-cycled them. Try re-initialising.
779
for (uint8_t i=0; i<_esc_count; i++) {
780
auto &esc = _escs[i];
781
if (!esc.telem_requested || now - esc.last_telem_us < 1000000U ) {
782
// telem OK
783
continue;
784
}
785
_running_mask &= ~(1U << esc.servo_ofs);
786
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "No telem from esc id=%u. Resetting it.", esc.id);
787
//GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "unknown %u, invalid %u, too short %u, unexpected: %u, crc_err %u", _unknown_esc_message, _message_invalid_in_state_count, _period_too_short, esc.unexpected_telem, crc_rec_err_cnt);
788
esc.set_state(ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE);
789
esc.telem_requested = false;
790
}
791
}
792
#endif // HAL_WITH_ESC_TELEM
793
794
if (now - _last_transmit_us < 700U) {
795
// in case the SRV_Channels::push() is running at very high rates, limit the period
796
// this function gets executed because FETtec needs a time gap between frames
797
_period_too_short++;
798
return;
799
}
800
801
#if defined(STM32F4)
802
if (_uart->tx_pending()) {
803
// there is unsent data in the send buffer,
804
// do not send more data because FETtec needs a time gap between frames
805
_period_too_short++;
806
return;
807
}
808
#endif
809
810
#if HAL_AP_FETTEC_CONFIGURE_ESCS
811
// run ESC configuration state machines if needed
812
if (_running_mask != _motor_mask) {
813
configure_escs();
814
return; // do not send fast-throttle command if a configuration command just got sent
815
}
816
#endif
817
818
// get ESC set points
819
uint16_t motor_pwm[_esc_count];
820
for (uint8_t i = 0; i < _esc_count; i++) {
821
const ESC &esc = _escs[i];
822
const SRV_Channel* c = SRV_Channels::srv_channel(esc.servo_ofs);
823
// check if safety switch has been pushed
824
if ( (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED)
825
|| (c == nullptr)) { // this should never ever happen, but just in case ...
826
motor_pwm[i] = 1000; // stop motor
827
continue;
828
}
829
motor_pwm[i] = constrain_int16(c->get_output_pwm(), 1000, 2000);
830
fet_debug("esc=%u in: %u", esc.id, motor_pwm[i]);
831
if (_reverse_mask & (1U << i)) {
832
motor_pwm[i] = 2000-motor_pwm[i];
833
}
834
}
835
836
// send motor setpoints to ESCs, and request for telemetry data
837
escs_set_values(motor_pwm);
838
}
839
840
#if HAL_AP_FETTEC_ESC_BEEP
841
/**
842
makes all connected ESCs beep
843
@param beep_frequency a 8 bit value from 0-255. higher make a higher beep
844
*/
845
void AP_FETtecOneWire::beep(const uint8_t beep_frequency)
846
{
847
for (uint8_t i=0; i<_esc_count; i++) {
848
auto &esc = _escs[i];
849
if (esc.state != ESCState::RUNNING) {
850
continue;
851
}
852
transmit_config_request(PackedMessage<Beep>{esc.id, Beep{beep_frequency}});
853
}
854
}
855
#endif // HAL_AP_FETTEC_ESC_BEEP
856
857
#if HAL_AP_FETTEC_ESC_LIGHT
858
/**
859
sets the racewire color for all ESCs
860
r = red brightness
861
g = green brightness
862
b = blue brightness
863
*/
864
void AP_FETtecOneWire::led_color(const uint8_t r, const uint8_t g, const uint8_t b)
865
{
866
for (uint8_t i=0; i<_esc_count; i++) {
867
auto &esc = _escs[i];
868
if (esc.state != ESCState::RUNNING) {
869
continue;
870
}
871
transmit_config_request(PackedMessage<LEDColour>{esc.id, LEDColour{r, g, b}});
872
}
873
}
874
#endif // HAL_AP_FETTEC_ESC_LIGHT
875
876
#endif // AP_FETTEC_ONEWIRE_ENABLED
877
878