Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/can.cpp
9442 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
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 (HAL_PROGRAM_SIZE_LIMIT_KB >= 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
#if AP_PERIPH_GPS_ENABLED
350
AP_Param::setup_object_defaults(&gps, gps.var_info);
351
#endif
352
#if AP_PERIPH_BATTERY_ENABLED
353
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
354
#endif
355
#if AP_PERIPH_MAG_ENABLED
356
AP_Param::setup_object_defaults(&compass, compass.var_info);
357
#endif
358
#if AP_PERIPH_BARO_ENABLED
359
AP_Param::setup_object_defaults(&baro, baro.var_info);
360
#endif
361
#if AP_PERIPH_AIRSPEED_ENABLED
362
AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);
363
#endif
364
#if AP_PERIPH_RANGEFINDER_ENABLED
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 AP_PERIPH_GPS_ENABLED && (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) || AP_PERIPH_RC_OUT_ENABLED
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
#if AP_PERIPH_RTC_GLOBALTIME_ENABLED
528
/*
529
handle GlobalTime
530
*/
531
void AP_Periph_FW::handle_globaltime(CanardInstance* canard_instance, CanardRxTransfer* transfer)
532
{
533
dronecan_protocol_GlobalTime req;
534
if (dronecan_protocol_GlobalTime_decode(transfer, &req)) {
535
return;
536
}
537
AP::rtc().set_utc_usec(req.timestamp.usec, AP_RTC::source_type::SOURCE_GPS);
538
}
539
#endif // AP_PERIPH_RTC_GLOBALTIME_ENABLED
540
541
542
543
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
544
void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
545
{
546
#if AP_PERIPH_NOTIFY_ENABLED
547
notify.handle_rgb(red, green, blue);
548
#if AP_PERIPH_RC_OUT_ENABLED
549
rcout_has_new_data_to_update = true;
550
#endif // AP_PERIPH_RC_OUT_ENABLED
551
#endif // AP_PERIPH_NOTIFY_ENABLED
552
553
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
554
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);
555
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
556
#endif // HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
557
558
#if AP_PERIPH_NCP5623_LED_WITHOUT_NOTIFY_ENABLED
559
{
560
const uint8_t i2c_address = 0x38;
561
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
562
if (!dev) {
563
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
564
}
565
WITH_SEMAPHORE(dev->get_semaphore());
566
dev->set_retries(0);
567
uint8_t v = 0x3f; // enable LED
568
dev->transfer(&v, 1, nullptr, 0);
569
v = 0x40 | red >> 3; // red
570
dev->transfer(&v, 1, nullptr, 0);
571
v = 0x60 | green >> 3; // green
572
dev->transfer(&v, 1, nullptr, 0);
573
v = 0x80 | blue >> 3; // blue
574
dev->transfer(&v, 1, nullptr, 0);
575
}
576
#endif // AP_PERIPH_NCP5623_LED_WITHOUT_NOTIFY_ENABLED
577
578
#if AP_PERIPH_NCP5623_BGR_LED_WITHOUT_NOTIFY_ENABLED
579
{
580
const uint8_t i2c_address = 0x38;
581
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
582
if (!dev) {
583
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
584
}
585
WITH_SEMAPHORE(dev->get_semaphore());
586
dev->set_retries(0);
587
uint8_t v = 0x3f; // enable LED
588
dev->transfer(&v, 1, nullptr, 0);
589
v = 0x40 | blue >> 3; // blue
590
dev->transfer(&v, 1, nullptr, 0);
591
v = 0x60 | green >> 3; // green
592
dev->transfer(&v, 1, nullptr, 0);
593
v = 0x80 | red >> 3; // red
594
dev->transfer(&v, 1, nullptr, 0);
595
}
596
#endif // AP_PERIPH_NCP5623_BGR_LED_WITHOUT_NOTIFY_ENABLED
597
#if AP_PERIPH_TOSHIBA_LED_WITHOUT_NOTIFY_ENABLED
598
{
599
#define TOSHIBA_LED_PWM0 0x01 // pwm0 register
600
#define TOSHIBA_LED_ENABLE 0x04 // enable register
601
#define TOSHIBA_LED_I2C_ADDR 0x55 // default I2C bus address
602
603
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_toshiba;
604
if (!dev_toshiba) {
605
dev_toshiba = std::move(hal.i2c_mgr->get_device(0, TOSHIBA_LED_I2C_ADDR));
606
}
607
WITH_SEMAPHORE(dev_toshiba->get_semaphore());
608
dev_toshiba->set_retries(0); // use 0 because this is running on main thread.
609
610
// enable the led
611
dev_toshiba->write_register(TOSHIBA_LED_ENABLE, 0x03);
612
613
/* 4-bit for each color */
614
uint8_t val[4] = {
615
TOSHIBA_LED_PWM0,
616
(uint8_t)(blue >> 4),
617
(uint8_t)(green / 16),
618
(uint8_t)(red / 16)
619
};
620
dev_toshiba->transfer(val, sizeof(val), nullptr, 0);
621
}
622
#endif // AP_PERIPH_TOSHIBA_LED_WITHOUT_NOTIFY_ENABLED
623
}
624
625
/*
626
handle lightscommand
627
*/
628
void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
629
{
630
uavcan_equipment_indication_LightsCommand req;
631
if (uavcan_equipment_indication_LightsCommand_decode(transfer, &req)) {
632
return;
633
}
634
for (uint8_t i=0; i<req.commands.len; i++) {
635
uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];
636
// to get the right color proportions we scale the green so that is uses the
637
// same number of bits as red and blue
638
uint8_t red = cmd.color.red<<3U;
639
uint8_t green = (cmd.color.green>>1U)<<3U;
640
uint8_t blue = cmd.color.blue<<3U;
641
#if AP_PERIPH_NOTIFY_ENABLED
642
const int8_t brightness = notify.get_rgb_led_brightness_percent();
643
#elif AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
644
const int8_t brightness = g.led_brightness;
645
#endif
646
if (brightness != 100 && brightness >= 0) {
647
const float scale = brightness * 0.01;
648
red = constrain_int16(red * scale, 0, 255);
649
green = constrain_int16(green * scale, 0, 255);
650
blue = constrain_int16(blue * scale, 0, 255);
651
}
652
set_rgb_led(red, green, blue);
653
}
654
}
655
#endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
656
657
#if AP_PERIPH_RC_OUT_ENABLED
658
void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
659
{
660
uavcan_equipment_esc_RawCommand cmd;
661
if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) {
662
return;
663
}
664
rcout_esc(cmd.cmd.data, cmd.cmd.len);
665
666
// Update internal copy for disabling output to ESC when CAN packets are lost
667
last_esc_num_channels = cmd.cmd.len;
668
last_esc_raw_command_ms = AP_HAL::millis();
669
}
670
671
void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer)
672
{
673
uavcan_equipment_actuator_ArrayCommand cmd;
674
if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) {
675
return;
676
}
677
678
bool valid_output = false;
679
for (uint8_t i=0; i < cmd.commands.len; i++) {
680
const auto &c = cmd.commands.data[i];
681
switch (c.command_type) {
682
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS:
683
rcout_srv_unitless(c.actuator_id, c.command_value);
684
valid_output = true;
685
break;
686
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM:
687
rcout_srv_PWM(c.actuator_id, c.command_value);
688
valid_output = true;
689
break;
690
}
691
}
692
693
if (valid_output) {
694
actuator.last_command_ms = AP_HAL::millis();
695
}
696
}
697
#endif // AP_PERIPH_RC_OUT_ENABLED
698
699
#if AP_PERIPH_NOTIFY_ENABLED
700
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
701
{
702
ardupilot_indication_NotifyState msg;
703
if (ardupilot_indication_NotifyState_decode(transfer, &msg)) {
704
return;
705
}
706
if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) {
707
uint16_t tmp = 0;
708
memcpy(&tmp, msg.aux_data.data, sizeof(tmp));
709
yaw_earth = radians((float)tmp * 0.01f);
710
}
711
vehicle_state = msg.vehicle_state;
712
last_vehicle_state_ms = AP_HAL::millis();
713
}
714
#endif // AP_PERIPH_NOTIFY_ENABLED
715
716
#ifdef HAL_GPIO_PIN_SAFE_LED
717
/*
718
update safety LED
719
*/
720
void AP_Periph_FW::can_safety_LED_update(void)
721
{
722
static uint32_t last_update_ms;
723
switch (safety_state) {
724
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF:
725
palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON);
726
break;
727
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: {
728
uint32_t now = AP_HAL::millis();
729
if (now - last_update_ms > 100) {
730
last_update_ms = now;
731
static uint8_t led_counter;
732
const uint16_t led_pattern = 0x5500;
733
led_counter = (led_counter+1) % 16;
734
palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U << led_counter))?!SAFE_LED_ON:SAFE_LED_ON);
735
}
736
break;
737
}
738
default:
739
palWriteLine(HAL_GPIO_PIN_SAFE_LED, !SAFE_LED_ON);
740
break;
741
}
742
}
743
#endif // HAL_GPIO_PIN_SAFE_LED
744
745
746
#ifdef HAL_GPIO_PIN_SAFE_BUTTON
747
#ifndef HAL_SAFE_BUTTON_ON
748
#define HAL_SAFE_BUTTON_ON 1
749
#endif
750
/*
751
update safety button
752
*/
753
void AP_Periph_FW::can_safety_button_update(void)
754
{
755
static uint32_t last_update_ms;
756
static uint8_t counter;
757
uint32_t now = AP_HAL::millis();
758
// send at 10Hz when pressed
759
if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) {
760
counter = 0;
761
return;
762
}
763
if (now - last_update_ms < 100) {
764
return;
765
}
766
if (counter < 255) {
767
counter++;
768
}
769
770
last_update_ms = now;
771
ardupilot_indication_Button pkt {};
772
pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY;
773
pkt.press_time = counter;
774
775
uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE];
776
uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout());
777
778
canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE,
779
ARDUPILOT_INDICATION_BUTTON_ID,
780
CANARD_TRANSFER_PRIORITY_LOW,
781
&buffer[0],
782
total_size);
783
}
784
#endif // HAL_GPIO_PIN_SAFE_BUTTON
785
786
/**
787
* This callback is invoked by the library when a new message or request or response is received.
788
*/
789
void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
790
CanardRxTransfer* transfer)
791
{
792
#ifdef HAL_GPIO_PIN_LED_CAN1
793
palToggleLine(HAL_GPIO_PIN_LED_CAN1);
794
#endif
795
796
#if HAL_CANFD_SUPPORTED
797
// enable tao for decoding when not on CANFD
798
transfer->tao = !transfer->canfd;
799
#endif
800
801
/*
802
* Dynamic node ID allocation protocol.
803
* Taking this branch only if we don't have a node ID, ignoring otherwise.
804
*/
805
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) {
806
if (transfer->transfer_type == CanardTransferTypeBroadcast &&
807
transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
808
handle_allocation_response(canard_instance, transfer);
809
}
810
return;
811
}
812
813
switch (transfer->data_type_id) {
814
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
815
handle_get_node_info(canard_instance, transfer);
816
break;
817
818
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
819
handle_begin_firmware_update(canard_instance, transfer);
820
break;
821
822
case UAVCAN_PROTOCOL_RESTARTNODE_ID: {
823
printf("RestartNode\n");
824
uavcan_protocol_RestartNodeResponse pkt {
825
ok: true,
826
};
827
uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];
828
uint16_t total_size = uavcan_protocol_RestartNodeResponse_encode(&pkt, buffer, !canfdout());
829
canard_respond(canard_instance,
830
transfer,
831
UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE,
832
UAVCAN_PROTOCOL_RESTARTNODE_ID,
833
&buffer[0],
834
total_size);
835
836
// schedule a reboot to occur
837
reboot_request_ms = AP_HAL::millis();
838
}
839
break;
840
841
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
842
handle_param_getset(canard_instance, transfer);
843
break;
844
845
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
846
handle_param_executeopcode(canard_instance, transfer);
847
break;
848
849
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NOTIFY_ENABLED
850
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
851
handle_beep_command(canard_instance, transfer);
852
break;
853
#endif
854
855
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
856
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
857
handle_safety_state(canard_instance, transfer);
858
break;
859
#endif
860
861
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
862
handle_arming_status(canard_instance, transfer);
863
break;
864
865
#if AP_PERIPH_GPS_ENABLED
866
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
867
handle_RTCMStream(canard_instance, transfer);
868
break;
869
870
#if GPS_MOVING_BASELINE
871
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
872
handle_MovingBaselineData(canard_instance, transfer);
873
break;
874
#endif
875
#endif // AP_PERIPH_GPS_ENABLED
876
877
#if AP_UART_MONITOR_ENABLED
878
case UAVCAN_TUNNEL_TARGETTED_ID:
879
handle_tunnel_Targetted(canard_instance, transfer);
880
break;
881
#endif
882
883
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
884
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
885
handle_lightscommand(canard_instance, transfer);
886
break;
887
#endif
888
889
#if AP_PERIPH_RC_OUT_ENABLED
890
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
891
handle_esc_rawcommand(canard_instance, transfer);
892
break;
893
894
case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:
895
handle_act_command(canard_instance, transfer);
896
break;
897
#endif
898
899
#if AP_PERIPH_NOTIFY_ENABLED
900
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
901
handle_notify_state(canard_instance, transfer);
902
break;
903
#endif
904
905
#if AP_PERIPH_RELAY_ENABLED
906
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
907
handle_hardpoint_command(canard_instance, transfer);
908
break;
909
#endif
910
#if AP_PERIPH_RTC_GLOBALTIME_ENABLED
911
case DRONECAN_PROTOCOL_GLOBALTIME_ID:
912
handle_globaltime(canard_instance, transfer);
913
break;
914
#endif
915
916
}
917
}
918
919
/**
920
* This callback is invoked by the library when a new message or request or response is received.
921
*/
922
static void onTransferReceived_trampoline(CanardInstance* canard_instance,
923
CanardRxTransfer* transfer)
924
{
925
AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;
926
fw->onTransferReceived(canard_instance, transfer);
927
}
928
929
930
/**
931
* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received
932
* by the local node.
933
* If the callback returns true, the library will receive the transfer.
934
* If the callback returns false, the library will ignore the transfer.
935
* All transfers that are addressed to other nodes are always ignored.
936
*/
937
bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
938
uint64_t* out_data_type_signature,
939
uint16_t data_type_id,
940
CanardTransferType transfer_type,
941
uint8_t source_node_id)
942
{
943
(void)source_node_id;
944
945
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID)
946
{
947
/*
948
* If we're in the process of allocation of dynamic node ID, accept only relevant transfers.
949
*/
950
if ((transfer_type == CanardTransferTypeBroadcast) &&
951
(data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID))
952
{
953
*out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
954
return true;
955
}
956
return false;
957
}
958
959
switch (data_type_id) {
960
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
961
*out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE;
962
return true;
963
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
964
*out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE;
965
return true;
966
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
967
*out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;
968
return true;
969
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
970
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE;
971
return true;
972
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
973
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;
974
return true;
975
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NOTIFY_ENABLED
976
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
977
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
978
return true;
979
#endif
980
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
981
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
982
*out_data_type_signature = ARDUPILOT_INDICATION_SAFETYSTATE_SIGNATURE;
983
return true;
984
#endif
985
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
986
*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;
987
return true;
988
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
989
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
990
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
991
return true;
992
#endif
993
#if AP_PERIPH_GPS_ENABLED
994
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
995
*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;
996
return true;
997
998
#if GPS_MOVING_BASELINE
999
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
1000
*out_data_type_signature = ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE;
1001
return true;
1002
#endif
1003
#endif // AP_PERIPH_GPS_ENABLED
1004
1005
#if AP_UART_MONITOR_ENABLED
1006
case UAVCAN_TUNNEL_TARGETTED_ID:
1007
*out_data_type_signature = UAVCAN_TUNNEL_TARGETTED_SIGNATURE;
1008
return true;
1009
#endif
1010
1011
#if AP_PERIPH_RC_OUT_ENABLED
1012
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
1013
*out_data_type_signature = UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE;
1014
return true;
1015
1016
case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:
1017
*out_data_type_signature = UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_SIGNATURE;
1018
return true;
1019
#endif
1020
#if AP_PERIPH_NOTIFY_ENABLED
1021
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
1022
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
1023
return true;
1024
#endif
1025
#if AP_PERIPH_RELAY_ENABLED
1026
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
1027
*out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE;
1028
return true;
1029
#endif
1030
#if AP_PERIPH_RTC_GLOBALTIME_ENABLED
1031
case DRONECAN_PROTOCOL_GLOBALTIME_ID:
1032
*out_data_type_signature = DRONECAN_PROTOCOL_GLOBALTIME_SIGNATURE;
1033
return true;
1034
#endif
1035
default:
1036
break;
1037
}
1038
1039
return false;
1040
}
1041
1042
static bool shouldAcceptTransfer_trampoline(const CanardInstance* canard_instance,
1043
uint64_t* out_data_type_signature,
1044
uint16_t data_type_id,
1045
CanardTransferType transfer_type,
1046
uint8_t source_node_id)
1047
{
1048
AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;
1049
return fw->shouldAcceptTransfer(canard_instance, out_data_type_signature, data_type_id, transfer_type, source_node_id);
1050
}
1051
1052
void AP_Periph_FW::cleanup_stale_transactions(uint64_t timestamp_usec)
1053
{
1054
canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec);
1055
}
1056
1057
uint8_t *AP_Periph_FW::get_tid_ptr(uint32_t transfer_desc)
1058
{
1059
// check head
1060
if (!dronecan.tid_map_head) {
1061
dronecan.tid_map_head = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));
1062
if (dronecan.tid_map_head == nullptr) {
1063
return nullptr;
1064
}
1065
dronecan.tid_map_head->transfer_desc = transfer_desc;
1066
dronecan.tid_map_head->next = nullptr;
1067
return &dronecan.tid_map_head->tid;
1068
} else if (dronecan.tid_map_head->transfer_desc == transfer_desc) {
1069
return &dronecan.tid_map_head->tid;
1070
}
1071
1072
// search through the list for an existing entry
1073
dronecan_protocol_t::tid_map *tid_map_ptr = dronecan.tid_map_head;
1074
while(tid_map_ptr->next) {
1075
tid_map_ptr = tid_map_ptr->next;
1076
if (tid_map_ptr->transfer_desc == transfer_desc) {
1077
return &tid_map_ptr->tid;
1078
}
1079
}
1080
1081
// create a new entry, if not found
1082
tid_map_ptr->next = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));
1083
if (tid_map_ptr->next == nullptr) {
1084
return nullptr;
1085
}
1086
tid_map_ptr->next->transfer_desc = transfer_desc;
1087
tid_map_ptr->next->next = nullptr;
1088
return &tid_map_ptr->next->tid;
1089
}
1090
1091
bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature,
1092
uint16_t data_type_id,
1093
uint8_t priority,
1094
const void* payload,
1095
uint16_t payload_len,
1096
uint8_t iface_mask)
1097
{
1098
WITH_SEMAPHORE(canard_broadcast_semaphore);
1099
const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID;
1100
if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
1101
return false;
1102
}
1103
1104
uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(data_type_signature, data_type_id, 0, CANARD_BROADCAST_NODE_ID));
1105
if (tid_ptr == nullptr) {
1106
return false;
1107
}
1108
1109
// create transfer object
1110
CanardTxTransfer transfer_object = {
1111
.transfer_type = CanardTransferTypeBroadcast,
1112
.data_type_signature = data_type_signature,
1113
.data_type_id = data_type_id,
1114
.inout_transfer_id = tid_ptr,
1115
.priority = priority,
1116
.payload = (uint8_t*)payload,
1117
.payload_len = payload_len,
1118
#if CANARD_ENABLE_CANFD
1119
.canfd = is_dna? false : canfdout(),
1120
#endif
1121
.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,
1122
#if CANARD_MULTI_IFACE
1123
.iface_mask = iface_mask==0 ? uint8_t(IFACE_ALL) : iface_mask,
1124
#endif
1125
};
1126
const int16_t res = canardBroadcastObj(&dronecan.canard, &transfer_object);
1127
1128
#if DEBUG_PKTS
1129
if (res < 0) {
1130
can_printf("Tx error %d\n", res);
1131
}
1132
#endif
1133
#if HAL_ENABLE_SENDING_STATS
1134
if (res <= 0) {
1135
protocol_stats.tx_errors++;
1136
} else {
1137
protocol_stats.tx_frames += res;
1138
}
1139
#endif
1140
return res > 0;
1141
}
1142
1143
/*
1144
send a response
1145
*/
1146
bool AP_Periph_FW::canard_respond(CanardInstance* canard_instance,
1147
CanardRxTransfer *transfer,
1148
uint64_t data_type_signature,
1149
uint16_t data_type_id,
1150
const uint8_t *payload,
1151
uint16_t payload_len)
1152
{
1153
CanardTxTransfer transfer_object = {
1154
.transfer_type = CanardTransferTypeResponse,
1155
.data_type_signature = data_type_signature,
1156
.data_type_id = data_type_id,
1157
.inout_transfer_id = &transfer->transfer_id,
1158
.priority = transfer->priority,
1159
.payload = payload,
1160
.payload_len = payload_len,
1161
#if CANARD_ENABLE_CANFD
1162
.canfd = canfdout(),
1163
#endif
1164
.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,
1165
#if CANARD_MULTI_IFACE
1166
.iface_mask = IFACE_ALL,
1167
#endif
1168
};
1169
const auto res = canardRequestOrRespondObj(canard_instance,
1170
transfer->source_node_id,
1171
&transfer_object);
1172
#if DEBUG_PKTS
1173
if (res < 0) {
1174
can_printf("Tx error %d\n", res);
1175
}
1176
#endif
1177
#if HAL_ENABLE_SENDING_STATS
1178
if (res <= 0) {
1179
protocol_stats.tx_errors++;
1180
} else {
1181
protocol_stats.tx_frames += res;
1182
}
1183
#endif
1184
return res > 0;
1185
}
1186
1187
void AP_Periph_FW::processTx(void)
1188
{
1189
for (CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) {
1190
AP_HAL::CANFrame txmsg {};
1191
txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);
1192
memcpy(txmsg.data, txf->data, txf->data_len);
1193
txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);
1194
#if HAL_CANFD_SUPPORTED
1195
txmsg.canfd = txf->canfd;
1196
#endif
1197
// push message with 1s timeout
1198
bool sent = true;
1199
const uint64_t now_us = AP_HAL::micros64();
1200
const uint64_t deadline = now_us + 1000000U;
1201
// try sending to all interfaces
1202
for (auto &_ins : instances) {
1203
if (_ins.iface == NULL) {
1204
continue;
1205
}
1206
#if CANARD_MULTI_IFACE
1207
if (!(txf->iface_mask & (1U<<_ins.index))) {
1208
continue;
1209
}
1210
#endif
1211
#if HAL_NUM_CAN_IFACES >= 2
1212
if (can_protocol_cached[_ins.index] != AP_CAN::Protocol::DroneCAN) {
1213
continue;
1214
}
1215
#endif
1216
if (_ins.iface->send(txmsg, deadline, 0) <= 0) {
1217
/*
1218
We were not able to queue the frame for
1219
sending. Only mark the send as failing if the
1220
interface is active. We consider an interface as
1221
active if it has had a successful transmit in the
1222
last 2 seconds
1223
*/
1224
volatile const auto *stats = _ins.iface->get_statistics();
1225
uint64_t last_transmit_us = stats->last_transmit_us;
1226
if (stats == nullptr || AP_HAL::micros64() - last_transmit_us < 2000000UL) {
1227
sent = false;
1228
}
1229
} else {
1230
#if CANARD_MULTI_IFACE
1231
txf->iface_mask &= ~(1U<<_ins.index);
1232
#endif
1233
}
1234
}
1235
if (sent) {
1236
canardPopTxQueue(&dronecan.canard);
1237
dronecan.tx_fail_count = 0;
1238
} else {
1239
// exit and try again later. If we fail 8 times in a row
1240
// then cleanup any stale transfers to keep the queue from
1241
// filling
1242
if (dronecan.tx_fail_count < 8) {
1243
dronecan.tx_fail_count++;
1244
} else {
1245
#if HAL_ENABLE_SENDING_STATS
1246
protocol_stats.tx_errors++;
1247
#endif
1248
dronecan.tx_fail_count = 0;
1249
cleanup_stale_transactions(now_us);
1250
}
1251
break;
1252
}
1253
}
1254
}
1255
1256
#if HAL_ENABLE_SENDING_STATS
1257
void AP_Periph_FW::update_rx_protocol_stats(int16_t res)
1258
{
1259
switch (-res) {
1260
case CANARD_OK:
1261
protocol_stats.rx_frames++;
1262
break;
1263
case CANARD_ERROR_OUT_OF_MEMORY:
1264
protocol_stats.rx_error_oom++;
1265
break;
1266
case CANARD_ERROR_INTERNAL:
1267
protocol_stats.rx_error_internal++;
1268
break;
1269
case CANARD_ERROR_RX_INCOMPATIBLE_PACKET:
1270
protocol_stats.rx_ignored_not_wanted++;
1271
break;
1272
case CANARD_ERROR_RX_WRONG_ADDRESS:
1273
protocol_stats.rx_ignored_wrong_address++;
1274
break;
1275
case CANARD_ERROR_RX_NOT_WANTED:
1276
protocol_stats.rx_ignored_not_wanted++;
1277
break;
1278
case CANARD_ERROR_RX_MISSED_START:
1279
protocol_stats.rx_error_missed_start++;
1280
break;
1281
case CANARD_ERROR_RX_WRONG_TOGGLE:
1282
protocol_stats.rx_error_wrong_toggle++;
1283
break;
1284
case CANARD_ERROR_RX_UNEXPECTED_TID:
1285
protocol_stats.rx_ignored_unexpected_tid++;
1286
break;
1287
case CANARD_ERROR_RX_SHORT_FRAME:
1288
protocol_stats.rx_error_short_frame++;
1289
break;
1290
case CANARD_ERROR_RX_BAD_CRC:
1291
protocol_stats.rx_error_bad_crc++;
1292
break;
1293
default:
1294
// mark all other errors as internal
1295
protocol_stats.rx_error_internal++;
1296
break;
1297
}
1298
}
1299
#endif
1300
1301
void AP_Periph_FW::processRx(void)
1302
{
1303
AP_HAL::CANFrame rxmsg;
1304
for (auto &instance : instances) {
1305
if (instance.iface == NULL) {
1306
continue;
1307
}
1308
#if HAL_NUM_CAN_IFACES >= 2
1309
if (can_protocol_cached[instance.index] != AP_CAN::Protocol::DroneCAN) {
1310
continue;
1311
}
1312
#endif
1313
while (true) {
1314
bool read_select = true;
1315
bool write_select = false;
1316
instance.iface->select(read_select, write_select, nullptr, 0);
1317
if (!read_select) { // No data pending
1318
break;
1319
}
1320
CanardCANFrame rx_frame {};
1321
1322
//palToggleLine(HAL_GPIO_PIN_LED);
1323
uint64_t timestamp;
1324
AP_HAL::CANIface::CanIOFlags flags;
1325
if (instance.iface->receive(rxmsg, timestamp, flags) <= 0) {
1326
break;
1327
}
1328
#if HAL_PERIPH_CAN_MIRROR
1329
for (auto &other_instance : instances) {
1330
if (other_instance.mirror_queue == nullptr) { // we aren't mirroring here, or failed on memory
1331
continue;
1332
}
1333
if (other_instance.index == instance.index) { // don't self add
1334
continue;
1335
}
1336
other_instance.mirror_queue->push(rxmsg);
1337
}
1338
#endif // HAL_PERIPH_CAN_MIRROR
1339
rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc);
1340
memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
1341
#if HAL_CANFD_SUPPORTED
1342
rx_frame.canfd = rxmsg.canfd;
1343
#endif
1344
rx_frame.id = rxmsg.id;
1345
#if CANARD_MULTI_IFACE
1346
rx_frame.iface_id = instance.index;
1347
#endif
1348
1349
const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp);
1350
#if HAL_ENABLE_SENDING_STATS
1351
if (res == -CANARD_ERROR_RX_MISSED_START) {
1352
// this might remaining frames from a message that we don't accept, so check
1353
uint64_t dummy_signature;
1354
if (shouldAcceptTransfer(&dronecan.canard,
1355
&dummy_signature,
1356
extractDataType(rx_frame.id),
1357
extractTransferType(rx_frame.id),
1358
1)) { // doesn't matter what we pass here
1359
update_rx_protocol_stats(res);
1360
} else {
1361
protocol_stats.rx_ignored_not_wanted++;
1362
}
1363
} else {
1364
update_rx_protocol_stats(res);
1365
}
1366
#else
1367
(void)res;
1368
#endif
1369
}
1370
}
1371
}
1372
1373
#if HAL_PERIPH_CAN_MIRROR
1374
void AP_Periph_FW::processMirror(void)
1375
{
1376
const uint64_t deadline = AP_HAL::micros64() + 1000000;
1377
1378
for (auto &ins : instances) {
1379
if (ins.iface == nullptr || ins.mirror_queue == nullptr) { // can't send on a null interface
1380
continue;
1381
}
1382
1383
const uint32_t pending = ins.mirror_queue->available();
1384
for (uint32_t i = 0; i < pending; i++) { // limit how long we can loop
1385
AP_HAL::CANFrame txmsg {};
1386
1387
if (!ins.mirror_queue->peek(txmsg)) {
1388
break;
1389
}
1390
1391
if (ins.iface->send(txmsg, deadline, 0) <= 0) {
1392
if (ins.mirror_fail_count < 8) {
1393
ins.mirror_fail_count++;
1394
} else {
1395
ins.mirror_queue->pop();
1396
}
1397
break;
1398
} else {
1399
ins.mirror_fail_count = 0;
1400
ins.mirror_queue->pop();
1401
}
1402
}
1403
}
1404
}
1405
#endif // HAL_PERIPH_CAN_MIRROR
1406
1407
uint16_t AP_Periph_FW::pool_peak_percent()
1408
{
1409
const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&dronecan.canard);
1410
const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks);
1411
return peak_percent;
1412
}
1413
1414
void AP_Periph_FW::node_status_send(void)
1415
{
1416
{
1417
uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];
1418
node_status.uptime_sec = AP_HAL::millis() / 1000U;
1419
1420
node_status.vendor_specific_status_code = MIN(hal.util->available_memory(), unsigned(UINT16_MAX));
1421
1422
uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !canfdout());
1423
1424
canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
1425
UAVCAN_PROTOCOL_NODESTATUS_ID,
1426
CANARD_TRANSFER_PRIORITY_LOW,
1427
buffer,
1428
len);
1429
}
1430
#if HAL_ENABLE_SENDING_STATS
1431
if (debug_option_is_set(AP_Periph_FW::DebugOptions::ENABLE_STATS)) {
1432
{
1433
uint8_t buffer[DRONECAN_PROTOCOL_STATS_MAX_SIZE];
1434
uint32_t len = dronecan_protocol_Stats_encode(&protocol_stats, buffer, !canfdout());
1435
canard_broadcast(DRONECAN_PROTOCOL_STATS_SIGNATURE,
1436
DRONECAN_PROTOCOL_STATS_ID,
1437
CANARD_TRANSFER_PRIORITY_LOWEST,
1438
buffer,
1439
len);
1440
}
1441
for (auto &instance : instances) {
1442
uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE];
1443
dronecan_protocol_CanStats can_stats;
1444
const AP_HAL::CANIface::bus_stats_t *bus_stats = instance.iface->get_statistics();
1445
if (bus_stats == nullptr) {
1446
return;
1447
}
1448
can_stats.interface = instance.index;
1449
can_stats.tx_requests = bus_stats->tx_requests;
1450
can_stats.tx_rejected = bus_stats->tx_rejected;
1451
can_stats.tx_overflow = bus_stats->tx_overflow;
1452
can_stats.tx_success = bus_stats->tx_success;
1453
can_stats.tx_timedout = bus_stats->tx_timedout;
1454
can_stats.tx_abort = bus_stats->tx_abort;
1455
can_stats.rx_received = bus_stats->rx_received;
1456
can_stats.rx_overflow = bus_stats->rx_overflow;
1457
can_stats.rx_errors = bus_stats->rx_errors;
1458
can_stats.busoff_errors = bus_stats->num_busoff_err;
1459
uint32_t len = dronecan_protocol_CanStats_encode(&can_stats, buffer, !canfdout());
1460
canard_broadcast(DRONECAN_PROTOCOL_CANSTATS_SIGNATURE,
1461
DRONECAN_PROTOCOL_CANSTATS_ID,
1462
CANARD_TRANSFER_PRIORITY_LOWEST,
1463
buffer,
1464
len);
1465
}
1466
}
1467
#endif
1468
}
1469
1470
1471
/**
1472
* This function is called at 1 Hz rate from the main loop.
1473
*/
1474
void AP_Periph_FW::process1HzTasks(uint64_t timestamp_usec)
1475
{
1476
/*
1477
* Purging transfers that are no longer transmitted. This will occasionally free up some memory.
1478
*/
1479
cleanup_stale_transactions(timestamp_usec);
1480
1481
/*
1482
* Printing the memory usage statistics.
1483
*/
1484
{
1485
/*
1486
* The recommended way to establish the minimal size of the memory pool is to stress-test the application and
1487
* record the worst case memory usage.
1488
*/
1489
1490
const float pool_pct = pool_peak_percent();
1491
if (pool_pct > 70) {
1492
printf("WARNING: ENLARGE MEMORY POOL (peak=%f%%)\n", pool_pct);
1493
}
1494
}
1495
1496
/*
1497
* Transmitting the node status message periodically.
1498
*/
1499
node_status_send();
1500
1501
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
1502
if (g.flash_bootloader.get()) {
1503
const uint8_t flash_bl = g.flash_bootloader.get();
1504
g.flash_bootloader.set_and_save_ifchanged(0);
1505
if (flash_bl == 42) {
1506
// magic developer value to test watchdog support with main loop lockup
1507
while (true) {
1508
can_printf("entering lockup\n");
1509
hal.scheduler->delay(100);
1510
}
1511
}
1512
if (flash_bl == 43) {
1513
// magic developer value to test watchdog support with hard fault
1514
can_printf("entering fault\n");
1515
void *foo = (void*)0xE000ED38;
1516
typedef void (*fptr)();
1517
fptr gptr = (fptr) (void *) foo;
1518
gptr();
1519
}
1520
EXPECT_DELAY_MS(2000);
1521
hal.scheduler->delay(1000);
1522
AP_HAL::Util::FlashBootloader res = hal.util->flash_bootloader();
1523
switch (res) {
1524
case AP_HAL::Util::FlashBootloader::OK:
1525
can_printf("Flash bootloader OK\n");
1526
break;
1527
case AP_HAL::Util::FlashBootloader::NO_CHANGE:
1528
can_printf("Bootloader unchanged\n");
1529
break;
1530
#if AP_SIGNED_FIRMWARE
1531
case AP_HAL::Util::FlashBootloader::NOT_SIGNED:
1532
can_printf("Bootloader not signed\n");
1533
break;
1534
#endif
1535
default:
1536
can_printf("Flash bootloader FAILED\n");
1537
break;
1538
}
1539
}
1540
#endif
1541
1542
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1543
if (hal.run_in_maintenance_mode()) {
1544
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;
1545
} else
1546
#endif
1547
{
1548
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL;
1549
}
1550
1551
#if 0
1552
// test code for watchdog reset
1553
if (AP_HAL::millis() > 15000) {
1554
while (true) ;
1555
}
1556
#endif
1557
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1558
if (AP_HAL::millis() > 30000) {
1559
// use RTC to mark that we have been running fine for
1560
// 30s. This is used along with watchdog resets to ensure the
1561
// user has a chance to load a fixed firmware
1562
set_fast_reboot(RTC_BOOT_FWOK);
1563
}
1564
#endif
1565
}
1566
1567
/*
1568
wait for dynamic allocation of node ID
1569
*/
1570
bool AP_Periph_FW::no_iface_finished_dna = true;
1571
1572
bool AP_Periph_FW::can_do_dna()
1573
{
1574
if (canardGetLocalNodeID(&dronecan.canard) != CANARD_BROADCAST_NODE_ID) {
1575
AP_Periph_FW::no_iface_finished_dna = false;
1576
return true;
1577
}
1578
1579
const uint32_t now = AP_HAL::millis();
1580
1581
if (AP_Periph_FW::no_iface_finished_dna) {
1582
printf("Waiting for dynamic node ID allocation %x... (pool %u)\n", IFACE_ALL, pool_peak_percent());
1583
}
1584
1585
dronecan.send_next_node_id_allocation_request_at_ms =
1586
now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
1587
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
1588
1589
// Structure of the request is documented in the DSDL definition
1590
// See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
1591
uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];
1592
allocation_request[0] = 0; // we are only called if the user has not set an ID, so request any ID
1593
1594
if (dronecan.node_id_allocation_unique_id_offset == 0) {
1595
allocation_request[0] |= 1; // First part of unique ID
1596
// set interface to try
1597
dronecan.dna_interface++;
1598
dronecan.dna_interface %= HAL_NUM_CAN_IFACES;
1599
}
1600
1601
uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)];
1602
readUniqueID(my_unique_id);
1603
1604
static const uint8_t MaxLenOfUniqueIDInRequest = 6;
1605
uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - dronecan.node_id_allocation_unique_id_offset);
1606
1607
if (uid_size > MaxLenOfUniqueIDInRequest) {
1608
uid_size = MaxLenOfUniqueIDInRequest;
1609
}
1610
1611
memmove(&allocation_request[1], &my_unique_id[dronecan.node_id_allocation_unique_id_offset], uid_size);
1612
1613
// Broadcasting the request
1614
canard_broadcast(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
1615
UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
1616
CANARD_TRANSFER_PRIORITY_LOW,
1617
&allocation_request[0],
1618
(uint16_t) (uid_size + 1));
1619
1620
// Preparing for timeout; if response is received, this value will be updated from the callback.
1621
dronecan.node_id_allocation_unique_id_offset = 0;
1622
return false;
1623
}
1624
1625
void AP_Periph_FW::can_start()
1626
{
1627
node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;
1628
node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION;
1629
node_status.uptime_sec = AP_HAL::millis() / 1000U;
1630
1631
if (g.can_node >= 0 && g.can_node < 128) {
1632
user_set_node_id = g.can_node;
1633
}
1634
1635
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
1636
g.flash_bootloader.set_and_save_ifchanged(0);
1637
#endif
1638
1639
#if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 2
1640
bool has_uavcan_at_1MHz = false;
1641
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
1642
if (g.can_protocol[i] == AP_CAN::Protocol::DroneCAN && g.can_baudrate[i] == 1000000) {
1643
has_uavcan_at_1MHz = true;
1644
}
1645
}
1646
if (!has_uavcan_at_1MHz) {
1647
g.can_protocol[0].set_and_save(AP_CAN::Protocol::DroneCAN);
1648
g.can_baudrate[0].set_and_save(1000000);
1649
}
1650
#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
1651
1652
{
1653
/*
1654
support termination parameters, and also a hardware switch
1655
to force termination and an LED to indicate if termination
1656
is active
1657
*/
1658
#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM
1659
bool can1_term = g.can_terminate[0];
1660
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH
1661
can1_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH);
1662
# endif
1663
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term);
1664
# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED
1665
palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON);
1666
# endif
1667
#endif
1668
1669
#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM
1670
bool can2_term = g.can_terminate[1];
1671
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH
1672
can2_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH);
1673
# endif
1674
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term);
1675
# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED
1676
palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON);
1677
# endif
1678
#endif
1679
1680
#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM
1681
bool can3_term = g.can_terminate[2];
1682
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH
1683
can3_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH);
1684
# endif
1685
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term);
1686
# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED
1687
palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON);
1688
# endif
1689
#endif
1690
}
1691
1692
for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {
1693
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1694
can_iface_periph[i] = NEW_NOTHROW ChibiOS::CANIface();
1695
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
1696
can_iface_periph[i] = NEW_NOTHROW HALSITL::CANIface();
1697
#endif
1698
instances[i].iface = can_iface_periph[i];
1699
instances[i].index = i;
1700
#if HAL_PERIPH_CAN_MIRROR
1701
if ((g.can_mirror_ports & (1U << i)) != 0) {
1702
instances[i].mirror_queue = NEW_NOTHROW ObjectBuffer<AP_HAL::CANFrame> (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE);
1703
}
1704
#endif //HAL_PERIPH_CAN_MIRROR
1705
#if HAL_NUM_CAN_IFACES >= 2
1706
can_protocol_cached[i] = g.can_protocol[i];
1707
CANSensor::set_periph(i, can_protocol_cached[i], can_iface_periph[i]);
1708
#endif
1709
if (can_iface_periph[i] != nullptr) {
1710
#if HAL_CANFD_SUPPORTED
1711
can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U);
1712
#else
1713
can_iface_periph[i]->init(g.can_baudrate[i]);
1714
#endif
1715
}
1716
}
1717
1718
#if AP_CAN_SLCAN_ENABLED
1719
const uint8_t slcan_selected_index = g.can_slcan_cport - 1;
1720
if (slcan_selected_index < HAL_NUM_CAN_IFACES) {
1721
slcan_interface.set_can_iface(can_iface_periph[slcan_selected_index]);
1722
instances[slcan_selected_index].iface = (AP_HAL::CANIface*)&slcan_interface;
1723
1724
// ensure there's a serial port mapped to SLCAN
1725
if (!serial_manager.have_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)) {
1726
serial_manager.set_protocol_and_baud(SERIALMANAGER_NUM_PORTS-1, AP_SerialManager::SerialProtocol_SLCAN, 1500000);
1727
}
1728
}
1729
#endif
1730
1731
canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool),
1732
onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, this);
1733
1734
if (user_set_node_id != CANARD_BROADCAST_NODE_ID) {
1735
canardSetLocalNodeID(&dronecan.canard, user_set_node_id);
1736
}
1737
}
1738
1739
1740
#if AP_PERIPH_RC_OUT_ENABLED
1741
#if HAL_WITH_ESC_TELEM
1742
// try to map the ESC number to a motor number. This is needed
1743
// for when we have multiple CAN nodes, one for each ESC
1744
uint8_t AP_Periph_FW::get_motor_number(const uint8_t esc_number) const
1745
{
1746
const auto *channel = SRV_Channels::srv_channel(esc_number);
1747
// try to map the ESC number to a motor number. This is needed
1748
// for when we have multiple CAN nodes, one for each ESC
1749
if (channel == nullptr) {
1750
return esc_number;
1751
}
1752
const int8_t motor_num = channel->get_motor_num();
1753
return (motor_num == -1) ? esc_number : motor_num;
1754
}
1755
1756
/*
1757
send ESC status packets based on AP_ESC_Telem
1758
*/
1759
void AP_Periph_FW::esc_telem_update()
1760
{
1761
uint32_t mask = esc_telem.get_active_esc_mask();
1762
while (mask != 0) {
1763
int8_t i = __builtin_ffs(mask) - 1;
1764
mask &= ~(1U<<i);
1765
const float nan = nanf("");
1766
uavcan_equipment_esc_Status pkt {};
1767
pkt.esc_index = get_motor_number(i);
1768
1769
if (!esc_telem.get_voltage(i, pkt.voltage)) {
1770
pkt.voltage = nan;
1771
}
1772
if (!esc_telem.get_current(i, pkt.current)) {
1773
pkt.current = nan;
1774
}
1775
int16_t temperature;
1776
if (esc_telem.get_motor_temperature(i, temperature)) {
1777
pkt.temperature = C_TO_KELVIN(temperature*0.01);
1778
} else if (esc_telem.get_temperature(i, temperature)) {
1779
pkt.temperature = C_TO_KELVIN(temperature*0.01);
1780
} else {
1781
pkt.temperature = nan;
1782
}
1783
float rpm;
1784
float error_rate;
1785
if (esc_telem.get_raw_rpm_and_error_rate(i, rpm, error_rate)) {
1786
pkt.rpm = rpm;
1787
pkt.error_count = error_rate;
1788
}
1789
1790
#if AP_EXTENDED_ESC_TELEM_ENABLED
1791
uint8_t power_rating_pct;
1792
if (esc_telem.get_power_percentage(i, power_rating_pct)) {
1793
pkt.power_rating_pct = power_rating_pct;
1794
}
1795
#endif
1796
1797
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
1798
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
1799
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
1800
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
1801
CANARD_TRANSFER_PRIORITY_LOW,
1802
&buffer[0],
1803
total_size);
1804
}
1805
}
1806
#endif // HAL_WITH_ESC_TELEM
1807
1808
#if AP_EXTENDED_ESC_TELEM_ENABLED
1809
void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)
1810
{
1811
if (g.esc_extended_telem_rate <= 0) {
1812
// Not configured to send
1813
return;
1814
}
1815
1816
uint32_t mask = esc_telem.get_active_esc_mask();
1817
if (mask == 0) {
1818
// No ESCs to report
1819
return;
1820
}
1821
1822
// ESCs are sent in turn to minimise used bandwidth, to make the rate param match the status message we multiply
1823
// the period such that the param gives the per-esc rate
1824
const uint32_t update_period_ms = 1000 / constrain_int32(g.esc_extended_telem_rate.get() * __builtin_popcount(mask), 1, 1000);
1825
if (now_ms - last_esc_telem_extended_update < update_period_ms) {
1826
// Too soon!
1827
return;
1828
}
1829
last_esc_telem_extended_update = now_ms;
1830
1831
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
1832
// Send each ESC in turn
1833
const uint8_t index = (last_esc_telem_extended_sent_id + 1 + i) % ESC_TELEM_MAX_ESCS;
1834
1835
if ((mask & (1U << index)) == 0) {
1836
// Not enabled
1837
continue;
1838
}
1839
1840
uavcan_equipment_esc_StatusExtended pkt {};
1841
1842
// Only send if we have data
1843
bool have_data = false;
1844
1845
int16_t motor_temp_cdeg;
1846
if (esc_telem.get_motor_temperature(index, motor_temp_cdeg)) {
1847
// Convert from centi-degrees to degrees
1848
pkt.motor_temperature_degC = motor_temp_cdeg * 0.01;
1849
have_data = true;
1850
}
1851
1852
have_data |= esc_telem.get_input_duty(index, pkt.input_pct);
1853
have_data |= esc_telem.get_output_duty(index, pkt.output_pct);
1854
have_data |= esc_telem.get_flags(index, pkt.status_flags);
1855
1856
if (have_data) {
1857
pkt.esc_index = get_motor_number(index);
1858
1859
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE];
1860
const uint16_t total_size = uavcan_equipment_esc_StatusExtended_encode(&pkt, buffer, !canfdout());
1861
1862
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE,
1863
UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID,
1864
CANARD_TRANSFER_PRIORITY_LOW,
1865
&buffer[0],
1866
total_size);
1867
}
1868
1869
last_esc_telem_extended_sent_id = index;
1870
break;
1871
}
1872
}
1873
#endif
1874
1875
#if AP_PERIPH_ESC_APD_ENABLED
1876
void AP_Periph_FW::apd_esc_telem_update()
1877
{
1878
for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {
1879
if (apd_esc_telem[i] == nullptr) {
1880
continue;
1881
}
1882
ESC_APD_Telem &esc = *apd_esc_telem[i];
1883
1884
if (esc.update()) {
1885
const ESC_APD_Telem::telem &t = esc.get_telem();
1886
1887
uavcan_equipment_esc_Status pkt {};
1888
static_assert(APD_ESC_INSTANCES <= ARRAY_SIZE(g.esc_number), "There must be an ESC instance number for each APD ESC");
1889
pkt.esc_index = g.esc_number[i];
1890
pkt.voltage = t.voltage;
1891
pkt.current = t.current;
1892
pkt.temperature = t.temperature;
1893
pkt.rpm = t.rpm;
1894
pkt.power_rating_pct = t.power_rating_pct;
1895
pkt.error_count = t.error_count;
1896
1897
uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];
1898
uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());
1899
canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,
1900
UAVCAN_EQUIPMENT_ESC_STATUS_ID,
1901
CANARD_TRANSFER_PRIORITY_LOW,
1902
&buffer[0],
1903
total_size);
1904
}
1905
}
1906
1907
}
1908
#endif // AP_PERIPH_ESC_APD_ENABLED
1909
#endif // AP_PERIPH_RC_OUT_ENABLED
1910
1911
void AP_Periph_FW::can_update()
1912
{
1913
const uint32_t now = AP_HAL::millis();
1914
const uint32_t led_pattern = 0xAAAA;
1915
const uint32_t led_change_period = 50;
1916
static uint8_t led_idx = 0;
1917
static uint32_t last_led_change;
1918
1919
if ((now - last_led_change > led_change_period) && no_iface_finished_dna) {
1920
// blink LED in recognisable pattern while waiting for DNA
1921
#ifdef HAL_GPIO_PIN_LED
1922
palWriteLine(HAL_GPIO_PIN_LED, (led_pattern & (1U<<led_idx))?1:0);
1923
#elif defined(HAL_GPIO_PIN_SAFE_LED)
1924
// or use safety LED if defined
1925
palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U<<led_idx))?1:0);
1926
#else
1927
(void)led_pattern;
1928
(void)led_idx;
1929
#endif
1930
led_idx = (led_idx+1) % 32;
1931
last_led_change = now;
1932
}
1933
1934
if (AP_HAL::millis() > dronecan.send_next_node_id_allocation_request_at_ms) {
1935
can_do_dna();
1936
}
1937
1938
static uint32_t last_1Hz_ms;
1939
if (now - last_1Hz_ms >= 1000) {
1940
last_1Hz_ms = now;
1941
process1HzTasks(AP_HAL::micros64());
1942
}
1943
1944
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1945
if (!hal.run_in_maintenance_mode())
1946
#endif
1947
{
1948
#if AP_PERIPH_MAG_ENABLED
1949
can_mag_update();
1950
#endif
1951
#if AP_PERIPH_GPS_ENABLED
1952
can_gps_update();
1953
#endif
1954
#if AP_UART_MONITOR_ENABLED
1955
send_serial_monitor_data();
1956
#endif
1957
#if AP_PERIPH_BATTERY_ENABLED
1958
can_battery_update();
1959
#endif
1960
#if AP_PERIPH_BARO_ENABLED
1961
can_baro_update();
1962
#endif
1963
#if AP_PERIPH_AIRSPEED_ENABLED
1964
can_airspeed_update();
1965
#endif
1966
#if AP_PERIPH_RANGEFINDER_ENABLED
1967
can_rangefinder_update();
1968
#endif
1969
#if AP_PERIPH_PROXIMITY_ENABLED
1970
can_proximity_update();
1971
#endif
1972
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NOTIFY_ENABLED
1973
can_buzzer_update();
1974
#endif
1975
#ifdef HAL_GPIO_PIN_SAFE_LED
1976
can_safety_LED_update();
1977
#endif
1978
#ifdef HAL_GPIO_PIN_SAFE_BUTTON
1979
can_safety_button_update();
1980
#endif
1981
#if AP_PERIPH_PWM_HARDPOINT_ENABLED
1982
pwm_hardpoint_update();
1983
#endif
1984
#if AP_PERIPH_HOBBYWING_ESC_ENABLED
1985
hwesc_telem_update();
1986
#endif
1987
#if AP_PERIPH_ESC_APD_ENABLED
1988
apd_esc_telem_update();
1989
#endif
1990
#if AP_PERIPH_MSP_ENABLED
1991
msp_sensor_update();
1992
#endif
1993
#if AP_PERIPH_RC_OUT_ENABLED
1994
rcout_update();
1995
#endif
1996
#if AP_PERIPH_EFI_ENABLED
1997
can_efi_update();
1998
#endif
1999
#if AP_PERIPH_DEVICE_TEMPERATURE_ENABLED
2000
temperature_sensor_update();
2001
#endif
2002
#if AP_PERIPH_RPM_STREAM_ENABLED
2003
rpm_sensor_send();
2004
#endif
2005
}
2006
const uint32_t now_us = AP_HAL::micros();
2007
while ((AP_HAL::micros() - now_us) < 1000) {
2008
hal.scheduler->delay_microseconds(HAL_PERIPH_LOOP_DELAY_US);
2009
2010
#if HAL_CANFD_SUPPORTED
2011
// allow for user enabling/disabling CANFD at runtime
2012
dronecan.canard.tao_disabled = g.can_fdmode == 1;
2013
#endif
2014
{
2015
WITH_SEMAPHORE(canard_broadcast_semaphore);
2016
processTx();
2017
processRx();
2018
#if HAL_PERIPH_CAN_MIRROR
2019
processMirror();
2020
#endif // HAL_PERIPH_CAN_MIRROR
2021
2022
}
2023
}
2024
2025
// if there is a reboot scheduled, do it 1 second after request to allow the acknowledgement to be sent
2026
if (reboot_request_ms != 0 && (AP_HAL::millis() - reboot_request_ms > 1000)) {
2027
prepare_reboot();
2028
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
2029
NVIC_SystemReset();
2030
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
2031
HAL_SITL::actually_reboot();
2032
#endif
2033
}
2034
}
2035
2036
// printf to CAN LogMessage for debugging
2037
void can_vprintf(uint8_t severity, const char *fmt, va_list ap)
2038
{
2039
// map MAVLink levels to CAN levels
2040
uint8_t level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;
2041
switch (severity) {
2042
case MAV_SEVERITY_DEBUG:
2043
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;
2044
break;
2045
case MAV_SEVERITY_INFO:
2046
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_INFO;
2047
break;
2048
case MAV_SEVERITY_NOTICE:
2049
case MAV_SEVERITY_WARNING:
2050
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_WARNING;
2051
break;
2052
case MAV_SEVERITY_ERROR:
2053
case MAV_SEVERITY_CRITICAL:
2054
case MAV_SEVERITY_ALERT:
2055
case MAV_SEVERITY_EMERGENCY:
2056
level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_ERROR;
2057
break;
2058
}
2059
2060
#if HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF
2061
const uint8_t packet_count_max = 4; // how many packets we're willing to break up an over-sized string into
2062
const uint8_t packet_data_max = 90; // max single debug string length = sizeof(uavcan_protocol_debug_LogMessage.text.data)
2063
uint8_t buffer_data[packet_count_max*packet_data_max] {};
2064
2065
// strip off any negative return errors by treating result as 0
2066
uint32_t char_count = MAX(vsnprintf((char*)buffer_data, sizeof(buffer_data), fmt, ap), 0);
2067
2068
// send multiple uavcan_protocol_debug_LogMessage packets if the fmt string is too long.
2069
uint16_t buffer_offset = 0;
2070
for (uint8_t i=0; i<packet_count_max && char_count > 0; i++) {
2071
uavcan_protocol_debug_LogMessage pkt {};
2072
pkt.level.value = level;
2073
pkt.text.len = MIN(char_count, sizeof(pkt.text.data));
2074
char_count -= pkt.text.len;
2075
2076
memcpy(pkt.text.data, &buffer_data[buffer_offset], pkt.text.len);
2077
buffer_offset += pkt.text.len;
2078
2079
uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
2080
const uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer_packet, !periph.canfdout());
2081
2082
periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
2083
UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
2084
CANARD_TRANSFER_PRIORITY_LOW,
2085
buffer_packet,
2086
len);
2087
}
2088
2089
#else
2090
uavcan_protocol_debug_LogMessage pkt {};
2091
uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];
2092
uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
2093
pkt.level.value = level;
2094
pkt.text.len = MIN(n, sizeof(pkt.text.data));
2095
2096
uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer, !periph.canfdout());
2097
2098
periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
2099
UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
2100
CANARD_TRANSFER_PRIORITY_LOW,
2101
buffer,
2102
len);
2103
2104
#endif
2105
}
2106
2107
// printf to CAN LogMessage for debugging, with severity
2108
void can_printf_severity(uint8_t severity, const char *fmt, ...)
2109
{
2110
va_list ap;
2111
va_start(ap, fmt);
2112
can_vprintf(severity, fmt, ap);
2113
va_end(ap);
2114
}
2115
2116
// printf to CAN LogMessage for debugging, with DEBUG level
2117
void can_printf(const char *fmt, ...)
2118
{
2119
va_list ap;
2120
va_start(ap, fmt);
2121
can_vprintf(MAV_SEVERITY_DEBUG, fmt, ap);
2122
va_end(ap);
2123
}
2124
2125