Skip to content

Commit

Permalink
Replace dynamic memory allocation inside receive buffer with static m…
Browse files Browse the repository at this point in the history
…emory allocaton. (#195)

Doing so allows the compiler to report memory usage during compilation time.
  • Loading branch information
aentinger committed Jan 9, 2023
1 parent 9c72e9a commit f6bda74
Show file tree
Hide file tree
Showing 11 changed files with 113 additions and 76 deletions.
4 changes: 3 additions & 1 deletion examples/OpenCyphal-Blink/OpenCyphal-Blink.ino
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,9 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(
Heartbeat_1_0<>::PORT_ID, 1*1000*1000UL /* = 1 sec in usecs. */);
auto heartbeat_subscription = node_hdl.create_subscription<Bit_1_0<BIT_PORT_ID>>(
Expand Down
4 changes: 3 additions & 1 deletion examples/OpenCyphal-GNSS-Node/OpenCyphal-GNSS-Node.ino
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,9 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Publisher<uavcan::node::Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<uavcan::node::Heartbeat_1_0<>>(uavcan::node::Heartbeat_1_0<>::PORT_ID, 1*1000*1000UL /* = 1 sec in usecs. */);

ArduinoNmeaParser nmea_parser(gnss::onRmcUpdate, gnss::onGgaUpdate);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,9 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, 1*1000*1000UL /* = 1 sec in usecs. */);

Heartbeat_1_0<> hb_msg;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,9 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Subscription heartbeat_subscription =
node_hdl.create_subscription<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, CANARD_DEFAULT_TRANSFER_ID_TIMEOUT_USEC, onHeartbeat_1_0_Received);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

/**************************************************************************************
* SETUP/LOOP
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,9 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros);

Service execute_command_srv = node_hdl.create_service<ExecuteCommand_1_0::Request<>, ExecuteCommand_1_0::Response<>>(
ExecuteCommand_1_0::Request<>::PORT_ID,
2*1000*1000UL,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,9 @@ ArduinoMCP2515 mcp2515([]()
nullptr);

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros, OPEN_CYPHAL_NODE_ID);
CircularBuffer<Node::TReceiveCircularBuffer>::Heap<Node::DEFAULT_RX_QUEUE_SIZE> node_rx_queue;
Node node_hdl(node_heap.data(), node_heap.size(), node_rx_queue.data(), node_rx_queue.size(), micros, OPEN_CYPHAL_NODE_ID);

Publisher<Heartbeat_1_0<>> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0<>>(Heartbeat_1_0<>::PORT_ID, 1*1000*1000UL /* = 1 sec in usecs. */);
Publisher<DistanceMessageType> tof_pub = node_hdl.create_publisher<DistanceMessageType>(OPEN_CYPHAL_ID_DISTANCE_DATA, 1*1000*1000UL /* = 1 sec in usecs. */);

Expand Down
84 changes: 25 additions & 59 deletions src/RingBuffer.hpp → src/CircularBuffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,83 +9,49 @@
#define ARDUINO_CYPHAL_UTILITY_RINGBUFFER_H_

/**************************************************************************************
* NAMESPACE
* INCLUDE
**************************************************************************************/

namespace opencyphal
{
#include <cstdlib>

#include <array>

/**************************************************************************************
* CLASS DECLARATION
**************************************************************************************/

template <class T>
class RingBuffer
template <typename T>
class CircularBuffer
{
public:
RingBuffer(size_t const size)
: _buffer{new T[size]}
, _size{size}
, _head{0}
, _tail{0}
, _num_elems{0}
{ }

~RingBuffer()
{
delete[] _buffer;
_size = 0;
_head = 0;
_tail = 0;
_num_elems = 0;
}

void enqueue(T const & val)
{
if (isFull()) return;
_buffer[_head] = val;
_head = nextIndex(_head);
_num_elems++;
}

T dequeue()
{
if (isEmpty()) return T{};
T const val = _buffer[_tail];
_tail = nextIndex(_tail);
_num_elems--;
return val;
}

size_t available() const
{
return _num_elems;
}

bool isFull() const
{
return (_num_elems == _size);
}

bool isEmpty() const
{
return (_num_elems == 0);
}
template <size_t SIZE>
struct Heap final : public std::array<T, SIZE> {};


CircularBuffer(T * heap_ptr, size_t const heap_size);
~CircularBuffer();


void enqueue(T const & val);
T dequeue();


size_t available() const { return _num_elems; }
bool isFull() const { return (_num_elems == _size); }
bool isEmpty() const { return (_num_elems == 0); }


private:
T * _buffer;
size_t _size, _head, _tail, _num_elems;

size_t nextIndex(size_t const index)
{
return ((index + 1) % _size);
}
size_t nextIndex(size_t const index) { return ((index + 1) % _size); }
};

/**************************************************************************************
* NAMESPACE
* TEMPLATE IMPLEMENTATION
**************************************************************************************/

} /* opencyphal */
#include "CircularBuffer.ipp"

#endif /* ARDUINO_CYPHAL_UTILITY_RINGBUFFER_H_ */
55 changes: 55 additions & 0 deletions src/CircularBuffer.ipp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
/**
* This software is distributed under the terms of the MIT License.
* Copyright (c) 2020-2023 LXRobotics.
* Author: Alexander Entinger <alexander.entinger@lxrobotics.com>
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
*/

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/

template <typename T>
CircularBuffer<T>::CircularBuffer(T * heap_ptr, size_t const heap_size)
: _buffer{heap_ptr}
, _size{heap_size}
, _head{0}
, _tail{0}
, _num_elems{0}
{

}

template <typename T>
CircularBuffer<T>::~CircularBuffer()
{
_size = 0;
_head = 0;
_tail = 0;
_num_elems = 0;
}

/**************************************************************************************
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/

template <typename T>
void CircularBuffer<T>::enqueue(T const & val)
{
if (isFull()) return;

_buffer[_head] = val;
_head = nextIndex(_head);
_num_elems++;
}

template <typename T>
T CircularBuffer<T>::dequeue()
{
if (isEmpty()) return T{};

T const val = _buffer[_tail];
_tail = nextIndex(_tail);
_num_elems--;
return val;
}
5 changes: 3 additions & 2 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,16 +19,17 @@

Node::Node(uint8_t * heap_ptr,
size_t const heap_size,
TReceiveCircularBuffer * rx_queue_heap_ptr,
size_t const rx_queue_heap_size,
MicrosFunc const micros_func,
CanardNodeID const node_id,
size_t const tx_queue_capacity,
size_t const rx_queue_capacity,
size_t const mtu_bytes)
: _o1heap_ins{o1heapInit(heap_ptr, heap_size)}
, _canard_hdl{canardInit(Node::o1heap_allocate, Node::o1heap_free)}
, _micros_func{micros_func}
, _canard_tx_queue{canardTxInit(tx_queue_capacity, mtu_bytes)}
, _canard_rx_queue{rx_queue_capacity}
, _canard_rx_queue{rx_queue_heap_ptr, rx_queue_heap_size}
{
_canard_hdl.node_id = node_id;
_canard_hdl.user_reference = static_cast<void *>(_o1heap_ins);
Expand Down
18 changes: 10 additions & 8 deletions src/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "Service.hpp"
#include "Publisher.hpp"
#include "Subscription.hpp"
#include "RingBuffer.hpp"
#include "CircularBuffer.hpp"

#include "libo1heap/o1heap.h"
#include "libcanard/canard.h"
Expand All @@ -43,27 +43,29 @@ class Node
template <size_t SIZE>
struct alignas(O1HEAP_ALIGNMENT) Heap final : public std::array<uint8_t, SIZE> {};

typedef std::tuple<uint32_t, size_t, std::array<uint8_t, 8>, CanardMicrosecond> TReceiveCircularBuffer;

static size_t constexpr DEFAULT_O1HEAP_SIZE = 4096;
static CanardNodeID constexpr DEFAULT_NODE_ID = 42;
static size_t constexpr DEFAULT_TX_QUEUE_SIZE = 64;
static size_t constexpr DEFAULT_RX_QUEUE_SIZE = 64;
static size_t constexpr DEFAULT_TX_QUEUE_SIZE = 64;
static size_t constexpr DEFAULT_MTU_SIZE = CANARD_MTU_CAN_CLASSIC;


Node(uint8_t * heap_ptr,
size_t const heap_size,
TReceiveCircularBuffer * rx_queue_heap_ptr,
size_t const rx_queue_heap_size,
MicrosFunc const micros_func,
CanardNodeID const node_id,
size_t const tx_queue_capacity,
size_t const rx_queue_capacity,
size_t const mtu_bytes);

Node(uint8_t * heap_ptr, size_t const heap_size, MicrosFunc const micros_func)
: Node(heap_ptr, heap_size, micros_func, DEFAULT_NODE_ID, DEFAULT_TX_QUEUE_SIZE, DEFAULT_RX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }
Node(uint8_t * heap_ptr, size_t const heap_size, TReceiveCircularBuffer * rx_queue_heap_ptr, size_t const rx_queue_heap_size, MicrosFunc const micros_func)
: Node(heap_ptr, heap_size, rx_queue_heap_ptr, rx_queue_heap_size, micros_func, DEFAULT_NODE_ID, DEFAULT_TX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }

Node(uint8_t * heap_ptr, size_t const heap_size, MicrosFunc const micros_func, CanardNodeID const node_id)
: Node(heap_ptr, heap_size, micros_func, node_id, DEFAULT_TX_QUEUE_SIZE, DEFAULT_RX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }
Node(uint8_t * heap_ptr, size_t const heap_size, TReceiveCircularBuffer * rx_queue_heap_ptr, size_t const rx_queue_heap_size, MicrosFunc const micros_func, CanardNodeID const node_id)
: Node(heap_ptr, heap_size, rx_queue_heap_ptr, rx_queue_heap_size, micros_func, node_id, DEFAULT_TX_QUEUE_SIZE, DEFAULT_MTU_SIZE) { }


inline void setNodeId(CanardNodeID const node_id) { _canard_hdl.node_id = node_id; }
Expand Down Expand Up @@ -105,7 +107,7 @@ class Node
CanardInstance _canard_hdl;
MicrosFunc const _micros_func;
CanardTxQueue _canard_tx_queue;
opencyphal::RingBuffer<std::tuple<uint32_t, size_t, std::array<uint8_t, 8>, CanardMicrosecond>> _canard_rx_queue;
CircularBuffer<TReceiveCircularBuffer> _canard_rx_queue;

static void * o1heap_allocate(CanardInstance * const ins, size_t const amount);
static void o1heap_free (CanardInstance * const ins, void * const pointer);
Expand Down

0 comments on commit f6bda74

Please sign in to comment.