forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 5
Expand file tree
/
Copy pathcan.cpp
More file actions
2126 lines (1896 loc) · 71.9 KB
/
can.cpp
File metadata and controls
2126 lines (1896 loc) · 71.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
AP_Periph can support
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL_Boards.h>
#include "AP_Periph.h"
#include <stdio.h>
#include <drivers/stm32/canard_stm32.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/utility/RingBuffer.h>
#include <AP_Common/AP_FWVersion.h>
#include <dronecan_msgs.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <hal.h>
#include <AP_HAL_ChibiOS/CANIface.h>
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL/CANSocketIface.h>
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#endif
#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U)
#include "i2c.h"
#include <utility>
#if HAL_NUM_CAN_IFACES >= 2
#include <AP_CANManager/AP_CANSensor.h>
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
extern const HAL_SITL &hal;
#else
extern const AP_HAL::HAL &hal;
#endif
extern AP_Periph_FW periph;
#ifndef HAL_PERIPH_LOOP_DELAY_US
// delay between can loop updates. This needs to be longer on F4
#if defined(STM32H7)
#define HAL_PERIPH_LOOP_DELAY_US 64
#else
#define HAL_PERIPH_LOOP_DELAY_US 1024
#endif
#endif
// timeout all frames at 1s
#define CAN_FRAME_TIMEOUT 1000000ULL
#define DEBUG_PKTS 0
#if HAL_PERIPH_CAN_MIRROR
#ifndef HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE
#define HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE 64
#endif
#endif //HAL_PERIPH_CAN_MIRROR
#ifndef HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF
// When enabled, can_printf() strings longer than the droneCAN max text length (90 chars)
// are split into multiple packets instead of truncating the string. This is
// especially helpful with HAL_GCS_ENABLED where libraries use the mavlink
// send_text() method where we support strings up to 256 chars by splitting them
// up into multiple 50 char mavlink packets.
#define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF (HAL_PROGRAM_SIZE_LIMIT_KB >= 1024)
#endif
static struct instance_t {
uint8_t index;
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
AP_HAL::CANIface* iface;
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
HALSITL::CANIface* iface;
#endif
#if HAL_PERIPH_CAN_MIRROR
#if HAL_NUM_CAN_IFACES < 2
#error "Can't use HAL_PERIPH_CAN_MIRROR if there are not at least 2 HAL_NUM_CAN_IFACES"
#endif
ObjectBuffer<AP_HAL::CANFrame> *mirror_queue;
uint8_t mirror_fail_count;
#endif // HAL_PERIPH_CAN_MIRROR
} instances[HAL_NUM_CAN_IFACES];
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) && (HAL_NUM_CAN_IFACES >= 2)
static ioline_t can_term_lines[] = {
HAL_GPIO_PIN_TERMCAN1
#if HAL_NUM_CAN_IFACES > 2
#ifdef HAL_GPIO_PIN_TERMCAN2
,HAL_GPIO_PIN_TERMCAN2
#else
#error "Only one Can Terminator defined with over two CAN Ifaces"
#endif
#endif
#if HAL_NUM_CAN_IFACES > 2
#ifdef HAL_GPIO_PIN_TERMCAN3
,HAL_GPIO_PIN_TERMCAN3
#else
#error "Only two Can Terminator defined with three CAN Ifaces"
#endif
#endif
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1)
uint8_t user_set_node_id = HAL_CAN_DEFAULT_NODE_ID;
#ifndef AP_PERIPH_PROBE_CONTINUOUS
#define AP_PERIPH_PROBE_CONTINUOUS 0
#endif
#ifndef AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz
#define AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz 1
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
ChibiOS::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
HALSITL::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];
#endif
#if AP_CAN_SLCAN_ENABLED
SLCAN::CANIface AP_Periph_FW::slcan_interface;
#endif
#ifdef EXT_FLASH_SIZE_MB
static_assert(EXT_FLASH_SIZE_MB == 0, "DroneCAN bootloader cannot support external flash");
#endif
/*
* Node status variables
*/
static uavcan_protocol_NodeStatus node_status;
#if HAL_ENABLE_SENDING_STATS
static dronecan_protocol_Stats protocol_stats;
#endif
/**
* Returns a pseudo random integer in a given range
*/
static uint16_t get_random_range(uint16_t range)
{
return get_random16() % range;
}
/*
get cpu unique ID
*/
static void readUniqueID(uint8_t* out_uid)
{
uint8_t len = sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data);
memset(out_uid, 0, len);
hal.util->get_system_id_unformatted(out_uid, len);
}
/*
handle a GET_NODE_INFO request
*/
void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,
CanardRxTransfer* transfer)
{
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
uavcan_protocol_GetNodeInfoResponse pkt {};
node_status.uptime_sec = AP_HAL::millis() / 1000U;
pkt.status = node_status;
pkt.software_version.major = AP::fwversion().major;
pkt.software_version.minor = AP::fwversion().minor;
pkt.software_version.optional_field_flags = UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT | UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC;
pkt.software_version.vcs_commit = app_descriptor.git_hash;
uint32_t *crc = (uint32_t *)&pkt.software_version.image_crc;
crc[0] = app_descriptor.image_crc1;
crc[1] = app_descriptor.image_crc2;
readUniqueID(pkt.hardware_version.unique_id);
// use hw major/minor for APJ_BOARD_ID so we know what fw is
// compatible with this hardware
pkt.hardware_version.major = APJ_BOARD_ID >> 8;
pkt.hardware_version.minor = APJ_BOARD_ID & 0xFF;
if (g.serial_number > 0) {
hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s(%u)", CAN_APP_NODE_NAME, (unsigned)g.serial_number);
} else {
hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);
}
pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));
uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !canfdout());
canard_respond(canard_instance,
transfer,
UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
UAVCAN_PROTOCOL_GETNODEINFO_ID,
&buffer[0],
total_size);
}
// compatability code added Mar 2024 for 4.6:
#ifndef AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
#define AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED 1
#endif
/*
handle parameter GetSet request
*/
void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
// param fetch all can take a long time, so pat watchdog
stm32_watchdog_pat();
uavcan_protocol_param_GetSetRequest req;
if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) {
return;
}
uavcan_protocol_param_GetSetResponse pkt {};
AP_Param *vp;
enum ap_var_type ptype;
if (req.name.len != 0 && req.name.len > AP_MAX_NAME_SIZE) {
vp = nullptr;
} else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) {
memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);
#if AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED
// cope with older versions of ArduPilot attempting to
// auto-configure AP_Periph using "GPS_TYPE" by
// auto-converting to "GPS1_TYPE":
if (strncmp((char*)req.name.data, "GPS_TYPE", req.name.len) == 0) {
vp = AP_Param::find("GPS1_TYPE", &ptype);
} else {
vp = AP_Param::find((char *)pkt.name.data, &ptype);
}
#else
vp = AP_Param::find((char *)pkt.name.data, &ptype);
#endif
} else {
AP_Param::ParamToken token {};
vp = AP_Param::find_by_index(req.index, &ptype, &token);
if (vp != nullptr) {
vp->copy_name_token(token, (char *)pkt.name.data, AP_MAX_NAME_SIZE+1, true);
}
}
if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) {
// param set
switch (ptype) {
case AP_PARAM_INT8:
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
return;
}
((AP_Int8 *)vp)->set_and_save_ifchanged(req.value.integer_value);
break;
case AP_PARAM_INT16:
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
return;
}
((AP_Int16 *)vp)->set_and_save_ifchanged(req.value.integer_value);
break;
case AP_PARAM_INT32:
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
return;
}
((AP_Int32 *)vp)->set_and_save_ifchanged(req.value.integer_value);
break;
case AP_PARAM_FLOAT:
if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) {
return;
}
((AP_Float *)vp)->set_and_save_ifchanged(req.value.real_value);
break;
default:
return;
}
}
if (vp != nullptr) {
switch (ptype) {
case AP_PARAM_INT8:
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
pkt.value.integer_value = ((AP_Int8 *)vp)->get();
break;
case AP_PARAM_INT16:
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
pkt.value.integer_value = ((AP_Int16 *)vp)->get();
break;
case AP_PARAM_INT32:
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
pkt.value.integer_value = ((AP_Int32 *)vp)->get();
break;
case AP_PARAM_FLOAT:
pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;
pkt.value.real_value = ((AP_Float *)vp)->get();
break;
default:
return;
}
pkt.name.len = strnlen((char *)pkt.name.data, sizeof(pkt.name.data));
}
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE];
uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout());
canard_respond(canard_instance,
transfer,
UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE,
UAVCAN_PROTOCOL_PARAM_GETSET_ID,
&buffer[0],
total_size);
}
/*
handle parameter executeopcode request
*/
void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_protocol_param_ExecuteOpcodeRequest req;
if (uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &req)) {
return;
}
if (req.opcode == UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE) {
StorageManager::erase();
AP_Param::erase_all();
AP_Param::load_all();
AP_Param::setup_sketch_defaults();
#if AP_PERIPH_GPS_ENABLED
AP_Param::setup_object_defaults(&gps, gps.var_info);
#endif
#if AP_PERIPH_BATTERY_ENABLED
AP_Param::setup_object_defaults(&battery, battery_lib.var_info);
#endif
#if AP_PERIPH_MAG_ENABLED
AP_Param::setup_object_defaults(&compass, compass.var_info);
#endif
#if AP_PERIPH_BARO_ENABLED
AP_Param::setup_object_defaults(&baro, baro.var_info);
#endif
#if AP_PERIPH_AIRSPEED_ENABLED
AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);
#endif
#if AP_PERIPH_RANGEFINDER_ENABLED
AP_Param::setup_object_defaults(&rangefinder, rangefinder.var_info);
#endif
}
uavcan_protocol_param_ExecuteOpcodeResponse pkt {};
pkt.ok = true;
uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE];
uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout());
canard_respond(canard_instance,
transfer,
UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE,
UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID,
&buffer[0],
total_size);
}
void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
#if HAL_RAM_RESERVE_START >= 256
// setup information on firmware request at start of ram
auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;
if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
memset(comms, 0, sizeof(*comms));
}
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
uavcan_protocol_file_BeginFirmwareUpdateRequest req;
if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) {
return;
}
comms->server_node_id = req.source_node_id;
if (comms->server_node_id == 0) {
comms->server_node_id = transfer->source_node_id;
}
memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len);
comms->my_node_id = canardGetLocalNodeID(canard_instance);
uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];
uavcan_protocol_file_BeginFirmwareUpdateResponse reply {};
reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK;
uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !canfdout());
canard_respond(canard_instance,
transfer,
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE,
UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID,
&buffer[0],
total_size);
uint8_t count = 50;
while (count--) {
processTx();
hal.scheduler->delay(1);
}
#endif
// instant reboot, with backup register used to give bootloader
// the node_id
prepare_reboot();
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(canard_instance)));
NVIC_SystemReset();
#endif
}
void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
// Rule C - updating the randomized time interval
dronecan.send_next_node_id_allocation_request_at_ms =
AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)
{
printf("Allocation request from another allocatee\n");
dronecan.node_id_allocation_unique_id_offset = 0;
return;
}
// Copying the unique ID from the message
uavcan_protocol_dynamic_node_id_Allocation msg;
if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) {
// failed decode
return;
}
// Obtaining the local unique ID
uint8_t my_unique_id[sizeof(msg.unique_id.data)];
readUniqueID(my_unique_id);
// Matching the received UID against the local one
if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {
printf("Mismatching allocation response\n");
dronecan.node_id_allocation_unique_id_offset = 0;
return; // No match, return
}
if (msg.unique_id.len < sizeof(msg.unique_id.data)) {
// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
dronecan.node_id_allocation_unique_id_offset = msg.unique_id.len;
dronecan.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
printf("Matching allocation response: %d\n", msg.unique_id.len);
} else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over)
// Allocation complete - copying the allocated node ID from the message
canardSetLocalNodeID(canard_instance, msg.node_id);
printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id);
#if AP_PERIPH_GPS_ENABLED && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE
if (g.gps_mb_only_can_port) {
// we need to assign the unallocated port to be used for Moving Baseline only
gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES;
if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {
// copy node id from the primary iface
canardSetLocalNodeID(&dronecan.canard, msg.node_id);
#ifdef HAL_GPIO_PIN_TERMCAN1
// also terminate the line as we don't have any other device on this port
palWriteLine(can_term_lines[gps_mb_can_port], 1);
#endif
}
}
#endif
}
}
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
static uint8_t safety_state;
/*
handle SafetyState
*/
void AP_Periph_FW::handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
ardupilot_indication_SafetyState req;
if (ardupilot_indication_SafetyState_decode(transfer, &req)) {
return;
}
safety_state = req.status;
#if AP_PERIPH_SAFETY_SWITCH_ENABLED
rcout_handle_safety_state(safety_state);
#endif
}
#endif // HAL_GPIO_PIN_SAFE_LED
/*
handle ArmingStatus
*/
void AP_Periph_FW::handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_equipment_safety_ArmingStatus req;
if (uavcan_equipment_safety_ArmingStatus_decode(transfer, &req)) {
return;
}
hal.util->set_soft_armed(req.status == UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED);
}
#if AP_PERIPH_RTC_GLOBALTIME_ENABLED
/*
handle GlobalTime
*/
void AP_Periph_FW::handle_globaltime(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
dronecan_protocol_GlobalTime req;
if (dronecan_protocol_GlobalTime_decode(transfer, &req)) {
return;
}
AP::rtc().set_utc_usec(req.timestamp.usec, AP_RTC::source_type::SOURCE_GPS);
}
#endif // AP_PERIPH_RTC_GLOBALTIME_ENABLED
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
{
#if AP_PERIPH_NOTIFY_ENABLED
notify.handle_rgb(red, green, blue);
#if AP_PERIPH_RC_OUT_ENABLED
rcout_has_new_data_to_update = true;
#endif // AP_PERIPH_RC_OUT_ENABLED
#endif // AP_PERIPH_NOTIFY_ENABLED
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
#endif // HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
#if AP_PERIPH_NCP5623_LED_WITHOUT_NOTIFY_ENABLED
{
const uint8_t i2c_address = 0x38;
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
if (!dev) {
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
}
WITH_SEMAPHORE(dev->get_semaphore());
dev->set_retries(0);
uint8_t v = 0x3f; // enable LED
dev->transfer(&v, 1, nullptr, 0);
v = 0x40 | red >> 3; // red
dev->transfer(&v, 1, nullptr, 0);
v = 0x60 | green >> 3; // green
dev->transfer(&v, 1, nullptr, 0);
v = 0x80 | blue >> 3; // blue
dev->transfer(&v, 1, nullptr, 0);
}
#endif // AP_PERIPH_NCP5623_LED_WITHOUT_NOTIFY_ENABLED
#if AP_PERIPH_NCP5623_BGR_LED_WITHOUT_NOTIFY_ENABLED
{
const uint8_t i2c_address = 0x38;
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
if (!dev) {
dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));
}
WITH_SEMAPHORE(dev->get_semaphore());
dev->set_retries(0);
uint8_t v = 0x3f; // enable LED
dev->transfer(&v, 1, nullptr, 0);
v = 0x40 | blue >> 3; // blue
dev->transfer(&v, 1, nullptr, 0);
v = 0x60 | green >> 3; // green
dev->transfer(&v, 1, nullptr, 0);
v = 0x80 | red >> 3; // red
dev->transfer(&v, 1, nullptr, 0);
}
#endif // AP_PERIPH_NCP5623_BGR_LED_WITHOUT_NOTIFY_ENABLED
#if AP_PERIPH_TOSHIBA_LED_WITHOUT_NOTIFY_ENABLED
{
#define TOSHIBA_LED_PWM0 0x01 // pwm0 register
#define TOSHIBA_LED_ENABLE 0x04 // enable register
#define TOSHIBA_LED_I2C_ADDR 0x55 // default I2C bus address
static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_toshiba;
if (!dev_toshiba) {
dev_toshiba = std::move(hal.i2c_mgr->get_device(0, TOSHIBA_LED_I2C_ADDR));
}
WITH_SEMAPHORE(dev_toshiba->get_semaphore());
dev_toshiba->set_retries(0); // use 0 because this is running on main thread.
// enable the led
dev_toshiba->write_register(TOSHIBA_LED_ENABLE, 0x03);
/* 4-bit for each color */
uint8_t val[4] = {
TOSHIBA_LED_PWM0,
(uint8_t)(blue >> 4),
(uint8_t)(green / 16),
(uint8_t)(red / 16)
};
dev_toshiba->transfer(val, sizeof(val), nullptr, 0);
}
#endif // AP_PERIPH_TOSHIBA_LED_WITHOUT_NOTIFY_ENABLED
}
/*
handle lightscommand
*/
void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_equipment_indication_LightsCommand req;
if (uavcan_equipment_indication_LightsCommand_decode(transfer, &req)) {
return;
}
for (uint8_t i=0; i<req.commands.len; i++) {
uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];
// to get the right color proportions we scale the green so that is uses the
// same number of bits as red and blue
uint8_t red = cmd.color.red<<3U;
uint8_t green = (cmd.color.green>>1U)<<3U;
uint8_t blue = cmd.color.blue<<3U;
#if AP_PERIPH_NOTIFY_ENABLED
const int8_t brightness = notify.get_rgb_led_brightness_percent();
#elif AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
const int8_t brightness = g.led_brightness;
#endif
if (brightness != 100 && brightness >= 0) {
const float scale = brightness * 0.01;
red = constrain_int16(red * scale, 0, 255);
green = constrain_int16(green * scale, 0, 255);
blue = constrain_int16(blue * scale, 0, 255);
}
set_rgb_led(red, green, blue);
}
}
#endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
#if AP_PERIPH_RC_OUT_ENABLED
void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_equipment_esc_RawCommand cmd;
if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) {
return;
}
rcout_esc(cmd.cmd.data, cmd.cmd.len);
// Update internal copy for disabling output to ESC when CAN packets are lost
last_esc_num_channels = cmd.cmd.len;
last_esc_raw_command_ms = AP_HAL::millis();
}
void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_equipment_actuator_ArrayCommand cmd;
if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) {
return;
}
bool valid_output = false;
for (uint8_t i=0; i < cmd.commands.len; i++) {
const auto &c = cmd.commands.data[i];
switch (c.command_type) {
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS:
rcout_srv_unitless(c.actuator_id, c.command_value);
valid_output = true;
break;
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM:
rcout_srv_PWM(c.actuator_id, c.command_value);
valid_output = true;
break;
}
}
if (valid_output) {
actuator.last_command_ms = AP_HAL::millis();
}
}
#endif // AP_PERIPH_RC_OUT_ENABLED
#if AP_PERIPH_NOTIFY_ENABLED
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
ardupilot_indication_NotifyState msg;
if (ardupilot_indication_NotifyState_decode(transfer, &msg)) {
return;
}
if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) {
uint16_t tmp = 0;
memcpy(&tmp, msg.aux_data.data, sizeof(tmp));
yaw_earth = radians((float)tmp * 0.01f);
}
vehicle_state = msg.vehicle_state;
last_vehicle_state_ms = AP_HAL::millis();
}
#endif // AP_PERIPH_NOTIFY_ENABLED
#ifdef HAL_GPIO_PIN_SAFE_LED
/*
update safety LED
*/
void AP_Periph_FW::can_safety_LED_update(void)
{
static uint32_t last_update_ms;
switch (safety_state) {
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF:
palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON);
break;
case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: {
uint32_t now = AP_HAL::millis();
if (now - last_update_ms > 100) {
last_update_ms = now;
static uint8_t led_counter;
const uint16_t led_pattern = 0x5500;
led_counter = (led_counter+1) % 16;
palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U << led_counter))?!SAFE_LED_ON:SAFE_LED_ON);
}
break;
}
default:
palWriteLine(HAL_GPIO_PIN_SAFE_LED, !SAFE_LED_ON);
break;
}
}
#endif // HAL_GPIO_PIN_SAFE_LED
#ifdef HAL_GPIO_PIN_SAFE_BUTTON
#ifndef HAL_SAFE_BUTTON_ON
#define HAL_SAFE_BUTTON_ON 1
#endif
/*
update safety button
*/
void AP_Periph_FW::can_safety_button_update(void)
{
static uint32_t last_update_ms;
static uint8_t counter;
uint32_t now = AP_HAL::millis();
// send at 10Hz when pressed
if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) {
counter = 0;
return;
}
if (now - last_update_ms < 100) {
return;
}
if (counter < 255) {
counter++;
}
last_update_ms = now;
ardupilot_indication_Button pkt {};
pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY;
pkt.press_time = counter;
uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE];
uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout());
canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE,
ARDUPILOT_INDICATION_BUTTON_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer[0],
total_size);
}
#endif // HAL_GPIO_PIN_SAFE_BUTTON
/**
* This callback is invoked by the library when a new message or request or response is received.
*/
void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
CanardRxTransfer* transfer)
{
#ifdef HAL_GPIO_PIN_LED_CAN1
palToggleLine(HAL_GPIO_PIN_LED_CAN1);
#endif
#if HAL_CANFD_SUPPORTED
// enable tao for decoding when not on CANFD
transfer->tao = !transfer->canfd;
#endif
/*
* Dynamic node ID allocation protocol.
* Taking this branch only if we don't have a node ID, ignoring otherwise.
*/
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) {
if (transfer->transfer_type == CanardTransferTypeBroadcast &&
transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
handle_allocation_response(canard_instance, transfer);
}
return;
}
switch (transfer->data_type_id) {
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
handle_get_node_info(canard_instance, transfer);
break;
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
handle_begin_firmware_update(canard_instance, transfer);
break;
case UAVCAN_PROTOCOL_RESTARTNODE_ID: {
printf("RestartNode\n");
uavcan_protocol_RestartNodeResponse pkt {
ok: true,
};
uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];
uint16_t total_size = uavcan_protocol_RestartNodeResponse_encode(&pkt, buffer, !canfdout());
canard_respond(canard_instance,
transfer,
UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE,
UAVCAN_PROTOCOL_RESTARTNODE_ID,
&buffer[0],
total_size);
// schedule a reboot to occur
reboot_request_ms = AP_HAL::millis();
}
break;
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
handle_param_getset(canard_instance, transfer);
break;
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
handle_param_executeopcode(canard_instance, transfer);
break;
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NOTIFY_ENABLED
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
handle_beep_command(canard_instance, transfer);
break;
#endif
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
handle_safety_state(canard_instance, transfer);
break;
#endif
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
handle_arming_status(canard_instance, transfer);
break;
#if AP_PERIPH_GPS_ENABLED
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
handle_RTCMStream(canard_instance, transfer);
break;
#if GPS_MOVING_BASELINE
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
handle_MovingBaselineData(canard_instance, transfer);
break;
#endif
#endif // AP_PERIPH_GPS_ENABLED
#if AP_UART_MONITOR_ENABLED
case UAVCAN_TUNNEL_TARGETTED_ID:
handle_tunnel_Targetted(canard_instance, transfer);
break;
#endif
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
handle_lightscommand(canard_instance, transfer);
break;
#endif
#if AP_PERIPH_RC_OUT_ENABLED
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
handle_esc_rawcommand(canard_instance, transfer);
break;
case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:
handle_act_command(canard_instance, transfer);
break;
#endif
#if AP_PERIPH_NOTIFY_ENABLED
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
handle_notify_state(canard_instance, transfer);
break;
#endif
#if AP_PERIPH_RELAY_ENABLED
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
handle_hardpoint_command(canard_instance, transfer);
break;
#endif
#if AP_PERIPH_RTC_GLOBALTIME_ENABLED
case DRONECAN_PROTOCOL_GLOBALTIME_ID:
handle_globaltime(canard_instance, transfer);
break;
#endif
}
}
/**
* This callback is invoked by the library when a new message or request or response is received.
*/
static void onTransferReceived_trampoline(CanardInstance* canard_instance,
CanardRxTransfer* transfer)
{
AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;
fw->onTransferReceived(canard_instance, transfer);
}
/**
* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received
* by the local node.
* If the callback returns true, the library will receive the transfer.
* If the callback returns false, the library will ignore the transfer.
* All transfers that are addressed to other nodes are always ignored.
*/
bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
uint64_t* out_data_type_signature,
uint16_t data_type_id,
CanardTransferType transfer_type,
uint8_t source_node_id)
{
(void)source_node_id;
if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID)
{
/*
* If we're in the process of allocation of dynamic node ID, accept only relevant transfers.
*/
if ((transfer_type == CanardTransferTypeBroadcast) &&
(data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID))
{
*out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
return true;
}
return false;
}
switch (data_type_id) {
case UAVCAN_PROTOCOL_GETNODEINFO_ID:
*out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE;
return true;
case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:
*out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE;
return true;
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
*out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;
return true;
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE;
return true;
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;
return true;
#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED || AP_PERIPH_NOTIFY_ENABLED
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
return true;
#endif
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
*out_data_type_signature = ARDUPILOT_INDICATION_SAFETYSTATE_SIGNATURE;
return true;
#endif
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;
return true;
#if AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY || AP_PERIPH_NOTIFY_ENABLED
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
return true;
#endif
#if AP_PERIPH_GPS_ENABLED
case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;
return true;
#if GPS_MOVING_BASELINE
case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:
*out_data_type_signature = ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE;