Skip to content

Commit

Permalink
Instead of forward declarations, which are basically hidden global de…
Browse files Browse the repository at this point in the history
…pendencies, take the honest route and pass the required function as a function pointer.
  • Loading branch information
aentinger committed Dec 22, 2022
1 parent c99ae2b commit 9fb10db
Show file tree
Hide file tree
Showing 12 changed files with 30 additions and 34 deletions.
4 changes: 2 additions & 2 deletions examples/OpenCyphal-Blink/OpenCyphal-Blink.ino
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },

CyphalHeap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size());
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, micros);

Heartbeat_1_0<> hb_msg;

Expand Down Expand Up @@ -120,7 +120,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);

/* Update the heartbeat object */
hb_msg.data.uptime = millis() / 1000;
Expand Down
2 changes: 1 addition & 1 deletion examples/OpenCyphal-GNSS-Node/OpenCyphal-GNSS-Node.ino
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);

/* Handle actions common to all states.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },

CyphalHeap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size());
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, micros);

Heartbeat_1_0<> hb_msg;

Expand Down Expand Up @@ -79,7 +79,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);

/* Update the heartbeat object */
hb_msg.data.uptime = millis() / 1000;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);
}

/**************************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);
}

/**************************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);
}

/**************************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,8 +122,8 @@ ArduinoMCP2515 mcp2515([]()

CyphalHeap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), OPEN_CYPHAL_NODE_ID);
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
Publisher<DistanceMessageType> tof_pub = node_hdl.create_publisher<DistanceMessageType>(OPEN_CYPHAL_ID_DISTANCE_DATA, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC);
Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, micros);
Publisher<DistanceMessageType> tof_pub = node_hdl.create_publisher<DistanceMessageType>(OPEN_CYPHAL_ID_DISTANCE_DATA, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, micros);

OpenCyphalNodeData node_data = OPEN_CYPHAL_NODE_INITIAL_DATA;
OpenCyphalNodeConfiguration node_config = OPEN_CYPHAL_NODE_INITIAL_CONFIGURATION;
Expand Down Expand Up @@ -243,7 +243,7 @@ void loop()
{
/* Process all pending OpenCyphal actions.
*/
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); });
node_hdl.spinSome([] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, micros);

/* Handle actions common to all states.
*/
Expand Down
14 changes: 4 additions & 10 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,6 @@

#include "Node.hpp"

/**************************************************************************************
* FORWARD DECLARATION
**************************************************************************************/

extern "C" unsigned long micros();

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/
Expand All @@ -40,10 +34,10 @@ Node::Node(uint8_t * heap_ptr,
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/

void Node::spinSome(CanFrameTransmitFunc const tx_func)
void Node::spinSome(CanFrameTransmitFunc const tx_func, TransferTimestampFunc const micros_func)
{
processRxQueue();
processTxQueue(tx_func);
processTxQueue(tx_func, micros_func);
}

void Node::onCanFrameReceived(CanardFrame const & frame, CanardMicrosecond const & rx_timestamp_us)
Expand Down Expand Up @@ -115,14 +109,14 @@ void Node::processRxQueue()
}
}

void Node::processTxQueue(CanFrameTransmitFunc const tx_func)
void Node::processTxQueue(CanFrameTransmitFunc const tx_func, TransferTimestampFunc const micros_func)
{
for(CanardTxQueueItem * tx_queue_item = const_cast<CanardTxQueueItem *>(canardTxPeek(&_canard_tx_queue));
tx_queue_item != nullptr;
tx_queue_item = const_cast<CanardTxQueueItem *>(canardTxPeek(&_canard_tx_queue)))
{
/* Discard the frame if the transmit deadline has expired. */
if (tx_queue_item->tx_deadline_usec > micros()) {
if (tx_queue_item->tx_deadline_usec > micros_func()) {
_canard_hdl.memory_free(&_canard_hdl, canardTxPop(&_canard_tx_queue, tx_queue_item));
continue;
}
Expand Down
10 changes: 7 additions & 3 deletions src/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
class Node;
typedef std::function<void(CanardRxTransfer const &, Node &)> OnTransferReceivedFunc;
typedef std::function<bool(CanardFrame const &)> CanFrameTransmitFunc;
typedef std::function<CanardMicrosecond(void)> TransferTimestampFunc;

template <size_t SIZE>
struct alignas(O1HEAP_ALIGNMENT) CyphalHeap final : public std::array<uint8_t, SIZE> {};
Expand Down Expand Up @@ -76,12 +77,15 @@ class Node
inline void setNodeId(CanardNodeID const node_id) { _canard_hdl.node_id = node_id; }
inline CanardNodeID getNodeId() const { return _canard_hdl.node_id; }

template <typename T> Publisher<T> create_publisher(CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec);
template <typename T>
Publisher<T> create_publisher(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
std::function<CanardMicrosecond(void)> const micros_func);

/* Must be called from the application to process
* all received CAN frames.
*/
void spinSome(CanFrameTransmitFunc const tx_func);
void spinSome(CanFrameTransmitFunc const tx_func, TransferTimestampFunc const micros_func);
/* Must be called from the application upon the
* reception of a can frame.
*/
Expand Down Expand Up @@ -115,7 +119,7 @@ class Node
static void o1heap_free (CanardInstance * const ins, void * const pointer);

void processRxQueue();
void processTxQueue(CanFrameTransmitFunc const tx_func);
void processTxQueue(CanFrameTransmitFunc const tx_func, TransferTimestampFunc const micros_func);

CanardTransferID getNextTransferId(CanardPortID const port_id);
bool subscribe (CanardTransferKind const transfer_kind, CanardPortID const port_id, size_t const payload_size_max, OnTransferReceivedFunc func);
Expand Down
6 changes: 4 additions & 2 deletions src/Node.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,11 @@
**************************************************************************************/

template <typename T>
Publisher<T> Node::create_publisher(CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec)
Publisher<T> Node::create_publisher(CanardPortID const port_id,
CanardMicrosecond const tx_timeout_usec,
std::function<CanardMicrosecond(void)> const micros_func)
{
return std::make_shared<impl::Publisher<T>>(_canard_hdl, _canard_tx_queue, port_id, tx_timeout_usec);
return std::make_shared<impl::Publisher<T>>(_canard_hdl, _canard_tx_queue, port_id, tx_timeout_usec, micros_func);
}

template <typename T>
Expand Down
4 changes: 3 additions & 1 deletion src/Publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,12 @@ template <typename T>
class Publisher
{
public:
Publisher(CanardInstance & canard_hdl, CanardTxQueue & canard_tx_queue, CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec)
Publisher(CanardInstance & canard_hdl, CanardTxQueue & canard_tx_queue, CanardPortID const port_id, CanardMicrosecond const tx_timeout_usec, std::function<CanardMicrosecond(void)> const micros_func)
: _canard_hdl{canard_hdl}
, _canard_tx_queue{canard_tx_queue}
, _port_id{port_id}
, _tx_timeout_usec{tx_timeout_usec}
, _micros_func{micros_func}
, _transfer_id{0}
{ }

Expand All @@ -44,6 +45,7 @@ class Publisher
CanardTxQueue & _canard_tx_queue;
CanardPortID const _port_id;
CanardMicrosecond const _tx_timeout_usec;
std::function<CanardMicrosecond(void)> const _micros_func;
CanardTransferID _transfer_id;
};

Expand Down
8 changes: 1 addition & 7 deletions src/Publisher.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,6 @@
namespace impl
{

/**************************************************************************************
* FORWARD DECLARATION
**************************************************************************************/

extern "C" unsigned long micros();

/**************************************************************************************
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/
Expand All @@ -47,7 +41,7 @@ bool Publisher<T>::publish(T const & msg)
/* Serialize transfer into a series of CAN frames */
int32_t result = canardTxPush(&_canard_tx_queue,
&_canard_hdl,
micros() + _tx_timeout_usec,
_micros_func() + _tx_timeout_usec,
&transfer_metadata,
payload_buf_size,
payload_buf.data());
Expand Down

0 comments on commit 9fb10db

Please sign in to comment.