Skip to content

Commit

Permalink
Merge pull request #235 from rebeccaRossRobotics/feature/expose_metadata
Browse files Browse the repository at this point in the history
Add returning Metadata to subscription callback
  • Loading branch information
aentinger authored Jun 5, 2023
2 parents 65165ca + 98346ca commit 635cab8
Show file tree
Hide file tree
Showing 5 changed files with 151 additions and 1 deletion.
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
/*
* This example shows reception of a OpenCyphal heartbeat message via CAN.
*
* Hardware:
* - Arduino MKR family board, e.g. MKR VIDOR 4000
* - Arduino MKR CAN shield
*/

/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <SPI.h>

#include <107-Arduino-Cyphal.h>
#include <107-Arduino-MCP2515.h>
#include <107-Arduino-CriticalSection.h>

/**************************************************************************************
* NAMESPACE
**************************************************************************************/

using namespace uavcan::node;

/**************************************************************************************
* CONSTANTS
**************************************************************************************/

static int const MKRCAN_MCP2515_CS_PIN = 3;
static int const MKRCAN_MCP2515_INT_PIN = 7;

/**************************************************************************************
* FUNCTION DECLARATION
**************************************************************************************/

void onReceiveBufferFull(CanardFrame const &);
void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, TransferMetadata const & metadata);

/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/

ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
[]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
[](uint8_t const data) { return SPI.transfer(data); },
micros,
onReceiveBufferFull,
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });

Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);
/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/

void setup()
{
Serial.begin(9600);
while(!Serial) { }
delay(1000);
Serial.println("|---- OpenCyphal Heartbeat Subscription With Metadata Example ----|");

/* Setup SPI access */
SPI.begin();
pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);

/* Attach interrupt handler to register MCP2515 signaled by taking INT low */
pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);

/* Initialize MCP2515 */
mcp2515.begin();
mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
mcp2515.setNormalMode();

Serial.println("setup finished");
}

void loop()
{
/* Process all pending OpenCyphal actions.
*/
{
CriticalSection crit_sec;
node_hdl.spinSome();
}
}

/**************************************************************************************
* FUNCTION DEFINITION
**************************************************************************************/

void onReceiveBufferFull(CanardFrame const & frame)
{
node_hdl.onCanFrameReceived(frame);
}

void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, TransferMetadata const & metadata)
{
char msg_buf[70];
snprintf(
msg_buf,
sizeof(msg_buf),
"Node ID= %d, Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
metadata.remote_node_id,
msg.uptime,
msg.health.value,
msg.mode.value,
msg.vendor_specific_status_code);

Serial.println(msg_buf);
}
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,8 @@ void setup()
{
Serial.begin(9600);
while(!Serial) { }
delay(1000);
Serial.println("|---- OpenCyphal Heartbeat Subscription Example ----|");

/* Setup SPI access */
SPI.begin();
Expand All @@ -74,6 +76,8 @@ void setup()
mcp2515.begin();
mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
mcp2515.setNormalMode();

Serial.println("setup finished");
}

void loop()
Expand Down
7 changes: 6 additions & 1 deletion src/Subscription.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,12 @@ bool Subscription<T, OnReceiveCb>::onTransferReceived(CanardRxTransfer const & t
auto const rc = deserialize(msg, msg_bitspan);
if (!rc) return false;

_on_receive_cb(msg);
if constexpr (std::is_invocable_v<OnReceiveCb, T, TransferMetadata>) {
_on_receive_cb(msg, fillMetadata(transfer));
} else {
_on_receive_cb(msg);
}


return true;
}
Expand Down
9 changes: 9 additions & 0 deletions src/SubscriptionBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <memory>

#include "libcanard/canard.h"
#include "util/transfer_metadata.hpp"

/**************************************************************************************
* NAMESPACE
Expand Down Expand Up @@ -48,9 +49,17 @@ class SubscriptionBase
[[nodiscard]] CanardRxSubscription &canard_rx_subscription() { return _canard_rx_sub; }



protected:
[[nodiscard]] CanardTransferKind canard_transfer_kind() const { return _transfer_kind; }

[[nodiscard]] TransferMetadata fillMetadata(CanardRxTransfer const & transfer)
{
TransferMetadata transfer_metadata;
transfer_metadata.remote_node_id = static_cast<uint16_t>(transfer.metadata.remote_node_id);

return transfer_metadata;
}

private:
CanardTransferKind const _transfer_kind;
Expand Down
17 changes: 17 additions & 0 deletions src/util/transfer_metadata.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2020-2023 LXRobotics.
* Author: Alexander Entinger <[email protected]>
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
*/

#ifndef ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_
#define ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_

struct TransferMetadata final
{
uint16_t remote_node_id;
// More stuff may appear here in the future!
};

#endif // ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_

0 comments on commit 635cab8

Please sign in to comment.