Skip to content

Commit d5ef5b5

Browse files
o-gentSamJCKnox
andauthored
1.3 (#4)
* Documentation, organise + simplemsgs * Fix for invalid number * add in node allocation fix * No bootloader option --------- Co-authored-by: Samuel Knox <[email protected]>
1 parent 947d4ba commit d5ef5b5

File tree

4 files changed

+229
-95
lines changed

4 files changed

+229
-95
lines changed

src/app.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
*/
99
void app_setup()
1010
{
11+
#ifndef DISABLE_APP_SETUP
1112
SCB->VTOR = 0x0800A000;
1213
RCC_OscInitTypeDef RCC_OscInitStruct = {};
1314
RCC_ClkInitTypeDef RCC_ClkInitStruct = {};
@@ -58,5 +59,6 @@ void app_setup()
5859
Error_Handler();
5960
}
6061
NVIC_EnableIRQ(SysTick_IRQn);
62+
#endif
6163
}
6264

src/dronecan.cpp

Lines changed: 86 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,14 @@
11
#include <dronecan.h>
22

3+
/*
4+
Kick off the CAN driver, Canard, do some parameter management
5+
*/
36
void DroneCAN::init(CanardOnTransferReception onTransferReceived,
47
CanardShouldAcceptTransfer shouldAcceptTransfer,
5-
const std::vector<parameter>& param_list,
6-
const char* name)
8+
const std::vector<parameter> &param_list,
9+
const char *name)
710
{
11+
// start our CAN driver
812
CANInit(CAN_1000KBPS, 2);
913

1014
strncpy(this->node_name, name, sizeof(this->node_name));
@@ -16,44 +20,51 @@ void DroneCAN::init(CanardOnTransferReception onTransferReceived,
1620
shouldAcceptTransfer,
1721
NULL);
1822

19-
if (node_id > 0)
23+
if (this->node_id > 0)
2024
{
21-
canardSetLocalNodeID(&canard, node_id);
25+
canardSetLocalNodeID(&this->canard, node_id);
2226
}
2327
else
2428
{
2529
Serial.println("Waiting for DNA node allocation");
2630
}
31+
2732
// initialise the internal LED
2833
pinMode(19, OUTPUT);
2934

3035
// put our user params into memory
31-
set_parameters(param_list);
36+
this->set_parameters(param_list);
3237

3338
// get the parameters in the EEPROM
3439
this->read_parameter_memory();
40+
41+
while(canardGetLocalNodeID(&this->canard) == CANARD_BROADCAST_NODE_ID)
42+
{
43+
this->cycle();
44+
IWatchdog.reload();
45+
}
3546
}
3647

3748
/*
38-
Gets the node id our DNA requests on init
49+
Gets the node id our DNA requests on init
3950
*/
4051
uint8_t DroneCAN::get_preferred_node_id()
4152
{
4253
float ret = this->getParameter("NODEID");
43-
if (ret == __FLT_MIN__)
54+
if (ret > 0 || ret < 127)
4455
{
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;
4857
}
4958
else
5059
{
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;
5263
}
5364
}
5465

5566
/*
56-
Processes any DroneCAN actions required. Call as quickly as practical !
67+
Processes any DroneCAN actions required. Call as quickly as practical !
5768
*/
5869
void DroneCAN::cycle()
5970
{
@@ -72,11 +83,17 @@ void DroneCAN::cycle()
7283
this->request_DNA();
7384
}
7485

86+
/*
87+
For compatibility
88+
*/
7589
uint64_t DroneCAN::micros64()
7690
{
7791
return (uint64_t)micros();
7892
}
7993

94+
/*
95+
Returns the unique STM CPU ID required for DNA
96+
*/
8097
void DroneCAN::getUniqueID(uint8_t uniqueId[16])
8198
{
8299
memset(uniqueId, 0, 16);
@@ -103,6 +120,9 @@ void DroneCAN::getUniqueID(uint8_t uniqueId[16])
103120
uniqueId[15] = 0;
104121
}
105122

123+
/*
124+
Responds to a request for node info from CAN devices
125+
*/
106126
void DroneCAN::handle_GetNodeInfo(CanardRxTransfer *transfer)
107127
{
108128
Serial.print("GetNodeInfo request from");
@@ -145,8 +165,8 @@ void DroneCAN::handle_GetNodeInfo(CanardRxTransfer *transfer)
145165
}
146166

147167
/*
148-
handle parameter GetSet request
149-
*/
168+
handle parameter GetSet request
169+
*/
150170
void DroneCAN::handle_param_GetSet(CanardRxTransfer *transfer)
151171
{
152172
// Decode the incoming request
@@ -250,8 +270,8 @@ void DroneCAN::handle_param_GetSet(CanardRxTransfer *transfer)
250270
}
251271

252272
/*
253-
handle parameter executeopcode request
254-
*/
273+
handle parameter executeopcode request
274+
*/
255275
void DroneCAN::handle_param_ExecuteOpcode(CanardRxTransfer *transfer)
256276
{
257277
struct uavcan_protocol_param_ExecuteOpcodeRequest req;
@@ -296,7 +316,7 @@ void DroneCAN::handle_param_ExecuteOpcode(CanardRxTransfer *transfer)
296316
}
297317

298318
/*
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
300320
*/
301321
void DroneCAN::read_parameter_memory()
302322
{
@@ -310,9 +330,9 @@ void DroneCAN::read_parameter_memory()
310330
}
311331

312332
/*
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
316336
*/
317337
float DroneCAN::getParameter(const char *name)
318338
{
@@ -329,9 +349,9 @@ float DroneCAN::getParameter(const char *name)
329349
}
330350

331351
/*
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
335355
*/
336356
int DroneCAN::setParameter(const char *name, float value)
337357
{
@@ -348,10 +368,9 @@ int DroneCAN::setParameter(const char *name, float value)
348368
return -1;
349369
}
350370

351-
352371
/*
353-
handle a DNA allocation packet
354-
*/
372+
handle a DNA allocation packet
373+
*/
355374
int DroneCAN::handle_DNA_Allocation(CanardRxTransfer *transfer)
356375
{
357376
if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID)
@@ -409,8 +428,8 @@ int DroneCAN::handle_DNA_Allocation(CanardRxTransfer *transfer)
409428
}
410429

411430
/*
412-
ask for a dynamic node allocation
413-
*/
431+
ask for a dynamic node allocation
432+
*/
414433
void DroneCAN::request_DNA()
415434
{
416435

@@ -438,7 +457,7 @@ void DroneCAN::request_DNA()
438457
uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];
439458
uint8_t pref_node_id = (uint8_t)(this->get_preferred_node_id() << 1U);
440459
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
442461
allocation_request[0] = pref_node_id;
443462

444463
if (DNA.node_id_allocation_unique_id_offset == 0)
@@ -482,21 +501,21 @@ void DroneCAN::request_DNA()
482501
}
483502

484503
/*
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
486505
487-
There are multiple ways to handle firmware update over DroneCAN:
506+
There are multiple ways to handle firmware update over DroneCAN:
488507
489508
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
492511
493512
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
497516
498517
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
500519
501520
In this example firmware we will write it to a file
502521
newfirmware.bin, which is option 3
@@ -509,8 +528,9 @@ void DroneCAN::handle_begin_firmware_update(CanardRxTransfer *transfer)
509528
Serial.println("Update request received");
510529

511530
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+
{
514534
memset(comms, 0, sizeof(*comms));
515535
}
516536
comms->magic = APP_BOOTLOADER_COMMS_MAGIC;
@@ -559,9 +579,9 @@ void DroneCAN::handle_begin_firmware_update(CanardRxTransfer *transfer)
559579
}
560580

561581
/*
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+
*/
565585
void DroneCAN::send_firmware_read(void)
566586
{
567587
uint32_t now = millis();
@@ -595,8 +615,8 @@ void DroneCAN::send_firmware_read(void)
595615
}
596616

597617
/*
598-
handle response to send_firmware_read()
599-
*/
618+
handle response to send_firmware_read()
619+
*/
600620
void DroneCAN::handle_file_read_response(CanardRxTransfer *transfer)
601621
{
602622
if ((transfer->transfer_id + 1) % 32 != fwupdate.transfer_id ||
@@ -637,9 +657,9 @@ void DroneCAN::handle_file_read_response(CanardRxTransfer *transfer)
637657
}
638658

639659
/*
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+
*/
643663
void DroneCAN::send_NodeStatus(void)
644664
{
645665
uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
@@ -677,6 +697,9 @@ void DroneCAN::send_NodeStatus(void)
677697
len);
678698
}
679699

700+
/*
701+
Handle re-occurring slow pace tasks
702+
*/
680703
void DroneCAN::process1HzTasks(uint64_t timestamp_usec)
681704
{
682705
/*
@@ -690,6 +713,9 @@ void DroneCAN::process1HzTasks(uint64_t timestamp_usec)
690713
send_NodeStatus();
691714
}
692715

716+
/*
717+
Send any packets currently waiting with Canard
718+
*/
693719
void DroneCAN::processTx()
694720
{
695721
for (const CanardCANFrame *txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;)
@@ -699,6 +725,9 @@ void DroneCAN::processTx()
699725
}
700726
}
701727

728+
/*
729+
Look at our mailbox
730+
*/
702731
void DroneCAN::processRx()
703732
{
704733
const uint64_t timestamp = micros();
@@ -714,6 +743,9 @@ void DroneCAN::processRx()
714743
}
715744
}
716745

746+
/*
747+
Send a debug message over CAN
748+
*/
717749
void DroneCAN::debug(const char *msg, uint8_t level)
718750
{
719751
uavcan_protocol_debug_LogMessage pkt{};
@@ -733,6 +765,9 @@ void DroneCAN::debug(const char *msg, uint8_t level)
733765
len);
734766
}
735767

768+
/*
769+
Bare minimum callback function for DroneCAN library requirements
770+
*/
736771
void DroneCANonTransferReceived(DroneCAN &dronecan, CanardInstance *ins, CanardRxTransfer *transfer)
737772
{
738773
if (transfer->transfer_type == CanardTransferTypeBroadcast)
@@ -760,7 +795,7 @@ void DroneCANonTransferReceived(DroneCAN &dronecan, CanardInstance *ins, CanardR
760795
}
761796
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
762797
{
763-
798+
764799
uavcan_protocol_RestartNodeResponse pkt{};
765800
pkt.ok = true;
766801
uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];
@@ -798,6 +833,9 @@ void DroneCANonTransferReceived(DroneCAN &dronecan, CanardInstance *ins, CanardR
798833
}
799834
}
800835

836+
/*
837+
Bare minimum message signing required for DroneCAN library
838+
*/
801839
bool DroneCANshoudlAcceptTransfer(const CanardInstance *ins,
802840
uint64_t *out_data_type_signature,
803841
uint16_t data_type_id,

0 commit comments

Comments
 (0)