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/can.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
AP_Periph can support
17
*/
18
19
#include <AP_HAL/AP_HAL.h>
20
#include <AP_Math/AP_Math.h>
21
#include <AP_HAL/AP_HAL_Boards.h>
22
#include "AP_Periph.h"
23
#include <stdio.h>
24
#include <drivers/stm32/canard_stm32.h>
25
#include <AP_HAL/I2CDevice.h>
26
#include <AP_HAL/utility/RingBuffer.h>
27
#include <AP_Common/AP_FWVersion.h>
28
#include <dronecan_msgs.h>
29
30
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
31
#include <hal.h>
32
#include <AP_HAL_ChibiOS/CANIface.h>
33
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
34
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
35
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
36
#include <AP_HAL_SITL/CANSocketIface.h>
37
#include <AP_HAL_SITL/AP_HAL_SITL.h>
38
#endif
39
40
#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U)
41
42
#include "i2c.h"
43
#include <utility>
44
45
#if HAL_NUM_CAN_IFACES >= 2
46
#include <AP_CANManager/AP_CANSensor.h>
47
#endif
48
49
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
50
extern const HAL_SITL &hal;
51
#else
52
extern const AP_HAL::HAL &hal;
53
#endif
54
55
extern AP_Periph_FW periph;
56
57
#ifndef HAL_PERIPH_LOOP_DELAY_US
58
// delay between can loop updates. This needs to be longer on F4
59
#if defined(STM32H7)
60
#define HAL_PERIPH_LOOP_DELAY_US 64
61
#else
62
#define HAL_PERIPH_LOOP_DELAY_US 1024
63
#endif
64
#endif
65
66
// timeout all frames at 1s
67
#define CAN_FRAME_TIMEOUT 1000000ULL
68
69
#define DEBUG_PKTS 0
70
71
#if HAL_PERIPH_CAN_MIRROR
72
#ifndef HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE
73
#define HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE 64
74
#endif
75
#endif //HAL_PERIPH_CAN_MIRROR
76
77
#ifndef HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF
78
// When enabled, can_printf() strings longer than the droneCAN max text length (90 chars)
79
// are split into multiple packets instead of truncating the string. This is
80
// especially helpful with HAL_GCS_ENABLED where libraries use the mavlink
81
// send_text() method where we support strings up to 256 chars by splitting them
82
// up into multiple 50 char mavlink packets.
83
#define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF (BOARD_FLASH_SIZE >= 1024)
84
#endif
85
86
static struct instance_t {
87
uint8_t index;
88
89
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
90
AP_HAL::CANIface* iface;
91
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
92
HALSITL::CANIface* iface;
93
#endif
94
95
#if HAL_PERIPH_CAN_MIRROR
96
#if HAL_NUM_CAN_IFACES < 2
97
#error "Can't use HAL_PERIPH_CAN_MIRROR if there are not at least 2 HAL_NUM_CAN_IFACES"
98
#endif
99
ObjectBuffer<AP_HAL::CANFrame> *mirror_queue;
100
uint8_t mirror_fail_count;
101
#endif // HAL_PERIPH_CAN_MIRROR
102
} instances[HAL_NUM_CAN_IFACES];
103
104
105
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) && (HAL_NUM_CAN_IFACES >= 2)
106
static ioline_t can_term_lines[] = {
107
HAL_GPIO_PIN_TERMCAN1
108
109
#if HAL_NUM_CAN_IFACES > 2
110
#ifdef HAL_GPIO_PIN_TERMCAN2
111
,HAL_GPIO_PIN_TERMCAN2
112
#else
113
#error "Only one Can Terminator defined with over two CAN Ifaces"
114
#endif
115
#endif
116
117
#if HAL_NUM_CAN_IFACES > 2
118
#ifdef HAL_GPIO_PIN_TERMCAN3
119
,HAL_GPIO_PIN_TERMCAN3
120
#else
121
#error "Only two Can Terminator defined with three CAN Ifaces"
122
#endif
123
#endif
124
125
};
126
#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1)
127
128
uint8_t user_set_node_id = HAL_CAN_DEFAULT_NODE_ID;
129
130
#ifndef AP_PERIPH_PROBE_CONTINUOUS
131
#define AP_PERIPH_PROBE_CONTINUOUS 0
132
#endif
133
134
#ifndef AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
135
#define AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz 1
136
#endif
137
138
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
139
ChibiOS::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];
140
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
141
HALSITL::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];
142
#endif
143
144
#if AP_CAN_SLCAN_ENABLED
145
SLCAN::CANIface AP_Periph_FW::slcan_interface;
146
#endif
147
148
#ifdef EXT_FLASH_SIZE_MB
149
static_assert(EXT_FLASH_SIZE_MB == 0, "DroneCAN bootloader cannot support external flash");
150
#endif
151
152
/*
153
* Node status variables
154
*/
155
static uavcan_protocol_NodeStatus node_status;
156
#if HAL_ENABLE_SENDING_STATS
157
static dronecan_protocol_Stats protocol_stats;
158
#endif
159
/**
160
* Returns a pseudo random integer in a given range
161
*/
162
static uint16_t get_random_range(uint16_t range)
163
{
164
return get_random16() % range;
165
}
166
167
168
/*
169
get cpu unique ID
170
*/
171
static void readUniqueID(uint8_t* out_uid)
172
{
173
uint8_t len = sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data);
174
memset(out_uid, 0, len);
175
hal.util->get_system_id_unformatted(out_uid, len);
176
}
177
178
179
/*
180
handle a GET_NODE_INFO request
181
*/
182
void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,
183
CanardRxTransfer* transfer)
184
{
185
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
186
uavcan_protocol_GetNodeInfoResponse pkt {};
187
188
node_status.uptime_sec = AP_HAL::millis() / 1000U;
189
190
pkt.status = node_status;
191
pkt.software_version.major = AP::fwversion().major;
192
pkt.software_version.minor = AP::fwversion().minor;
193
pkt.software_version.optional_field_flags = UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT | UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC;
194
pkt.software_version.vcs_commit = app_descriptor.git_hash;
195
uint32_t *crc = (uint32_t *)&pkt.software_version.image_crc;
196
crc[0] = app_descriptor.image_crc1;
197
crc[1] = app_descriptor.image_crc2;
198
199
readUniqueID(pkt.hardware_version.unique_id);
200
201
// use hw major/minor for APJ_BOARD_ID so we know what fw is
202
// compatible with this hardware
203
pkt.hardware_version.major = APJ_BOARD_ID >> 8;
204
pkt.hardware_version.minor = APJ_BOARD_ID & 0xFF;
205
206
if (g.serial_number > 0) {
207
hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s(%u)", CAN_APP_NODE_NAME, (unsigned)g.serial_number);
208
} else {
209
hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);
210
}
211
pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));
212
213
uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !canfdout());
214
215
canard_respond(canard_instance,
216
transfer,
217
UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
218
UAVCAN_PROTOCOL_GETNODEINFO_ID,
219
&buffer[0],
220
total_size);
221
}
222
223
// compatability code added Mar 2024 for 4.6:
224
#ifndef AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
225
#define AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED 1
226
#endif
227
228
/*
229
handle parameter GetSet request
230
*/
231
void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer)
232
{
233
// param fetch all can take a long time, so pat watchdog
234
stm32_watchdog_pat();
235
236
uavcan_protocol_param_GetSetRequest req;
237
if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) {
238
return;
239
}
240
241
uavcan_protocol_param_GetSetResponse pkt {};
242
243
AP_Param *vp;
244
enum ap_var_type ptype;
245
246
if (req.name.len != 0 && req.name.len > AP_MAX_NAME_SIZE) {
247
vp = nullptr;
248
} else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) {
249
memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);
250
#if AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
251
// cope with older versions of ArduPilot attempting to
252
// auto-configure AP_Periph using "GPS_TYPE" by
253
// auto-converting to "GPS1_TYPE":
254
if (strncmp((char*)req.name.data, "GPS_TYPE", req.name.len) == 0) {
255
vp = AP_Param::find("GPS1_TYPE", &ptype);
256
} else {
257
vp = AP_Param::find((char *)pkt.name.data, &ptype);
258
}
259
#else
260
vp = AP_Param::find((char *)pkt.name.data, &ptype);
261
#endif
262
} else {
263
AP_Param::ParamToken token {};
264
vp = AP_Param::find_by_index(req.index, &ptype, &token);
265
if (vp != nullptr) {
266
vp->copy_name_token(token, (char *)pkt.name.data, AP_MAX_NAME_SIZE+1, true);
267
}
268
}
269
if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) {
270
// param set
271
switch (ptype) {
272
case AP_PARAM_INT8:
273
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
274
return;
275
}
276
((AP_Int8 *)vp)->set_and_save_ifchanged(req.value.integer_value);
277
break;
278
case AP_PARAM_INT16:
279
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
280
return;
281
}
282
((AP_Int16 *)vp)->set_and_save_ifchanged(req.value.integer_value);
283
break;
284
case AP_PARAM_INT32:
285
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
286
return;
287
}
288
((AP_Int32 *)vp)->set_and_save_ifchanged(req.value.integer_value);
289
break;
290
case AP_PARAM_FLOAT:
291
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) {
292
return;
293
}
294
((AP_Float *)vp)->set_and_save_ifchanged(req.value.real_value);
295
break;
296
default:
297
return;
298
}
299
}
300
if (vp != nullptr) {
301
switch (ptype) {
302
case AP_PARAM_INT8:
303
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
304
pkt.value.integer_value = ((AP_Int8 *)vp)->get();
305
break;
306
case AP_PARAM_INT16:
307
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
308
pkt.value.integer_value = ((AP_Int16 *)vp)->get();
309
break;
310
case AP_PARAM_INT32:
311
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
312
pkt.value.integer_value = ((AP_Int32 *)vp)->get();
313
break;
314
case AP_PARAM_FLOAT:
315
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;
316
pkt.value.real_value = ((AP_Float *)vp)->get();
317
break;
318
default:
319
return;
320
}
321
pkt.name.len = strnlen((char *)pkt.name.data, sizeof(pkt.name.data));
322
}
323
324
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE];
325
uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout());
326
327
canard_respond(canard_instance,
328
transfer,
329
UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE,
330
UAVCAN_PROTOCOL_PARAM_GETSET_ID,
331
&buffer[0],
332
total_size);
333
}
334
335
/*
336
handle parameter executeopcode request
337
*/
338
void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer)
339
{
340
uavcan_protocol_param_ExecuteOpcodeRequest req;
341
if (uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &req)) {
342
return;
343
}
344
if (req.opcode == UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE) {
345
StorageManager::erase();
346
AP_Param::erase_all();
347
AP_Param::load_all();
348
AP_Param::setup_sketch_defaults();
349
#ifdef HAL_PERIPH_ENABLE_GPS
350
AP_Param::setup_object_defaults(&gps, gps.var_info);
351
#endif
352
#ifdef HAL_PERIPH_ENABLE_BATTERY
353
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
354
#endif
355
#ifdef HAL_PERIPH_ENABLE_MAG
356
AP_Param::setup_object_defaults(&compass, compass.var_info);
357
#endif
358
#ifdef HAL_PERIPH_ENABLE_BARO
359
AP_Param::setup_object_defaults(&baro, baro.var_info);
360
#endif
361
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
362
AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);
363
#endif
364
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
365
AP_Param::setup_object_defaults(&rangefinder, rangefinder.var_info);
366
#endif
367
}
368
369
uavcan_protocol_param_ExecuteOpcodeResponse pkt {};
370
371
pkt.ok = true;
372
373
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE];
374
uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout());
375
376
canard_respond(canard_instance,
377
transfer,
378
UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE,
379
UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID,
380
&buffer[0],
381
total_size);
382
}
383
384
void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer)
385
{
386
#if HAL_RAM_RESERVE_START >= 256
387
// setup information on firmware request at start of ram
388
auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
389
if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
390
memset(comms, 0, sizeof(*comms));
391
}
392
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
393
394
uavcan_protocol_file_BeginFirmwareUpdateRequest req;
395
if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) {
396
return;
397
}
398
399
comms->server_node_id = req.source_node_id;
400
if (comms->server_node_id == 0) {
401
comms->server_node_id = transfer->source_node_id;
402
}
403
memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len);
404
comms->my_node_id = canardGetLocalNodeID(canard_instance);
405
406
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
407
uavcan_protocol_file_BeginFirmwareUpdateResponse reply {};
408
reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK;
409
410
uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !canfdout());
411
canard_respond(canard_instance,
412
transfer,
413
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE,
414
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID,
415
&buffer[0],
416
total_size);
417
uint8_t count = 50;
418
while (count--) {
419
processTx();
420
hal.scheduler->delay(1);
421
}
422
#endif
423
424
// instant reboot, with backup register used to give bootloader
425
// the node_id
426
prepare_reboot();
427
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
428
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(canard_instance)));
429
NVIC_SystemReset();
430
#endif
431
}
432
433
void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer)
434
{
435
// Rule C - updating the randomized time interval
436
dronecan.send_next_node_id_allocation_request_at_ms =
437
AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
438
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
439
440
if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)
441
{
442
printf("Allocation request from another allocatee\n");
443
dronecan.node_id_allocation_unique_id_offset = 0;
444
return;
445
}
446
447
// Copying the unique ID from the message
448
uavcan_protocol_dynamic_node_id_Allocation msg;
449
450
if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) {
451
// failed decode
452
return;
453
}
454
455
// Obtaining the local unique ID
456
uint8_t my_unique_id[sizeof(msg.unique_id.data)];
457
readUniqueID(my_unique_id);
458
459
// Matching the received UID against the local one
460
if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {
461
printf("Mismatching allocation response\n");
462
dronecan.node_id_allocation_unique_id_offset = 0;
463
return; // No match, return
464
}
465
466
if (msg.unique_id.len < sizeof(msg.unique_id.data)) {
467
// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
468
dronecan.node_id_allocation_unique_id_offset = msg.unique_id.len;
469
dronecan.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
470
471
printf("Matching allocation response: %d\n", msg.unique_id.len);
472
} else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over)
473
// Allocation complete - copying the allocated node ID from the message
474
canardSetLocalNodeID(canard_instance, msg.node_id);
475
printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id);
476
477
#if defined(HAL_PERIPH_ENABLE_GPS) && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE
478
if (g.gps_mb_only_can_port) {
479
// we need to assign the unallocated port to be used for Moving Baseline only
480
gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES;
481
if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
482
// copy node id from the primary iface
483
canardSetLocalNodeID(&dronecan.canard, msg.node_id);
484
#ifdef HAL_GPIO_PIN_TERMCAN1
485
// also terminate the line as we don't have any other device on this port
486
palWriteLine(can_term_lines[gps_mb_can_port], 1);
487
#endif
488
}
489
}
490
#endif
491
}
492
}
493
494
495
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
496
static uint8_t safety_state;
497
498
/*
499
handle SafetyState
500
*/
501
void AP_Periph_FW::handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
502
{
503
ardupilot_indication_SafetyState req;
504
if (ardupilot_indication_SafetyState_decode(transfer, &req)) {
505
return;
506
}
507
safety_state = req.status;
508
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
509
rcout_handle_safety_state(safety_state);
510
#endif
511
}
512
#endif // HAL_GPIO_PIN_SAFE_LED
513
514
/*
515
handle ArmingStatus
516
*/
517
void AP_Periph_FW::handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer)
518
{
519
uavcan_equipment_safety_ArmingStatus req;
520
if (uavcan_equipment_safety_ArmingStatus_decode(transfer, &req)) {
521
return;
522
}
523
hal.util->set_soft_armed(req.status == UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED);
524
}
525
526
527
528
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
529
void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
530
{
531
#ifdef HAL_PERIPH_ENABLE_NOTIFY
532
notify.handle_rgb(red, green, blue);
533
#ifdef HAL_PERIPH_ENABLE_RC_OUT
534
rcout_has_new_data_to_update = true;
535
#endif // HAL_PERIPH_ENABLE_RC_OUT
536
#endif // HAL_PERIPH_ENABLE_NOTIFY
537
538
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
539
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);
540
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
541
#endif // HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
542
543
#ifdef HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
544
{
545
const uint8_t i2c_address = 0x38;
546
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
547
if (!dev) {
548
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
549
}
550
WITH_SEMAPHORE(dev->get_semaphore());
551
dev->set_retries(0);
552
uint8_t v = 0x3f; // enable LED
553
dev->transfer(&v, 1, nullptr, 0);
554
v = 0x40 | red >> 3; // red
555
dev->transfer(&v, 1, nullptr, 0);
556
v = 0x60 | green >> 3; // green
557
dev->transfer(&v, 1, nullptr, 0);
558
v = 0x80 | blue >> 3; // blue
559
dev->transfer(&v, 1, nullptr, 0);
560
}
561
#endif // HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
562
563
#ifdef HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY
564
{
565
const uint8_t i2c_address = 0x38;
566
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
567
if (!dev) {
568
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
569
}
570
WITH_SEMAPHORE(dev->get_semaphore());
571
dev->set_retries(0);
572
uint8_t v = 0x3f; // enable LED
573
dev->transfer(&v, 1, nullptr, 0);
574
v = 0x40 | blue >> 3; // blue
575
dev->transfer(&v, 1, nullptr, 0);
576
v = 0x60 | green >> 3; // green
577
dev->transfer(&v, 1, nullptr, 0);
578
v = 0x80 | red >> 3; // red
579
dev->transfer(&v, 1, nullptr, 0);
580
}
581
#endif // HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY
582
#ifdef HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY
583
{
584
#define TOSHIBA_LED_PWM0 0x01 // pwm0 register
585
#define TOSHIBA_LED_ENABLE 0x04 // enable register
586
#define TOSHIBA_LED_I2C_ADDR 0x55 // default I2C bus address
587
588
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_toshiba;
589
if (!dev_toshiba) {
590
dev_toshiba = std::move(hal.i2c_mgr->get_device(0, TOSHIBA_LED_I2C_ADDR));
591
}
592
WITH_SEMAPHORE(dev_toshiba->get_semaphore());
593
dev_toshiba->set_retries(0); // use 0 because this is running on main thread.
594
595
// enable the led
596
dev_toshiba->write_register(TOSHIBA_LED_ENABLE, 0x03);
597
598
/* 4-bit for each color */
599
uint8_t val[4] = {
600
TOSHIBA_LED_PWM0,
601
(uint8_t)(blue >> 4),
602
(uint8_t)(green / 16),
603
(uint8_t)(red / 16)
604
};
605
dev_toshiba->transfer(val, sizeof(val), nullptr, 0);
606
}
607
#endif // HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY
608
}
609
610
/*
611
handle lightscommand
612
*/
613
void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
614
{
615
uavcan_equipment_indication_LightsCommand req;
616
if (uavcan_equipment_indication_LightsCommand_decode(transfer, &req)) {
617
return;
618
}
619
for (uint8_t i=0; i<req.commands.len; i++) {
620
uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];
621
// to get the right color proportions we scale the green so that is uses the
622
// same number of bits as red and blue
623
uint8_t red = cmd.color.red<<3U;
624
uint8_t green = (cmd.color.green>>1U)<<3U;
625
uint8_t blue = cmd.color.blue<<3U;
626
#ifdef HAL_PERIPH_ENABLE_NOTIFY
627
const int8_t brightness = notify.get_rgb_led_brightness_percent();
628
#elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY)
629
const int8_t brightness = g.led_brightness;
630
#endif
631
if (brightness != 100 && brightness >= 0) {
632
const float scale = brightness * 0.01;
633
red = constrain_int16(red * scale, 0, 255);
634
green = constrain_int16(green * scale, 0, 255);
635
blue = constrain_int16(blue * scale, 0, 255);
636
}
637
set_rgb_led(red, green, blue);
638
}
639
}
640
#endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
641
642
#ifdef HAL_PERIPH_ENABLE_RC_OUT
643
void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
644
{
645
uavcan_equipment_esc_RawCommand cmd;
646
if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) {
647
return;
648
}
649
rcout_esc(cmd.cmd.data, cmd.cmd.len);
650
651
// Update internal copy for disabling output to ESC when CAN packets are lost
652
last_esc_num_channels = cmd.cmd.len;
653
last_esc_raw_command_ms = AP_HAL::millis();
654
}
655
656
void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer)
657
{
658
uavcan_equipment_actuator_ArrayCommand cmd;
659
if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) {
660
return;
661
}
662
663
for (uint8_t i=0; i < cmd.commands.len; i++) {
664
const auto &c = cmd.commands.data[i];
665
switch (c.command_type) {
666
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS:
667
rcout_srv_unitless(c.actuator_id, c.command_value);
668
break;
669
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM:
670
rcout_srv_PWM(c.actuator_id, c.command_value);
671
break;
672
}
673
}
674
}
675
#endif // HAL_PERIPH_ENABLE_RC_OUT
676
677
#if defined(HAL_PERIPH_ENABLE_NOTIFY)
678
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
679
{
680
ardupilot_indication_NotifyState msg;
681
if (ardupilot_indication_NotifyState_decode(transfer, &msg)) {
682
return;
683
}
684
if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) {
685
uint16_t tmp = 0;
686
memcpy(&tmp, msg.aux_data.data, sizeof(tmp));
687
yaw_earth = radians((float)tmp * 0.01f);
688
}
689
vehicle_state = msg.vehicle_state;
690
last_vehicle_state = AP_HAL::millis();
691
}
692
#endif // HAL_PERIPH_ENABLE_NOTIFY
693
694
#ifdef HAL_GPIO_PIN_SAFE_LED
695
/*
696
update safety LED
697
*/
698
void AP_Periph_FW::can_safety_LED_update(void)
699
{
700
static uint32_t last_update_ms;
701
switch (safety_state) {
702
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF:
703
palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON);
704
break;
705
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: {
706
uint32_t now = AP_HAL::millis();
707
if (now - last_update_ms > 100) {
708
last_update_ms = now;
709
static uint8_t led_counter;
710
const uint16_t led_pattern = 0x5500;
711
led_counter = (led_counter+1) % 16;
712
palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U << led_counter))?!SAFE_LED_ON:SAFE_LED_ON);
713
}
714
break;
715
}
716
default:
717
palWriteLine(HAL_GPIO_PIN_SAFE_LED, !SAFE_LED_ON);
718
break;
719
}
720
}
721
#endif // HAL_GPIO_PIN_SAFE_LED
722
723
724
#ifdef HAL_GPIO_PIN_SAFE_BUTTON
725
#ifndef HAL_SAFE_BUTTON_ON
726
#define HAL_SAFE_BUTTON_ON 1
727
#endif
728
/*
729
update safety button
730
*/
731
void AP_Periph_FW::can_safety_button_update(void)
732
{
733
static uint32_t last_update_ms;
734
static uint8_t counter;
735
uint32_t now = AP_HAL::millis();
736
// send at 10Hz when pressed
737
if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) {
738
counter = 0;
739
return;
740
}
741
if (now - last_update_ms < 100) {
742
return;
743
}
744
if (counter < 255) {
745
counter++;
746
}
747
748
last_update_ms = now;
749
ardupilot_indication_Button pkt {};
750
pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY;
751
pkt.press_time = counter;
752
753
uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE];
754
uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout());
755
756
canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE,
757
ARDUPILOT_INDICATION_BUTTON_ID,
758
CANARD_TRANSFER_PRIORITY_LOW,
759
&buffer[0],
760
total_size);
761
}
762
#endif // HAL_GPIO_PIN_SAFE_BUTTON
763
764
/**
765
* This callback is invoked by the library when a new message or request or response is received.
766
*/
767
void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
768
CanardRxTransfer* transfer)
769
{
770
#ifdef HAL_GPIO_PIN_LED_CAN1
771
palToggleLine(HAL_GPIO_PIN_LED_CAN1);
772
#endif
773
774
#if HAL_CANFD_SUPPORTED
775
// enable tao for decoding when not on CANFD
776
transfer->tao = !transfer->canfd;
777
#endif
778
779
/*
780
* Dynamic node ID allocation protocol.
781
* Taking this branch only if we don't have a node ID, ignoring otherwise.
782
*/
783
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) {
784
if (transfer->transfer_type == CanardTransferTypeBroadcast &&
785
transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
786
handle_allocation_response(canard_instance, transfer);
787
}
788
return;
789
}
790
791
switch (transfer->data_type_id) {
792
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
793
handle_get_node_info(canard_instance, transfer);
794
break;
795
796
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
797
handle_begin_firmware_update(canard_instance, transfer);
798
break;
799
800
case UAVCAN_PROTOCOL_RESTARTNODE_ID: {
801
printf("RestartNode\n");
802
uavcan_protocol_RestartNodeResponse pkt {
803
ok: true,
804
};
805
uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];
806
uint16_t total_size = uavcan_protocol_RestartNodeResponse_encode(&pkt, buffer, !canfdout());
807
canard_respond(canard_instance,
808
transfer,
809
UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE,
810
UAVCAN_PROTOCOL_RESTARTNODE_ID,
811
&buffer[0],
812
total_size);
813
814
// schedule a reboot to occur
815
reboot_request_ms = AP_HAL::millis();
816
}
817
break;
818
819
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
820
handle_param_getset(canard_instance, transfer);
821
break;
822
823
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
824
handle_param_executeopcode(canard_instance, transfer);
825
break;
826
827
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
828
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
829
handle_beep_command(canard_instance, transfer);
830
break;
831
#endif
832
833
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
834
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
835
handle_safety_state(canard_instance, transfer);
836
break;
837
#endif
838
839
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
840
handle_arming_status(canard_instance, transfer);
841
break;
842
843
#ifdef HAL_PERIPH_ENABLE_GPS
844
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
845
handle_RTCMStream(canard_instance, transfer);
846
break;
847
848
#if GPS_MOVING_BASELINE
849
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
850
handle_MovingBaselineData(canard_instance, transfer);
851
break;
852
#endif
853
#endif // HAL_PERIPH_ENABLE_GPS
854
855
#if AP_UART_MONITOR_ENABLED
856
case UAVCAN_TUNNEL_TARGETTED_ID:
857
handle_tunnel_Targetted(canard_instance, transfer);
858
break;
859
#endif
860
861
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
862
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
863
handle_lightscommand(canard_instance, transfer);
864
break;
865
#endif
866
867
#ifdef HAL_PERIPH_ENABLE_RC_OUT
868
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
869
handle_esc_rawcommand(canard_instance, transfer);
870
break;
871
872
case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:
873
handle_act_command(canard_instance, transfer);
874
break;
875
#endif
876
877
#ifdef HAL_PERIPH_ENABLE_NOTIFY
878
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
879
handle_notify_state(canard_instance, transfer);
880
break;
881
#endif
882
883
#ifdef HAL_PERIPH_ENABLE_RELAY
884
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
885
handle_hardpoint_command(canard_instance, transfer);
886
break;
887
#endif
888
889
}
890
}
891
892
/**
893
* This callback is invoked by the library when a new message or request or response is received.
894
*/
895
static void onTransferReceived_trampoline(CanardInstance* canard_instance,
896
CanardRxTransfer* transfer)
897
{
898
AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;
899
fw->onTransferReceived(canard_instance, transfer);
900
}
901
902
903
/**
904
* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received
905
* by the local node.
906
* If the callback returns true, the library will receive the transfer.
907
* If the callback returns false, the library will ignore the transfer.
908
* All transfers that are addressed to other nodes are always ignored.
909
*/
910
bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
911
uint64_t* out_data_type_signature,
912
uint16_t data_type_id,
913
CanardTransferType transfer_type,
914
uint8_t source_node_id)
915
{
916
(void)source_node_id;
917
918
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID)
919
{
920
/*
921
* If we're in the process of allocation of dynamic node ID, accept only relevant transfers.
922
*/
923
if ((transfer_type == CanardTransferTypeBroadcast) &&
924
(data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID))
925
{
926
*out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
927
return true;
928
}
929
return false;
930
}
931
932
switch (data_type_id) {
933
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
934
*out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE;
935
return true;
936
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
937
*out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE;
938
return true;
939
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
940
*out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;
941
return true;
942
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
943
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE;
944
return true;
945
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
946
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;
947
return true;
948
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
949
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
950
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
951
return true;
952
#endif
953
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
954
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
955
*out_data_type_signature = ARDUPILOT_INDICATION_SAFETYSTATE_SIGNATURE;
956
return true;
957
#endif
958
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
959
*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;
960
return true;
961
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
962
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
963
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
964
return true;
965
#endif
966
#ifdef HAL_PERIPH_ENABLE_GPS
967
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
968
*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;
969
return true;
970
971
#if GPS_MOVING_BASELINE
972
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
973
*out_data_type_signature = ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE;
974
return true;
975
#endif
976
#endif // HAL_PERIPH_ENABLE_GPS
977
978
#if AP_UART_MONITOR_ENABLED
979
case UAVCAN_TUNNEL_TARGETTED_ID:
980
*out_data_type_signature = UAVCAN_TUNNEL_TARGETTED_SIGNATURE;
981
return true;
982
#endif
983
984
#ifdef HAL_PERIPH_ENABLE_RC_OUT
985
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
986
*out_data_type_signature = UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE;
987
return true;
988
989
case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:
990
*out_data_type_signature = UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_SIGNATURE;
991
return true;
992
#endif
993
#if defined(HAL_PERIPH_ENABLE_NOTIFY)
994
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
995
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
996
return true;
997
#endif
998
#ifdef HAL_PERIPH_ENABLE_RELAY
999
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
1000
*out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE;
1001
return true;
1002
#endif
1003
default:
1004
break;
1005
}
1006
1007
return false;
1008
}
1009
1010
static bool shouldAcceptTransfer_trampoline(const CanardInstance* canard_instance,
1011
uint64_t* out_data_type_signature,
1012
uint16_t data_type_id,
1013
CanardTransferType transfer_type,
1014
uint8_t source_node_id)
1015
{
1016
AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;
1017
return fw->shouldAcceptTransfer(canard_instance, out_data_type_signature, data_type_id, transfer_type, source_node_id);
1018
}
1019
1020
void AP_Periph_FW::cleanup_stale_transactions(uint64_t timestamp_usec)
1021
{
1022
canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec);
1023
}
1024
1025
uint8_t *AP_Periph_FW::get_tid_ptr(uint32_t transfer_desc)
1026
{
1027
// check head
1028
if (!dronecan.tid_map_head) {
1029
dronecan.tid_map_head = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));
1030
if (dronecan.tid_map_head == nullptr) {
1031
return nullptr;
1032
}
1033
dronecan.tid_map_head->transfer_desc = transfer_desc;
1034
dronecan.tid_map_head->next = nullptr;
1035
return &dronecan.tid_map_head->tid;
1036
} else if (dronecan.tid_map_head->transfer_desc == transfer_desc) {
1037
return &dronecan.tid_map_head->tid;
1038
}
1039
1040
// search through the list for an existing entry
1041
dronecan_protocol_t::tid_map *tid_map_ptr = dronecan.tid_map_head;
1042
while(tid_map_ptr->next) {
1043
tid_map_ptr = tid_map_ptr->next;
1044
if (tid_map_ptr->transfer_desc == transfer_desc) {
1045
return &tid_map_ptr->tid;
1046
}
1047
}
1048
1049
// create a new entry, if not found
1050
tid_map_ptr->next = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));
1051
if (tid_map_ptr->next == nullptr) {
1052
return nullptr;
1053
}
1054
tid_map_ptr->next->transfer_desc = transfer_desc;
1055
tid_map_ptr->next->next = nullptr;
1056
return &tid_map_ptr->next->tid;
1057
}
1058
1059
bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature,
1060
uint16_t data_type_id,
1061
uint8_t priority,
1062
const void* payload,
1063
uint16_t payload_len,
1064
uint8_t iface_mask)
1065
{
1066
WITH_SEMAPHORE(canard_broadcast_semaphore);
1067
const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID;
1068
if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
1069
return false;
1070
}
1071
1072
uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(data_type_signature, data_type_id, 0, CANARD_BROADCAST_NODE_ID));
1073
if (tid_ptr == nullptr) {
1074
return false;
1075
}
1076
1077
// create transfer object
1078
CanardTxTransfer transfer_object = {
1079
.transfer_type = CanardTransferTypeBroadcast,
1080
.data_type_signature = data_type_signature,
1081
.data_type_id = data_type_id,
1082
.inout_transfer_id = tid_ptr,
1083
.priority = priority,
1084
.payload = (uint8_t*)payload,
1085
.payload_len = payload_len,
1086
#if CANARD_ENABLE_CANFD
1087
.canfd = is_dna? false : canfdout(),
1088
#endif
1089
.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,
1090
#if CANARD_MULTI_IFACE
1091
.iface_mask = iface_mask==0 ? uint8_t(IFACE_ALL) : iface_mask,
1092
#endif
1093
};
1094
const int16_t res = canardBroadcastObj(&dronecan.canard, &transfer_object);
1095
1096
#if DEBUG_PKTS
1097
if (res < 0) {
1098
can_printf("Tx error %d\n", res);
1099
}
1100
#endif
1101
#if HAL_ENABLE_SENDING_STATS
1102
if (res <= 0) {
1103
protocol_stats.tx_errors++;
1104
} else {
1105
protocol_stats.tx_frames += res;
1106
}
1107
#endif
1108
return res > 0;
1109
}
1110
1111
/*
1112
send a response
1113
*/
1114
bool AP_Periph_FW::canard_respond(CanardInstance* canard_instance,
1115
CanardRxTransfer *transfer,
1116
uint64_t data_type_signature,
1117
uint16_t data_type_id,
1118
const uint8_t *payload,
1119
uint16_t payload_len)
1120
{
1121
CanardTxTransfer transfer_object = {
1122
.transfer_type = CanardTransferTypeResponse,
1123
.data_type_signature = data_type_signature,
1124
.data_type_id = data_type_id,
1125
.inout_transfer_id = &transfer->transfer_id,
1126
.priority = transfer->priority,
1127
.payload = payload,
1128
.payload_len = payload_len,
1129
#if CANARD_ENABLE_CANFD
1130
.canfd = canfdout(),
1131
#endif
1132
.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,
1133
#if CANARD_MULTI_IFACE
1134
.iface_mask = IFACE_ALL,
1135
#endif
1136
};
1137
const auto res = canardRequestOrRespondObj(canard_instance,
1138
transfer->source_node_id,
1139
&transfer_object);
1140
#if DEBUG_PKTS
1141
if (res < 0) {
1142
can_printf("Tx error %d\n", res);
1143
}
1144
#endif
1145
#if HAL_ENABLE_SENDING_STATS
1146
if (res <= 0) {
1147
protocol_stats.tx_errors++;
1148
} else {
1149
protocol_stats.tx_frames += res;
1150
}
1151
#endif
1152
return res > 0;
1153
}
1154
1155
void AP_Periph_FW::processTx(void)
1156
{
1157
for (CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) {
1158
AP_HAL::CANFrame txmsg {};
1159
txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);
1160
memcpy(txmsg.data, txf->data, txf->data_len);
1161
txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);
1162
#if HAL_CANFD_SUPPORTED
1163
txmsg.canfd = txf->canfd;
1164
#endif
1165
// push message with 1s timeout
1166
bool sent = true;
1167
const uint64_t now_us = AP_HAL::micros64();
1168
const uint64_t deadline = now_us + 1000000U;
1169
// try sending to all interfaces
1170
for (auto &_ins : instances) {
1171
if (_ins.iface == NULL) {
1172
continue;
1173
}
1174
#if CANARD_MULTI_IFACE
1175
if (!(txf->iface_mask & (1U<<_ins.index))) {
1176
continue;
1177
}
1178
#endif
1179
#if HAL_NUM_CAN_IFACES >= 2
1180
if (can_protocol_cached[_ins.index] != AP_CAN::Protocol::DroneCAN) {
1181
continue;
1182
}
1183
#endif
1184
if (_ins.iface->send(txmsg, deadline, 0) <= 0) {
1185
/*
1186
We were not able to queue the frame for
1187
sending. Only mark the send as failing if the
1188
interface is active. We consider an interface as
1189
active if it has had a successful transmit in the
1190
last 2 seconds
1191
*/
1192
volatile const auto *stats = _ins.iface->get_statistics();
1193
uint64_t last_transmit_us = stats->last_transmit_us;
1194
if (stats == nullptr || AP_HAL::micros64() - last_transmit_us < 2000000UL) {
1195
sent = false;
1196
}
1197
} else {
1198
#if CANARD_MULTI_IFACE
1199
txf->iface_mask &= ~(1U<<_ins.index);
1200
#endif
1201
}
1202
}
1203
if (sent) {
1204
canardPopTxQueue(&dronecan.canard);
1205
dronecan.tx_fail_count = 0;
1206
} else {
1207
// exit and try again later. If we fail 8 times in a row
1208
// then cleanup any stale transfers to keep the queue from
1209
// filling
1210
if (dronecan.tx_fail_count < 8) {
1211
dronecan.tx_fail_count++;
1212
} else {
1213
#if HAL_ENABLE_SENDING_STATS
1214
protocol_stats.tx_errors++;
1215
#endif
1216
dronecan.tx_fail_count = 0;
1217
cleanup_stale_transactions(now_us);
1218
}
1219
break;
1220
}
1221
}
1222
}
1223
1224
#if HAL_ENABLE_SENDING_STATS
1225
void AP_Periph_FW::update_rx_protocol_stats(int16_t res)
1226
{
1227
switch (res) {
1228
case CANARD_OK:
1229
protocol_stats.rx_frames++;
1230
break;
1231
case -CANARD_ERROR_OUT_OF_MEMORY:
1232
protocol_stats.rx_error_oom++;
1233
break;
1234
case -CANARD_ERROR_INTERNAL:
1235
protocol_stats.rx_error_internal++;
1236
break;
1237
case -CANARD_ERROR_RX_INCOMPATIBLE_PACKET:
1238
protocol_stats.rx_ignored_not_wanted++;
1239
break;
1240
case -CANARD_ERROR_RX_WRONG_ADDRESS:
1241
protocol_stats.rx_ignored_wrong_address++;
1242
break;
1243
case -CANARD_ERROR_RX_NOT_WANTED:
1244
protocol_stats.rx_ignored_not_wanted++;
1245
break;
1246
case -CANARD_ERROR_RX_MISSED_START:
1247
protocol_stats.rx_error_missed_start++;
1248
break;
1249
case -CANARD_ERROR_RX_WRONG_TOGGLE:
1250
protocol_stats.rx_error_wrong_toggle++;
1251
break;
1252
case -CANARD_ERROR_RX_UNEXPECTED_TID:
1253
protocol_stats.rx_ignored_unexpected_tid++;
1254
break;
1255
case -CANARD_ERROR_RX_SHORT_FRAME:
1256
protocol_stats.rx_error_short_frame++;
1257
break;
1258
case -CANARD_ERROR_RX_BAD_CRC:
1259
protocol_stats.rx_error_bad_crc++;
1260
break;
1261
default:
1262
// mark all other errors as internal
1263
protocol_stats.rx_error_internal++;
1264
break;
1265
}
1266
}
1267
#endif
1268
1269
void AP_Periph_FW::processRx(void)
1270
{
1271
AP_HAL::CANFrame rxmsg;
1272
for (auto &instance : instances) {
1273
if (instance.iface == NULL) {
1274
continue;
1275
}
1276
#if HAL_NUM_CAN_IFACES >= 2
1277
if (can_protocol_cached[instance.index] != AP_CAN::Protocol::DroneCAN) {
1278
continue;
1279
}
1280
#endif
1281
while (true) {
1282
bool read_select = true;
1283
bool write_select = false;
1284
instance.iface->select(read_select, write_select, nullptr, 0);
1285
if (!read_select) { // No data pending
1286
break;
1287
}
1288
CanardCANFrame rx_frame {};
1289
1290
//palToggleLine(HAL_GPIO_PIN_LED);
1291
uint64_t timestamp;
1292
AP_HAL::CANIface::CanIOFlags flags;
1293
if (instance.iface->receive(rxmsg, timestamp, flags) <= 0) {
1294
break;
1295
}
1296
#if HAL_PERIPH_CAN_MIRROR
1297
for (auto &other_instance : instances) {
1298
if (other_instance.mirror_queue == nullptr) { // we aren't mirroring here, or failed on memory
1299
continue;
1300
}
1301
if (other_instance.index == instance.index) { // don't self add
1302
continue;
1303
}
1304
other_instance.mirror_queue->push(rxmsg);
1305
}
1306
#endif // HAL_PERIPH_CAN_MIRROR
1307
rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc);
1308
memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
1309
#if HAL_CANFD_SUPPORTED
1310
rx_frame.canfd = rxmsg.canfd;
1311
#endif
1312
rx_frame.id = rxmsg.id;
1313
#if CANARD_MULTI_IFACE
1314
rx_frame.iface_id = instance.index;
1315
#endif
1316
1317
const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp);
1318
#if HAL_ENABLE_SENDING_STATS
1319
if (res == -CANARD_ERROR_RX_MISSED_START) {
1320
// this might remaining frames from a message that we don't accept, so check
1321
uint64_t dummy_signature;
1322
if (shouldAcceptTransfer(&dronecan.canard,
1323
&dummy_signature,
1324
extractDataType(rx_frame.id),
1325
extractTransferType(rx_frame.id),
1326
1)) { // doesn't matter what we pass here
1327
update_rx_protocol_stats(res);
1328
} else {
1329
protocol_stats.rx_ignored_not_wanted++;
1330
}
1331
} else {
1332
update_rx_protocol_stats(res);
1333
}
1334
#else
1335
(void)res;
1336
#endif
1337
}
1338
}
1339
}
1340
1341
#if HAL_PERIPH_CAN_MIRROR
1342
void AP_Periph_FW::processMirror(void)
1343
{
1344
const uint64_t deadline = AP_HAL::micros64() + 1000000;
1345
1346
for (auto &ins : instances) {
1347
if (ins.iface == nullptr || ins.mirror_queue == nullptr) { // can't send on a null interface
1348
continue;
1349
}
1350
1351
const uint32_t pending = ins.mirror_queue->available();
1352
for (uint32_t i = 0; i < pending; i++) { // limit how long we can loop
1353
AP_HAL::CANFrame txmsg {};
1354
1355
if (!ins.mirror_queue->peek(txmsg)) {
1356
break;
1357
}
1358
1359
if (ins.iface->send(txmsg, deadline, 0) <= 0) {
1360
if (ins.mirror_fail_count < 8) {
1361
ins.mirror_fail_count++;
1362
} else {
1363
ins.mirror_queue->pop();
1364
}
1365
break;
1366
} else {
1367
ins.mirror_fail_count = 0;
1368
ins.mirror_queue->pop();
1369
}
1370
}
1371
}
1372
}
1373
#endif // HAL_PERIPH_CAN_MIRROR
1374
1375
uint16_t AP_Periph_FW::pool_peak_percent()
1376
{
1377
const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&dronecan.canard);
1378
const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks);
1379
return peak_percent;
1380
}
1381
1382
void AP_Periph_FW::node_status_send(void)
1383
{
1384
{
1385
uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];
1386
node_status.uptime_sec = AP_HAL::millis() / 1000U;
1387
1388
node_status.vendor_specific_status_code = MIN(hal.util->available_memory(), unsigned(UINT16_MAX));
1389
1390
uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !canfdout());
1391
1392
canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
1393
UAVCAN_PROTOCOL_NODESTATUS_ID,
1394
CANARD_TRANSFER_PRIORITY_LOW,
1395
buffer,
1396
len);
1397
}
1398
#if HAL_ENABLE_SENDING_STATS
1399
if (debug_option_is_set(AP_Periph_FW::DebugOptions::ENABLE_STATS)) {
1400
{
1401
uint8_t buffer[DRONECAN_PROTOCOL_STATS_MAX_SIZE];
1402
uint32_t len = dronecan_protocol_Stats_encode(&protocol_stats, buffer, !canfdout());
1403
canard_broadcast(DRONECAN_PROTOCOL_STATS_SIGNATURE,
1404
DRONECAN_PROTOCOL_STATS_ID,
1405
CANARD_TRANSFER_PRIORITY_LOWEST,
1406
buffer,
1407
len);
1408
}
1409
for (auto &instance : instances) {
1410
uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE];
1411
dronecan_protocol_CanStats can_stats;
1412
const AP_HAL::CANIface::bus_stats_t *bus_stats = instance.iface->get_statistics();
1413
if (bus_stats == nullptr) {
1414
return;
1415
}
1416
can_stats.interface = instance.index;
1417
can_stats.tx_requests = bus_stats->tx_requests;
1418
can_stats.tx_rejected = bus_stats->tx_rejected;
1419
can_stats.tx_overflow = bus_stats->tx_overflow;
1420
can_stats.tx_success = bus_stats->tx_success;
1421
can_stats.tx_timedout = bus_stats->tx_timedout;
1422
can_stats.tx_abort = bus_stats->tx_abort;
1423
can_stats.rx_received = bus_stats->rx_received;
1424
can_stats.rx_overflow = bus_stats->rx_overflow;
1425
can_stats.rx_errors = bus_stats->rx_errors;
1426
can_stats.busoff_errors = bus_stats->num_busoff_err;
1427
uint32_t len = dronecan_protocol_CanStats_encode(&can_stats, buffer, !canfdout());
1428
canard_broadcast(DRONECAN_PROTOCOL_CANSTATS_SIGNATURE,
1429
DRONECAN_PROTOCOL_CANSTATS_ID,
1430
CANARD_TRANSFER_PRIORITY_LOWEST,
1431
buffer,
1432
len);
1433
}
1434
}
1435
#endif
1436
}
1437
1438
1439
/**
1440
* This function is called at 1 Hz rate from the main loop.
1441
*/
1442
void AP_Periph_FW::process1HzTasks(uint64_t timestamp_usec)
1443
{
1444
/*
1445
* Purging transfers that are no longer transmitted. This will occasionally free up some memory.
1446
*/
1447
cleanup_stale_transactions(timestamp_usec);
1448
1449
/*
1450
* Printing the memory usage statistics.
1451
*/
1452
{
1453
/*
1454
* The recommended way to establish the minimal size of the memory pool is to stress-test the application and
1455
* record the worst case memory usage.
1456
*/
1457
1458
if (pool_peak_percent() > 70) {
1459
printf("WARNING: ENLARGE MEMORY POOL\n");
1460
}
1461
}
1462
1463
/*
1464
* Transmitting the node status message periodically.
1465
*/
1466
node_status_send();
1467
1468
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
1469
if (g.flash_bootloader.get()) {
1470
const uint8_t flash_bl = g.flash_bootloader.get();
1471
g.flash_bootloader.set_and_save_ifchanged(0);
1472
if (flash_bl == 42) {
1473
// magic developer value to test watchdog support with main loop lockup
1474
while (true) {
1475
can_printf("entering lockup\n");
1476
hal.scheduler->delay(100);
1477
}
1478
}
1479
if (flash_bl == 43) {
1480
// magic developer value to test watchdog support with hard fault
1481
can_printf("entering fault\n");
1482
void *foo = (void*)0xE000ED38;
1483
typedef void (*fptr)();
1484
fptr gptr = (fptr) (void *) foo;
1485
gptr();
1486
}
1487
EXPECT_DELAY_MS(2000);
1488
hal.scheduler->delay(1000);
1489
AP_HAL::Util::FlashBootloader res = hal.util->flash_bootloader();
1490
switch (res) {
1491
case AP_HAL::Util::FlashBootloader::OK:
1492
can_printf("Flash bootloader OK\n");
1493
break;
1494
case AP_HAL::Util::FlashBootloader::NO_CHANGE:
1495
can_printf("Bootloader unchanged\n");
1496
break;
1497
#if AP_SIGNED_FIRMWARE
1498
case AP_HAL::Util::FlashBootloader::NOT_SIGNED:
1499
can_printf("Bootloader not signed\n");
1500
break;
1501
#endif
1502
default:
1503
can_printf("Flash bootloader FAILED\n");
1504
break;
1505
}
1506
}
1507
#endif
1508
1509
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1510
if (hal.run_in_maintenance_mode()) {
1511
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;
1512
} else
1513
#endif
1514
{
1515
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL;
1516
}
1517
1518
#if 0
1519
// test code for watchdog reset
1520
if (AP_HAL::millis() > 15000) {
1521
while (true) ;
1522
}
1523
#endif
1524
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1525
if (AP_HAL::millis() > 30000) {
1526
// use RTC to mark that we have been running fine for
1527
// 30s. This is used along with watchdog resets to ensure the
1528
// user has a chance to load a fixed firmware
1529
set_fast_reboot(RTC_BOOT_FWOK);
1530
}
1531
#endif
1532
}
1533
1534
/*
1535
wait for dynamic allocation of node ID
1536
*/
1537
bool AP_Periph_FW::no_iface_finished_dna = true;
1538
1539
bool AP_Periph_FW::can_do_dna()
1540
{
1541
if (canardGetLocalNodeID(&dronecan.canard) != CANARD_BROADCAST_NODE_ID) {
1542
AP_Periph_FW::no_iface_finished_dna = false;
1543
return true;
1544
}
1545
1546
const uint32_t now = AP_HAL::millis();
1547
1548
if (AP_Periph_FW::no_iface_finished_dna) {
1549
printf("Waiting for dynamic node ID allocation %x... (pool %u)\n", IFACE_ALL, pool_peak_percent());
1550
}
1551
1552
dronecan.send_next_node_id_allocation_request_at_ms =
1553
now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
1554
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
1555
1556
// Structure of the request is documented in the DSDL definition
1557
// See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
1558
uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];
1559
allocation_request[0] = 0; // we are only called if the user has not set an ID, so request any ID
1560
1561
if (dronecan.node_id_allocation_unique_id_offset == 0) {
1562
allocation_request[0] |= 1; // First part of unique ID
1563
// set interface to try
1564
dronecan.dna_interface++;
1565
dronecan.dna_interface %= HAL_NUM_CAN_IFACES;
1566
}
1567
1568
uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)];
1569
readUniqueID(my_unique_id);
1570
1571
static const uint8_t MaxLenOfUniqueIDInRequest = 6;
1572
uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - dronecan.node_id_allocation_unique_id_offset);
1573
1574
if (uid_size > MaxLenOfUniqueIDInRequest) {
1575
uid_size = MaxLenOfUniqueIDInRequest;
1576
}
1577
1578
memmove(&allocation_request[1], &my_unique_id[dronecan.node_id_allocation_unique_id_offset], uid_size);
1579
1580
// Broadcasting the request
1581
canard_broadcast(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
1582
UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
1583
CANARD_TRANSFER_PRIORITY_LOW,
1584
&allocation_request[0],
1585
(uint16_t) (uid_size + 1));
1586
1587
// Preparing for timeout; if response is received, this value will be updated from the callback.
1588
dronecan.node_id_allocation_unique_id_offset = 0;
1589
return false;
1590
}
1591
1592
void AP_Periph_FW::can_start()
1593
{
1594
node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;
1595
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION;
1596
node_status.uptime_sec = AP_HAL::millis() / 1000U;
1597
1598
if (g.can_node >= 0 && g.can_node < 128) {
1599
user_set_node_id = g.can_node;
1600
}
1601
1602
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
1603
g.flash_bootloader.set_and_save_ifchanged(0);
1604
#endif
1605
1606
#if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 2
1607
bool has_uavcan_at_1MHz = false;
1608
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
1609
if (g.can_protocol[i] == AP_CAN::Protocol::DroneCAN && g.can_baudrate[i] == 1000000) {
1610
has_uavcan_at_1MHz = true;
1611
}
1612
}
1613
if (!has_uavcan_at_1MHz) {
1614
g.can_protocol[0].set_and_save(uint8_t(AP_CAN::Protocol::DroneCAN));
1615
g.can_baudrate[0].set_and_save(1000000);
1616
}
1617
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
1618
1619
#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM
1620
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, g.can_terminate[0]);
1621
#endif
1622
#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM
1623
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, g.can_terminate[1]);
1624
#endif
1625
#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM
1626
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, g.can_terminate[2]);
1627
#endif
1628
1629
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
1630
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1631
can_iface_periph[i] = NEW_NOTHROW ChibiOS::CANIface();
1632
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
1633
can_iface_periph[i] = NEW_NOTHROW HALSITL::CANIface();
1634
#endif
1635
instances[i].iface = can_iface_periph[i];
1636
instances[i].index = i;
1637
#if HAL_PERIPH_CAN_MIRROR
1638
if ((g.can_mirror_ports & (1U << i)) != 0) {
1639
instances[i].mirror_queue = NEW_NOTHROW ObjectBuffer<AP_HAL::CANFrame> (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE);
1640
}
1641
#endif //HAL_PERIPH_CAN_MIRROR
1642
#if HAL_NUM_CAN_IFACES >= 2
1643
can_protocol_cached[i] = g.can_protocol[i];
1644
CANSensor::set_periph(i, can_protocol_cached[i], can_iface_periph[i]);
1645
#endif
1646
if (can_iface_periph[i] != nullptr) {
1647
#if HAL_CANFD_SUPPORTED
1648
can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U, AP_HAL::CANIface::NormalMode);
1649
#else
1650
can_iface_periph[i]->init(g.can_baudrate[i], AP_HAL::CANIface::NormalMode);
1651
#endif
1652
}
1653
}
1654
1655
#if AP_CAN_SLCAN_ENABLED
1656
const uint8_t slcan_selected_index = g.can_slcan_cport - 1;
1657
if (slcan_selected_index < HAL_NUM_CAN_IFACES) {
1658
slcan_interface.set_can_iface(can_iface_periph[slcan_selected_index]);
1659
instances[slcan_selected_index].iface = (AP_HAL::CANIface*)&slcan_interface;
1660
1661
// ensure there's a serial port mapped to SLCAN
1662
if (!serial_manager.have_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)) {
1663
serial_manager.set_protocol_and_baud(SERIALMANAGER_NUM_PORTS-1, AP_SerialManager::SerialProtocol_SLCAN, 1500000);
1664
}
1665
}
1666
#endif
1667
1668
canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool),
1669
onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, this);
1670
1671
if (user_set_node_id != CANARD_BROADCAST_NODE_ID) {
1672
canardSetLocalNodeID(&dronecan.canard, user_set_node_id);
1673
}
1674
}
1675
1676
1677
#ifdef HAL_PERIPH_ENABLE_RC_OUT
1678
#if HAL_WITH_ESC_TELEM
1679
// try to map the ESC number to a motor number. This is needed
1680
// for when we have multiple CAN nodes, one for each ESC
1681
uint8_t AP_Periph_FW::get_motor_number(const uint8_t esc_number) const
1682
{
1683
const auto *channel = SRV_Channels::srv_channel(esc_number);
1684
// try to map the ESC number to a motor number. This is needed
1685
// for when we have multiple CAN nodes, one for each ESC
1686
if (channel == nullptr) {
1687
return esc_number;
1688
}
1689
const int8_t motor_num = channel->get_motor_num();
1690
return (motor_num == -1) ? esc_number : motor_num;
1691
}
1692
1693
/*
1694
send ESC status packets based on AP_ESC_Telem
1695
*/
1696
void AP_Periph_FW::esc_telem_update()
1697
{
1698
uint32_t mask = esc_telem.get_active_esc_mask();
1699
while (mask != 0) {
1700
int8_t i = __builtin_ffs(mask) - 1;
1701
mask &= ~(1U<<i);
1702
const float nan = nanf("");
1703
uavcan_equipment_esc_Status pkt {};
1704
pkt.esc_index = get_motor_number(i);
1705
1706
if (!esc_telem.get_voltage(i, pkt.voltage)) {
1707
pkt.voltage = nan;
1708
}
1709
if (!esc_telem.get_current(i, pkt.current)) {
1710
pkt.current = nan;
1711
}
1712
int16_t temperature;
1713
if (esc_telem.get_motor_temperature(i, temperature)) {
1714
pkt.temperature = C_TO_KELVIN(temperature*0.01);
1715
} else if (esc_telem.get_temperature(i, temperature)) {
1716
pkt.temperature = C_TO_KELVIN(temperature*0.01);
1717
} else {
1718
pkt.temperature = nan;
1719
}
1720
float rpm;
1721
if (esc_telem.get_raw_rpm(i, rpm)) {
1722
pkt.rpm = rpm;
1723
}
1724
1725
#if AP_EXTENDED_ESC_TELEM_ENABLED
1726
uint8_t power_rating_pct;
1727
if (esc_telem.get_power_percentage(i, power_rating_pct)) {
1728
pkt.power_rating_pct = power_rating_pct;
1729
}
1730
#endif
1731
1732
pkt.error_count = 0;
1733
1734
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
1735
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
1736
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
1737
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
1738
CANARD_TRANSFER_PRIORITY_LOW,
1739
&buffer[0],
1740
total_size);
1741
}
1742
}
1743
#endif // HAL_WITH_ESC_TELEM
1744
1745
#if AP_EXTENDED_ESC_TELEM_ENABLED
1746
void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)
1747
{
1748
if (g.esc_extended_telem_rate <= 0) {
1749
// Not configured to send
1750
return;
1751
}
1752
1753
uint32_t mask = esc_telem.get_active_esc_mask();
1754
if (mask == 0) {
1755
// No ESCs to report
1756
return;
1757
}
1758
1759
// ESCs are sent in turn to minimise used bandwidth, to make the rate param match the status message we multiply
1760
// the period such that the param gives the per-esc rate
1761
const uint32_t update_period_ms = 1000 / constrain_int32(g.esc_extended_telem_rate.get() * __builtin_popcount(mask), 1, 1000);
1762
if (now_ms - last_esc_telem_extended_update < update_period_ms) {
1763
// Too soon!
1764
return;
1765
}
1766
last_esc_telem_extended_update = now_ms;
1767
1768
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
1769
// Send each ESC in turn
1770
const uint8_t index = (last_esc_telem_extended_sent_id + 1 + i) % ESC_TELEM_MAX_ESCS;
1771
1772
if ((mask & (1U << index)) == 0) {
1773
// Not enabled
1774
continue;
1775
}
1776
1777
uavcan_equipment_esc_StatusExtended pkt {};
1778
1779
// Only send if we have data
1780
bool have_data = false;
1781
1782
int16_t motor_temp_cdeg;
1783
if (esc_telem.get_motor_temperature(index, motor_temp_cdeg)) {
1784
// Convert from centi-degrees to degrees
1785
pkt.motor_temperature_degC = motor_temp_cdeg * 0.01;
1786
have_data = true;
1787
}
1788
1789
have_data |= esc_telem.get_input_duty(index, pkt.input_pct);
1790
have_data |= esc_telem.get_output_duty(index, pkt.output_pct);
1791
have_data |= esc_telem.get_flags(index, pkt.status_flags);
1792
1793
if (have_data) {
1794
pkt.esc_index = get_motor_number(index);
1795
1796
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE];
1797
const uint16_t total_size = uavcan_equipment_esc_StatusExtended_encode(&pkt, buffer, !canfdout());
1798
1799
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE,
1800
UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID,
1801
CANARD_TRANSFER_PRIORITY_LOW,
1802
&buffer[0],
1803
total_size);
1804
}
1805
1806
last_esc_telem_extended_sent_id = index;
1807
break;
1808
}
1809
}
1810
#endif
1811
1812
#ifdef HAL_PERIPH_ENABLE_ESC_APD
1813
void AP_Periph_FW::apd_esc_telem_update()
1814
{
1815
for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {
1816
if (apd_esc_telem[i] == nullptr) {
1817
continue;
1818
}
1819
ESC_APD_Telem &esc = *apd_esc_telem[i];
1820
1821
if (esc.update()) {
1822
const ESC_APD_Telem::telem &t = esc.get_telem();
1823
1824
uavcan_equipment_esc_Status pkt {};
1825
static_assert(APD_ESC_INSTANCES <= ARRAY_SIZE(g.esc_number), "There must be an ESC instance number for each APD ESC");
1826
pkt.esc_index = g.esc_number[i];
1827
pkt.voltage = t.voltage;
1828
pkt.current = t.current;
1829
pkt.temperature = t.temperature;
1830
pkt.rpm = t.rpm;
1831
pkt.power_rating_pct = t.power_rating_pct;
1832
pkt.error_count = t.error_count;
1833
1834
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
1835
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
1836
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
1837
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
1838
CANARD_TRANSFER_PRIORITY_LOW,
1839
&buffer[0],
1840
total_size);
1841
}
1842
}
1843
1844
}
1845
#endif // HAL_PERIPH_ENABLE_ESC_APD
1846
#endif // HAL_PERIPH_ENABLE_RC_OUT
1847
1848
void AP_Periph_FW::can_update()
1849
{
1850
const uint32_t now = AP_HAL::millis();
1851
const uint32_t led_pattern = 0xAAAA;
1852
const uint32_t led_change_period = 50;
1853
static uint8_t led_idx = 0;
1854
static uint32_t last_led_change;
1855
1856
if ((now - last_led_change > led_change_period) && no_iface_finished_dna) {
1857
// blink LED in recognisable pattern while waiting for DNA
1858
#ifdef HAL_GPIO_PIN_LED
1859
palWriteLine(HAL_GPIO_PIN_LED, (led_pattern & (1U<<led_idx))?1:0);
1860
#elif defined(HAL_GPIO_PIN_SAFE_LED)
1861
// or use safety LED if defined
1862
palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U<<led_idx))?1:0);
1863
#else
1864
(void)led_pattern;
1865
(void)led_idx;
1866
#endif
1867
led_idx = (led_idx+1) % 32;
1868
last_led_change = now;
1869
}
1870
1871
if (AP_HAL::millis() > dronecan.send_next_node_id_allocation_request_at_ms) {
1872
can_do_dna();
1873
}
1874
1875
static uint32_t last_1Hz_ms;
1876
if (now - last_1Hz_ms >= 1000) {
1877
last_1Hz_ms = now;
1878
process1HzTasks(AP_HAL::micros64());
1879
}
1880
1881
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1882
if (!hal.run_in_maintenance_mode())
1883
#endif
1884
{
1885
#ifdef HAL_PERIPH_ENABLE_MAG
1886
can_mag_update();
1887
#endif
1888
#ifdef HAL_PERIPH_ENABLE_GPS
1889
can_gps_update();
1890
#endif
1891
#if AP_UART_MONITOR_ENABLED
1892
send_serial_monitor_data();
1893
#endif
1894
#ifdef HAL_PERIPH_ENABLE_BATTERY
1895
can_battery_update();
1896
#endif
1897
#ifdef HAL_PERIPH_ENABLE_BARO
1898
can_baro_update();
1899
#endif
1900
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
1901
can_airspeed_update();
1902
#endif
1903
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
1904
can_rangefinder_update();
1905
#endif
1906
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
1907
can_proximity_update();
1908
#endif
1909
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
1910
can_buzzer_update();
1911
#endif
1912
#ifdef HAL_GPIO_PIN_SAFE_LED
1913
can_safety_LED_update();
1914
#endif
1915
#ifdef HAL_GPIO_PIN_SAFE_BUTTON
1916
can_safety_button_update();
1917
#endif
1918
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
1919
pwm_hardpoint_update();
1920
#endif
1921
#ifdef HAL_PERIPH_ENABLE_HWESC
1922
hwesc_telem_update();
1923
#endif
1924
#ifdef HAL_PERIPH_ENABLE_ESC_APD
1925
apd_esc_telem_update();
1926
#endif
1927
#ifdef HAL_PERIPH_ENABLE_MSP
1928
msp_sensor_update();
1929
#endif
1930
#ifdef HAL_PERIPH_ENABLE_RC_OUT
1931
rcout_update();
1932
#endif
1933
#ifdef HAL_PERIPH_ENABLE_EFI
1934
can_efi_update();
1935
#endif
1936
#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE
1937
temperature_sensor_update();
1938
#endif
1939
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
1940
rpm_sensor_send();
1941
#endif
1942
}
1943
const uint32_t now_us = AP_HAL::micros();
1944
while ((AP_HAL::micros() - now_us) < 1000) {
1945
hal.scheduler->delay_microseconds(HAL_PERIPH_LOOP_DELAY_US);
1946
1947
#if HAL_CANFD_SUPPORTED
1948
// allow for user enabling/disabling CANFD at runtime
1949
dronecan.canard.tao_disabled = g.can_fdmode == 1;
1950
#endif
1951
{
1952
WITH_SEMAPHORE(canard_broadcast_semaphore);
1953
processTx();
1954
processRx();
1955
#if HAL_PERIPH_CAN_MIRROR
1956
processMirror();
1957
#endif // HAL_PERIPH_CAN_MIRROR
1958
1959
}
1960
}
1961
1962
// if there is a reboot scheduled, do it 1 second after request to allow the acknowledgement to be sent
1963
if (reboot_request_ms != 0 && (AP_HAL::millis() - reboot_request_ms > 1000)) {
1964
prepare_reboot();
1965
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1966
NVIC_SystemReset();
1967
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
1968
HAL_SITL::actually_reboot();
1969
#endif
1970
}
1971
}
1972
1973
// printf to CAN LogMessage for debugging
1974
void can_vprintf(uint8_t severity, const char *fmt, va_list ap)
1975
{
1976
// map MAVLink levels to CAN levels
1977
uint8_t level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;
1978
switch (severity) {
1979
case MAV_SEVERITY_DEBUG:
1980
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;
1981
break;
1982
case MAV_SEVERITY_INFO:
1983
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_INFO;
1984
break;
1985
case MAV_SEVERITY_NOTICE:
1986
case MAV_SEVERITY_WARNING:
1987
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_WARNING;
1988
break;
1989
case MAV_SEVERITY_ERROR:
1990
case MAV_SEVERITY_CRITICAL:
1991
case MAV_SEVERITY_ALERT:
1992
case MAV_SEVERITY_EMERGENCY:
1993
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_ERROR;
1994
break;
1995
}
1996
1997
#if HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF
1998
const uint8_t packet_count_max = 4; // how many packets we're willing to break up an over-sized string into
1999
const uint8_t packet_data_max = 90; // max single debug string length = sizeof(uavcan_protocol_debug_LogMessage.text.data)
2000
uint8_t buffer_data[packet_count_max*packet_data_max] {};
2001
2002
// strip off any negative return errors by treating result as 0
2003
uint32_t char_count = MAX(vsnprintf((char*)buffer_data, sizeof(buffer_data), fmt, ap), 0);
2004
2005
// send multiple uavcan_protocol_debug_LogMessage packets if the fmt string is too long.
2006
uint16_t buffer_offset = 0;
2007
for (uint8_t i=0; i<packet_count_max && char_count > 0; i++) {
2008
uavcan_protocol_debug_LogMessage pkt {};
2009
pkt.level.value = level;
2010
pkt.text.len = MIN(char_count, sizeof(pkt.text.data));
2011
char_count -= pkt.text.len;
2012
2013
memcpy(pkt.text.data, &buffer_data[buffer_offset], pkt.text.len);
2014
buffer_offset += pkt.text.len;
2015
2016
uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
2017
const uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer_packet, !periph.canfdout());
2018
2019
periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
2020
UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
2021
CANARD_TRANSFER_PRIORITY_LOW,
2022
buffer_packet,
2023
len);
2024
}
2025
2026
#else
2027
uavcan_protocol_debug_LogMessage pkt {};
2028
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
2029
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
2030
pkt.level.value = level;
2031
pkt.text.len = MIN(n, sizeof(pkt.text.data));
2032
2033
uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer, !periph.canfdout());
2034
2035
periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
2036
UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
2037
CANARD_TRANSFER_PRIORITY_LOW,
2038
buffer,
2039
len);
2040
2041
#endif
2042
}
2043
2044
// printf to CAN LogMessage for debugging, with severity
2045
void can_printf_severity(uint8_t severity, const char *fmt, ...)
2046
{
2047
va_list ap;
2048
va_start(ap, fmt);
2049
can_vprintf(severity, fmt, ap);
2050
va_end(ap);
2051
}
2052
2053
// printf to CAN LogMessage for debugging, with DEBUG level
2054
void can_printf(const char *fmt, ...)
2055
{
2056
va_list ap;
2057
va_start(ap, fmt);
2058
can_vprintf(MAV_SEVERITY_DEBUG, fmt, ap);
2059
va_end(ap);
2060
}
2061
2062