How to use Dronecan protocol on stm32

Hi everyone, I’m trying to use the DroneCAN protocol on an STM32 chip. The Libcanard documentation says that you only need to include the canard.c, canard.h, and canard_internals.h files. I’ve also checked various resources, and they all mention using Python and CMake to compile Libcanard into a C library, but I’m not entirely sure about the process or if I’m doing the right thing. Could anyone share an example project or offer some guidance? Thanks so much!

Hey!

You need these things from the library libcanard:

  • the canard.c & .h and canard_internals.h
  • If you want to use c++, you need everything from the canard subfolder (did not try this yet)
  • the can driver for stm32: canard_stm32.c and canard_stm32.h (in drivers/stm32/)

Then you are also going to need the DroneCAN DSDL datatypes and the generator (the datatype generator, all types can be found here) and generate the types you need.

I have just started with DroneCAN so my way might not be the best but it does work:

  • Create a STM32 project using CMake
  • Add the whole Libcanard project to Drivers/libcanard (git clone or git add submodule)
  • Add the DSDL generator to Drivers/dronecan_dsdlc
  • Add the DSDL sources to Drivers/DSDL
  • go to Drivers/ and generate the types: python dronecan_dsdlc/dronecan_dsdlc.py -O dsdl_generated DSDL/dronecan DSDL/uavcan DSDL/com DSDL/ardupilot (you only need to generate the types you are going to use)
  • now add all necessary files to the CMakeLists.txt of your file (again, not very familiar with CMake but this works):
    # project include files
    target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE
        Drivers/libcanard
        Drivers/libcanard/drivers/stm32
        Drivers/dsdl_generated/include
    )
    # all dsdl sources
    file(GLOB_RECURSE DSDL_SOURCES "Drivers/dsdl_generated/src/*.c")
    target_sources(${CMAKE_PROJECT_NAME} PRIVATE
        ${DSDL_SOURCES}
    )
    # canard and driver
    add_library(libcanard STATIC
        Drivers/libcanard/canard.c
        Drivers/libcanard/drivers/stm32/canard_stm32.c
    )
    # canard include paths
    target_include_directories(libcanard PRIVATE
        Drivers/libcanard
    )
    

Now I was able to import canard.h, canard_stm32.h and dronecan_msgs.h and from there you can use the examples in the libcanard project (you just need to change the adapter).

Here are my adapter specific snippets:

// some helper functions:
uint64_t micros64(void) {
  return HAL_GetTick() * 1000;
}

uint32_t millis32(void) {
  return HAL_GetTick();
}

void getUniqueID(uint8_t id[16]) {
  memset(id, 0, 16);
  // use stm32 unique id
  uint32_t uid[3];
  uid[0] = HAL_GetUIDw0();  // 0-3
  uid[1] = HAL_GetUIDw1();  // 4-7
  uid[2] = HAL_GetUIDw2();  // 8-11
  memcpy(id, uid, sizeof(uid));
  // TODO 12-15 is empty, you can add something here if you want
}

// the dronecan specific functions
#include <canard.h>
#include <canard_stm32.h>
#include <dronecan_msgs.h>

void processTxRxOnce() {
  // Transmitting
  for (const CanardCANFrame *txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
    const int16_t tx_res = canardSTM32Transmit(txf);
    if (tx_res < 0) {  // Failure - drop the frame
      canardPopTxQueue(&canard);
    } else if (tx_res > 0) {  // Success - just drop the frame
      canardPopTxQueue(&canard);
    } else {  // Timeout - just exit and try again later
      break;
    }
  }

  // Receiving
  CanardCANFrame rx_frame;

  const uint64_t timestamp = micros64();
  const int16_t  rx_res    = canardSTM32Receive(&rx_frame);
  if (rx_res < 0) {
    CNT_ReceiveErrors++;
  } else if (rx_res > 0) {  // Success - process the frame
    canardHandleRxFrame(&canard, &rx_frame, timestamp);
  }
}

bool shouldAcceptTransfer(const CanardInstance *ins __attribute__((unused)),
                          uint64_t             *out_data_type_signature,
                          uint16_t              data_type_id,
                          CanardTransferType    transfer_type,
                          uint8_t               source_node_id __attribute__((unused))) {
  if (transfer_type == CanardTransferTypeRequest) {
    if (!connected) {
      return false;  // can not get message if not connected (and therefore no node id)
    }
    switch (data_type_id) {
      case UAVCAN_PROTOCOL_GETNODEINFO_ID: {
        *out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_REQUEST_SIGNATURE;
        return true;
      }
      case UAVCAN_PROTOCOL_PARAM_GETSET_ID: {
        *out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE;
        return true;
      }
      case UAVCAN_PROTOCOL_RESTARTNODE_ID: {
        *out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;
        return true;
      }
    }
  } else if (transfer_type == CanardTransferTypeBroadcast) {
    switch (data_type_id) {
      if (!connected) {
        *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
        return true;
      } else {  // ignore if already connected
        return false;
      }
      case UAVCAN_PROTOCOL_NODESTATUS_ID: {
        return false;
      }
    }
  }
  return false;
}

//TODO you can copy the handle_* functions from the examples in the libcanard project

void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) {
  if (transfer->transfer_type == CanardTransferTypeRequest) {
    switch (transfer->data_type_id) {
      case UAVCAN_PROTOCOL_GETNODEINFO_ID: {
        handle_GetNodeInfo(ins, transfer);
        break;
      }
      case UAVCAN_PROTOCOL_RESTARTNODE_ID: {
        handle_RestartNode();
        break;
      }
    }
  } else if (transfer->transfer_type == CanardTransferTypeBroadcast) {
    switch (transfer->data_type_id) {
      case UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID: {
        handle_DNA_Allocation(ins, transfer); //TODO you need to set connected = true when DNA is finished
        break;
      }
    }
  }
}

void init_dronecan() {
  canardSTM32Init(&timings, CanardSTM32IfaceModeNormal);
  canardInit(&canard,
             memory_pool,
             sizeof(memory_pool),
             onTransferReceived,
             shouldAcceptTransfer,
             NULL);

  next_1hz_service_at = micros64();
}

void tick_dronecan() {
  processTxRxOnce();
  CNT.stats = canardSTM32GetStats();

  if (canardGetLocalNodeID(&canard) == CANARD_BROADCAST_NODE_ID) {
    connected = false;
    if (millis32() >= send_next_node_id_allocation_request_at_ms) {
      request_DNA();
    }
  }

  const uint64_t ts = micros64();
  if (ts >= next_1hz_service_at) {
    next_1hz_service_at += 1000000ULL;
    canardCleanupStaleTransfers(&canard, ts);
    if (connected) {
      send_NodeStatus();
    }
  }
}


Feel free to reply if something does not work :slight_smile: