1
1
#include < dronecan.h>
2
2
3
+ /*
4
+ Kick off the CAN driver, Canard, do some parameter management
5
+ */
3
6
void DroneCAN::init (CanardOnTransferReception onTransferReceived,
4
7
CanardShouldAcceptTransfer shouldAcceptTransfer,
5
- const std::vector<parameter>& param_list,
6
- const char * name)
8
+ const std::vector<parameter> & param_list,
9
+ const char * name)
7
10
{
11
+ // start our CAN driver
8
12
CANInit (CAN_1000KBPS, 2 );
9
13
10
14
strncpy (this ->node_name , name, sizeof (this ->node_name ));
@@ -16,44 +20,51 @@ void DroneCAN::init(CanardOnTransferReception onTransferReceived,
16
20
shouldAcceptTransfer,
17
21
NULL );
18
22
19
- if (node_id > 0 )
23
+ if (this -> node_id > 0 )
20
24
{
21
- canardSetLocalNodeID (&canard, node_id);
25
+ canardSetLocalNodeID (&this -> canard , node_id);
22
26
}
23
27
else
24
28
{
25
29
Serial.println (" Waiting for DNA node allocation" );
26
30
}
31
+
27
32
// initialise the internal LED
28
33
pinMode (19 , OUTPUT);
29
34
30
35
// put our user params into memory
31
- set_parameters (param_list);
36
+ this -> set_parameters (param_list);
32
37
33
38
// get the parameters in the EEPROM
34
39
this ->read_parameter_memory ();
40
+
41
+ while (canardGetLocalNodeID (&this ->canard ) == CANARD_BROADCAST_NODE_ID)
42
+ {
43
+ this ->cycle ();
44
+ IWatchdog.reload ();
45
+ }
35
46
}
36
47
37
48
/*
38
- Gets the node id our DNA requests on init
49
+ Gets the node id our DNA requests on init
39
50
*/
40
51
uint8_t DroneCAN::get_preferred_node_id ()
41
52
{
42
53
float ret = this ->getParameter (" NODEID" );
43
- if (ret == __FLT_MIN__ )
54
+ if (ret > 0 || ret < 127 )
44
55
{
45
- Serial.println (" No NODEID in storage, setting.." );
46
- this ->setParameter (" NODEID" , PREFERRED_NODE_ID);
47
- return PREFERRED_NODE_ID;
56
+ return (uint8_t )ret;
48
57
}
49
58
else
50
59
{
51
- return (uint8_t )ret;
60
+ Serial.println (" No NODEID in storage, setting.." );
61
+ this ->setParameter (" NODEID" , PREFERRED_NODE_ID);
62
+ return PREFERRED_NODE_ID;
52
63
}
53
64
}
54
65
55
66
/*
56
- Processes any DroneCAN actions required. Call as quickly as practical !
67
+ Processes any DroneCAN actions required. Call as quickly as practical !
57
68
*/
58
69
void DroneCAN::cycle ()
59
70
{
@@ -72,11 +83,17 @@ void DroneCAN::cycle()
72
83
this ->request_DNA ();
73
84
}
74
85
86
+ /*
87
+ For compatibility
88
+ */
75
89
uint64_t DroneCAN::micros64 ()
76
90
{
77
91
return (uint64_t )micros ();
78
92
}
79
93
94
+ /*
95
+ Returns the unique STM CPU ID required for DNA
96
+ */
80
97
void DroneCAN::getUniqueID (uint8_t uniqueId[16 ])
81
98
{
82
99
memset (uniqueId, 0 , 16 );
@@ -103,6 +120,9 @@ void DroneCAN::getUniqueID(uint8_t uniqueId[16])
103
120
uniqueId[15 ] = 0 ;
104
121
}
105
122
123
+ /*
124
+ Responds to a request for node info from CAN devices
125
+ */
106
126
void DroneCAN::handle_GetNodeInfo (CanardRxTransfer *transfer)
107
127
{
108
128
Serial.print (" GetNodeInfo request from" );
@@ -145,8 +165,8 @@ void DroneCAN::handle_GetNodeInfo(CanardRxTransfer *transfer)
145
165
}
146
166
147
167
/*
148
- handle parameter GetSet request
149
- */
168
+ handle parameter GetSet request
169
+ */
150
170
void DroneCAN::handle_param_GetSet (CanardRxTransfer *transfer)
151
171
{
152
172
// Decode the incoming request
@@ -250,8 +270,8 @@ void DroneCAN::handle_param_GetSet(CanardRxTransfer *transfer)
250
270
}
251
271
252
272
/*
253
- handle parameter executeopcode request
254
- */
273
+ handle parameter executeopcode request
274
+ */
255
275
void DroneCAN::handle_param_ExecuteOpcode (CanardRxTransfer *transfer)
256
276
{
257
277
struct uavcan_protocol_param_ExecuteOpcodeRequest req;
@@ -296,7 +316,7 @@ void DroneCAN::handle_param_ExecuteOpcode(CanardRxTransfer *transfer)
296
316
}
297
317
298
318
/*
299
- Read the EEPROM parameter storage and set the current parameter list to the read values
319
+ Read the EEPROM parameter storage and set the current parameter list to the read values
300
320
*/
301
321
void DroneCAN::read_parameter_memory ()
302
322
{
@@ -310,9 +330,9 @@ void DroneCAN::read_parameter_memory()
310
330
}
311
331
312
332
/*
313
- Get a parameter from storage by name
314
- Only handles float return values
315
- returns __FLT_MIN__ if no parameter found with the provided name
333
+ Get a parameter from storage by name
334
+ Only handles float return values
335
+ returns __FLT_MIN__ if no parameter found with the provided name
316
336
*/
317
337
float DroneCAN::getParameter (const char *name)
318
338
{
@@ -329,9 +349,9 @@ float DroneCAN::getParameter(const char *name)
329
349
}
330
350
331
351
/*
332
- Set a parameter from storage by name
333
- Values get stored as floats
334
- returns -1 if storage failed, 0 if good
352
+ Set a parameter from storage by name
353
+ Values get stored as floats
354
+ returns -1 if storage failed, 0 if good
335
355
*/
336
356
int DroneCAN::setParameter (const char *name, float value)
337
357
{
@@ -348,10 +368,9 @@ int DroneCAN::setParameter(const char *name, float value)
348
368
return -1 ;
349
369
}
350
370
351
-
352
371
/*
353
- handle a DNA allocation packet
354
- */
372
+ handle a DNA allocation packet
373
+ */
355
374
int DroneCAN::handle_DNA_Allocation (CanardRxTransfer *transfer)
356
375
{
357
376
if (canardGetLocalNodeID (&canard) != CANARD_BROADCAST_NODE_ID)
@@ -409,8 +428,8 @@ int DroneCAN::handle_DNA_Allocation(CanardRxTransfer *transfer)
409
428
}
410
429
411
430
/*
412
- ask for a dynamic node allocation
413
- */
431
+ ask for a dynamic node allocation
432
+ */
414
433
void DroneCAN::request_DNA ()
415
434
{
416
435
@@ -438,7 +457,7 @@ void DroneCAN::request_DNA()
438
457
uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1 ];
439
458
uint8_t pref_node_id = (uint8_t )(this ->get_preferred_node_id () << 1U );
440
459
Serial.print (" Requesting ID " );
441
- Serial.println (pref_node_id/ 2 ); // not sure why this is over 2 .. something to do with the bit shifting but this is what it actually sets
460
+ Serial.println (pref_node_id / 2 ); // not sure why this is over 2 .. something to do with the bit shifting but this is what it actually sets
442
461
allocation_request[0 ] = pref_node_id;
443
462
444
463
if (DNA.node_id_allocation_unique_id_offset == 0 )
@@ -482,21 +501,21 @@ void DroneCAN::request_DNA()
482
501
}
483
502
484
503
/*
485
- handle a BeginFirmwareUpdate request from a management tool like DroneCAN GUI tool or MissionPlanner
504
+ handle a BeginFirmwareUpdate request from a management tool like DroneCAN GUI tool or MissionPlanner
486
505
487
- There are multiple ways to handle firmware update over DroneCAN:
506
+ There are multiple ways to handle firmware update over DroneCAN:
488
507
489
508
1) on BeginFirmwareUpdate reboot to the bootloader, and implement
490
- the firmware upudate process in the bootloader. This is good on
491
- boards with smaller amounts of flash
509
+ the firmware upudate process in the bootloader. This is good on
510
+ boards with smaller amounts of flash
492
511
493
512
2) if you have enough flash for 2 copies of your firmware then you
494
- can use an A/B scheme, where the new firmware is saved to the
495
- inactive flash region and a tag is used to indicate which
496
- firmware to boot next time
513
+ can use an A/B scheme, where the new firmware is saved to the
514
+ inactive flash region and a tag is used to indicate which
515
+ firmware to boot next time
497
516
498
517
3) you could write the firmware to secondary storage (such as a
499
- microSD) and the bootloader would flash it on next boot
518
+ microSD) and the bootloader would flash it on next boot
500
519
501
520
In this example firmware we will write it to a file
502
521
newfirmware.bin, which is option 3
@@ -509,8 +528,9 @@ void DroneCAN::handle_begin_firmware_update(CanardRxTransfer *transfer)
509
528
Serial.println (" Update request received" );
510
529
511
530
auto *comms = (struct app_bootloader_comms *)0x20000000 ;
512
-
513
- if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {
531
+
532
+ if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC)
533
+ {
514
534
memset (comms, 0 , sizeof (*comms));
515
535
}
516
536
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
@@ -559,9 +579,9 @@ void DroneCAN::handle_begin_firmware_update(CanardRxTransfer *transfer)
559
579
}
560
580
561
581
/*
562
- send a read for a firmware update. This asks the client (firmware
563
- server) for a piece of the new firmware
564
- */
582
+ send a read for a firmware update. This asks the client (firmware
583
+ server) for a piece of the new firmware
584
+ */
565
585
void DroneCAN::send_firmware_read (void )
566
586
{
567
587
uint32_t now = millis ();
@@ -595,8 +615,8 @@ void DroneCAN::send_firmware_read(void)
595
615
}
596
616
597
617
/*
598
- handle response to send_firmware_read()
599
- */
618
+ handle response to send_firmware_read()
619
+ */
600
620
void DroneCAN::handle_file_read_response (CanardRxTransfer *transfer)
601
621
{
602
622
if ((transfer->transfer_id + 1 ) % 32 != fwupdate.transfer_id ||
@@ -637,9 +657,9 @@ void DroneCAN::handle_file_read_response(CanardRxTransfer *transfer)
637
657
}
638
658
639
659
/*
640
- send the 1Hz NodeStatus message. This is what allows a node to show
641
- up in the DroneCAN GUI tool and in the flight controller logs
642
- */
660
+ send the 1Hz NodeStatus message. This is what allows a node to show
661
+ up in the DroneCAN GUI tool and in the flight controller logs
662
+ */
643
663
void DroneCAN::send_NodeStatus (void )
644
664
{
645
665
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
@@ -677,6 +697,9 @@ void DroneCAN::send_NodeStatus(void)
677
697
len);
678
698
}
679
699
700
+ /*
701
+ Handle re-occurring slow pace tasks
702
+ */
680
703
void DroneCAN::process1HzTasks (uint64_t timestamp_usec)
681
704
{
682
705
/*
@@ -690,6 +713,9 @@ void DroneCAN::process1HzTasks(uint64_t timestamp_usec)
690
713
send_NodeStatus ();
691
714
}
692
715
716
+ /*
717
+ Send any packets currently waiting with Canard
718
+ */
693
719
void DroneCAN::processTx ()
694
720
{
695
721
for (const CanardCANFrame *txf = NULL ; (txf = canardPeekTxQueue (&canard)) != NULL ;)
@@ -699,6 +725,9 @@ void DroneCAN::processTx()
699
725
}
700
726
}
701
727
728
+ /*
729
+ Look at our mailbox
730
+ */
702
731
void DroneCAN::processRx ()
703
732
{
704
733
const uint64_t timestamp = micros ();
@@ -714,6 +743,9 @@ void DroneCAN::processRx()
714
743
}
715
744
}
716
745
746
+ /*
747
+ Send a debug message over CAN
748
+ */
717
749
void DroneCAN::debug (const char *msg, uint8_t level)
718
750
{
719
751
uavcan_protocol_debug_LogMessage pkt{};
@@ -733,6 +765,9 @@ void DroneCAN::debug(const char *msg, uint8_t level)
733
765
len);
734
766
}
735
767
768
+ /*
769
+ Bare minimum callback function for DroneCAN library requirements
770
+ */
736
771
void DroneCANonTransferReceived (DroneCAN &dronecan, CanardInstance *ins, CanardRxTransfer *transfer)
737
772
{
738
773
if (transfer->transfer_type == CanardTransferTypeBroadcast)
@@ -760,7 +795,7 @@ void DroneCANonTransferReceived(DroneCAN &dronecan, CanardInstance *ins, CanardR
760
795
}
761
796
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
762
797
{
763
-
798
+
764
799
uavcan_protocol_RestartNodeResponse pkt{};
765
800
pkt.ok = true ;
766
801
uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];
@@ -798,6 +833,9 @@ void DroneCANonTransferReceived(DroneCAN &dronecan, CanardInstance *ins, CanardR
798
833
}
799
834
}
800
835
836
+ /*
837
+ Bare minimum message signing required for DroneCAN library
838
+ */
801
839
bool DroneCANshoudlAcceptTransfer (const CanardInstance *ins,
802
840
uint64_t *out_data_type_signature,
803
841
uint16_t data_type_id,
0 commit comments