Skip to content

Commit 635cab8

Browse files
authored
Merge pull request #235 from rebeccaRossRobotics/feature/expose_metadata
Add returning Metadata to subscription callback
2 parents 65165ca + 98346ca commit 635cab8

File tree

5 files changed

+151
-1
lines changed

5 files changed

+151
-1
lines changed
Lines changed: 115 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,115 @@
1+
/*
2+
* This example shows reception of a OpenCyphal heartbeat message via CAN.
3+
*
4+
* Hardware:
5+
* - Arduino MKR family board, e.g. MKR VIDOR 4000
6+
* - Arduino MKR CAN shield
7+
*/
8+
9+
/**************************************************************************************
10+
* INCLUDE
11+
**************************************************************************************/
12+
13+
#include <SPI.h>
14+
15+
#include <107-Arduino-Cyphal.h>
16+
#include <107-Arduino-MCP2515.h>
17+
#include <107-Arduino-CriticalSection.h>
18+
19+
/**************************************************************************************
20+
* NAMESPACE
21+
**************************************************************************************/
22+
23+
using namespace uavcan::node;
24+
25+
/**************************************************************************************
26+
* CONSTANTS
27+
**************************************************************************************/
28+
29+
static int const MKRCAN_MCP2515_CS_PIN = 3;
30+
static int const MKRCAN_MCP2515_INT_PIN = 7;
31+
32+
/**************************************************************************************
33+
* FUNCTION DECLARATION
34+
**************************************************************************************/
35+
36+
void onReceiveBufferFull(CanardFrame const &);
37+
void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, TransferMetadata const & metadata);
38+
39+
/**************************************************************************************
40+
* GLOBAL VARIABLES
41+
**************************************************************************************/
42+
43+
ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
44+
[]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH); },
45+
[](uint8_t const data) { return SPI.transfer(data); },
46+
micros,
47+
onReceiveBufferFull,
48+
nullptr);
49+
50+
Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
51+
Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
52+
53+
Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);
54+
/**************************************************************************************
55+
* SETUP/LOOP
56+
**************************************************************************************/
57+
58+
void setup()
59+
{
60+
Serial.begin(9600);
61+
while(!Serial) { }
62+
delay(1000);
63+
Serial.println("|---- OpenCyphal Heartbeat Subscription With Metadata Example ----|");
64+
65+
/* Setup SPI access */
66+
SPI.begin();
67+
pinMode(MKRCAN_MCP2515_CS_PIN, OUTPUT);
68+
digitalWrite(MKRCAN_MCP2515_CS_PIN, HIGH);
69+
70+
/* Attach interrupt handler to register MCP2515 signaled by taking INT low */
71+
pinMode(MKRCAN_MCP2515_INT_PIN, INPUT_PULLUP);
72+
attachInterrupt(digitalPinToInterrupt(MKRCAN_MCP2515_INT_PIN), []() { mcp2515.onExternalEventHandler(); }, LOW);
73+
74+
/* Initialize MCP2515 */
75+
mcp2515.begin();
76+
mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
77+
mcp2515.setNormalMode();
78+
79+
Serial.println("setup finished");
80+
}
81+
82+
void loop()
83+
{
84+
/* Process all pending OpenCyphal actions.
85+
*/
86+
{
87+
CriticalSection crit_sec;
88+
node_hdl.spinSome();
89+
}
90+
}
91+
92+
/**************************************************************************************
93+
* FUNCTION DEFINITION
94+
**************************************************************************************/
95+
96+
void onReceiveBufferFull(CanardFrame const & frame)
97+
{
98+
node_hdl.onCanFrameReceived(frame);
99+
}
100+
101+
void onHeartbeat_1_0_Received(Heartbeat_1_0 const & msg, TransferMetadata const & metadata)
102+
{
103+
char msg_buf[70];
104+
snprintf(
105+
msg_buf,
106+
sizeof(msg_buf),
107+
"Node ID= %d, Uptime = %d, Health = %d, Mode = %d, VSSC = %d",
108+
metadata.remote_node_id,
109+
msg.uptime,
110+
msg.health.value,
111+
msg.mode.value,
112+
msg.vendor_specific_status_code);
113+
114+
Serial.println(msg_buf);
115+
}

examples/OpenCyphal-Heartbeat-Subscriber/OpenCyphal-Heartbeat-Subscriber.ino

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ void setup()
6060
{
6161
Serial.begin(9600);
6262
while(!Serial) { }
63+
delay(1000);
64+
Serial.println("|---- OpenCyphal Heartbeat Subscription Example ----|");
6365

6466
/* Setup SPI access */
6567
SPI.begin();
@@ -74,6 +76,8 @@ void setup()
7476
mcp2515.begin();
7577
mcp2515.setBitRate(CanBitRate::BR_250kBPS_16MHZ);
7678
mcp2515.setNormalMode();
79+
80+
Serial.println("setup finished");
7781
}
7882

7983
void loop()

src/Subscription.ipp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,12 @@ bool Subscription<T, OnReceiveCb>::onTransferReceived(CanardRxTransfer const & t
4141
auto const rc = deserialize(msg, msg_bitspan);
4242
if (!rc) return false;
4343

44-
_on_receive_cb(msg);
44+
if constexpr (std::is_invocable_v<OnReceiveCb, T, TransferMetadata>) {
45+
_on_receive_cb(msg, fillMetadata(transfer));
46+
} else {
47+
_on_receive_cb(msg);
48+
}
49+
4550

4651
return true;
4752
}

src/SubscriptionBase.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <memory>
1616

1717
#include "libcanard/canard.h"
18+
#include "util/transfer_metadata.hpp"
1819

1920
/**************************************************************************************
2021
* NAMESPACE
@@ -48,9 +49,17 @@ class SubscriptionBase
4849
[[nodiscard]] CanardRxSubscription &canard_rx_subscription() { return _canard_rx_sub; }
4950

5051

52+
5153
protected:
5254
[[nodiscard]] CanardTransferKind canard_transfer_kind() const { return _transfer_kind; }
5355

56+
[[nodiscard]] TransferMetadata fillMetadata(CanardRxTransfer const & transfer)
57+
{
58+
TransferMetadata transfer_metadata;
59+
transfer_metadata.remote_node_id = static_cast<uint16_t>(transfer.metadata.remote_node_id);
60+
61+
return transfer_metadata;
62+
}
5463

5564
private:
5665
CanardTransferKind const _transfer_kind;

src/util/transfer_metadata.hpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
/**
2+
* This software is distributed under the terms of the MIT License.
3+
* Copyright (c) 2020-2023 LXRobotics.
4+
* Author: Alexander Entinger <[email protected]>
5+
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
6+
*/
7+
8+
#ifndef ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_
9+
#define ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_
10+
11+
struct TransferMetadata final
12+
{
13+
uint16_t remote_node_id;
14+
// More stuff may appear here in the future!
15+
};
16+
17+
#endif // ARDUINO_CYPHAL_TRANSFER_METADATA_HPP_

0 commit comments

Comments
 (0)