Skip to content

Commit

Permalink
Encapsulate all library code into namespace "cyphal".
Browse files Browse the repository at this point in the history
The purpose of this is to prevent naming collisions with other libraries.
  • Loading branch information
aentinger committed Aug 10, 2023
1 parent 779cce9 commit 30da545
Show file tree
Hide file tree
Showing 33 changed files with 289 additions and 91 deletions.
8 changes: 4 additions & 4 deletions examples/OpenCyphal-Blink/OpenCyphal-Blink.ino
Original file line number Diff line number Diff line change
Expand Up @@ -55,12 +55,12 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
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); });
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });

Publisher<Heartbeat_1_0> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0>
cyphal::Publisher<Heartbeat_1_0> heartbeat_pub = node_hdl.create_publisher<Heartbeat_1_0>
(1*1000*1000UL /* = 1 sec in usecs. */);
Subscription bit_subscription = node_hdl.create_subscription<Bit_1_0>
cyphal::Subscription bit_subscription = node_hdl.create_subscription<Bit_1_0>
(BIT_PORT_ID, onBit_1_0_Received);

/**************************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
nullptr,
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); });
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });

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

/**************************************************************************************
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,11 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
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); });
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); });

cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);

Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);
/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
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); });
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::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);
cyphal::Subscription heartbeat_subscription = node_hdl.create_subscription<Heartbeat_1_0>(onHeartbeat_1_0_Received);

/**************************************************************************************
* SETUP/LOOP
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
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); }, 28);
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, 28);

ServiceClient<ExecuteCommand::Request_1_1> srv_client = node_hdl.create_service_client<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
cyphal::ServiceClient<ExecuteCommand::Request_1_1> srv_client = node_hdl.create_service_client<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
2*1000*1000UL,
onExecuteCommand_1_1_Response_Received);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,10 @@ ArduinoMCP2515 mcp2515([]() { digitalWrite(MKRCAN_MCP2515_CS_PIN, LOW); },
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); }, 27);
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [] (CanardFrame const & frame) { return mcp2515.transmit(frame); }, 27);

ServiceServer execute_command_srv = node_hdl.create_service_server<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
cyphal::ServiceServer execute_command_srv = node_hdl.create_service_server<ExecuteCommand::Request_1_1, ExecuteCommand::Response_1_1>(
2*1000*1000UL,
onExecuteCommand_1_1_Request_Received);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,14 +54,14 @@ int main(int argc, char ** argv)
return EXIT_FAILURE;
}

Node::Heap<Node::DEFAULT_O1HEAP_SIZE> node_heap;
Node node_hdl(node_heap.data(), node_heap.size(), micros, [socket_can_fd] (CanardFrame const & frame) { return (socketcanPush(socket_can_fd, &frame, 1000*1000UL) > 0); });
cyphal::Node::Heap<cyphal::Node::DEFAULT_O1HEAP_SIZE> node_heap;
cyphal::Node node_hdl(node_heap.data(), node_heap.size(), micros, [socket_can_fd] (CanardFrame const & frame) { return (socketcanPush(socket_can_fd, &frame, 1000*1000UL) > 0); });
std::mutex node_mtx;

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

Publisher<CounterMsg> counter_pub = node_hdl.create_publisher<CounterMsg>
cyphal::Publisher<CounterMsg> counter_pub = node_hdl.create_publisher<CounterMsg>
(DEFAULT_COUNTER_PORT_ID, 1*1000*1000UL /* = 1 sec in usecs. */);

/* REGISTER ***************************************************************************/
Expand Down
56 changes: 36 additions & 20 deletions src/CanRxQueueItem.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,51 +18,67 @@

#include <array>

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

namespace cyphal
{

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

template<size_t MTU_BYTES>
class CanRxQueueItem
{
static_assert((MTU_BYTES == CANARD_MTU_CAN_CLASSIC) || (MTU_BYTES == CANARD_MTU_CAN_FD),
"CanRxQueueItem can only have an MTU size of either 8 (CANARD_MTU_CAN_CLASSIC) or 64 (CANARD_MTU_CAN_FD).");
static_assert((MTU_BYTES
== CANARD_MTU_CAN_CLASSIC) || (MTU_BYTES == CANARD_MTU_CAN_FD),
"CanRxQueueItem can only have an MTU size of either 8 (CANARD_MTU_CAN_CLASSIC) or 64 (CANARD_MTU_CAN_FD).");
public:
CanRxQueueItem()
: _extended_can_id{0}
, _payload_size{0}
, _payload_buf{}
, _rx_timestamp_usec{0}
{ }
: _extended_can_id{0}, _payload_size{0}, _payload_buf{}, _rx_timestamp_usec{0}
{}

CanRxQueueItem(CanardFrame const *const frame, CanardMicrosecond const rx_timestamp_usec)
: _extended_can_id{frame->extended_can_id}, _payload_size{frame->payload_size},
_payload_buf{fromCanardFrame(frame)}, _rx_timestamp_usec{rx_timestamp_usec}
{}

CanRxQueueItem(CanardFrame const * const frame, CanardMicrosecond const rx_timestamp_usec)
: _extended_can_id{frame->extended_can_id}
, _payload_size{frame->payload_size}
, _payload_buf{fromCanardFrame(frame)}
, _rx_timestamp_usec{rx_timestamp_usec}
{ }

[[nodiscard]] uint32_t extended_can_id() const
{ return _extended_can_id; }

[[nodiscard]] uint32_t extended_can_id() const { return _extended_can_id; }
[[nodiscard]] size_t payload_size() const { return _payload_size; }
[[nodiscard]] std::array<uint8_t, MTU_BYTES> const & payload_buf() const { return _payload_buf; }
[[nodiscard]] CanardMicrosecond rx_timestamp_usec() const { return _rx_timestamp_usec; }
[[nodiscard]] size_t payload_size() const
{ return _payload_size; }

[[nodiscard]] std::array <uint8_t, MTU_BYTES> const &payload_buf() const
{ return _payload_buf; }

[[nodiscard]] CanardMicrosecond rx_timestamp_usec() const
{ return _rx_timestamp_usec; }


private:
uint32_t _extended_can_id;
size_t _payload_size;
std::array<uint8_t, MTU_BYTES> _payload_buf;
std::array <uint8_t, MTU_BYTES> _payload_buf;
CanardMicrosecond _rx_timestamp_usec;

static std::array<uint8_t, MTU_BYTES> fromCanardFrame(CanardFrame const * const frame)
static std::array <uint8_t, MTU_BYTES> fromCanardFrame(CanardFrame const *const frame)
{
std::array<uint8_t, MTU_BYTES> payload_buf{};
std::array <uint8_t, MTU_BYTES> payload_buf{};
std::copy(static_cast<uint8_t const *>(frame->payload),
static_cast<uint8_t const *>(frame->payload) + std::min(frame->payload_size, MTU_BYTES),
payload_buf.begin());
return payload_buf;
}
};

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

} /* cyphal */

#endif /* INC_107_ARDUINO_CYPHAL_CANARDRXQUEUEITEM_HPP */
13 changes: 13 additions & 0 deletions src/CircularBuffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,13 @@
#include <array>
#include <memory>

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

namespace cyphal
{

/**************************************************************************************
* CLASS DECLARATION
**************************************************************************************/
Expand Down Expand Up @@ -55,6 +62,12 @@ class CircularBuffer : public CircularBufferBase
size_t nextIndex(size_t const index) { return ((index + 1) % _size); }
};

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

} /* cyphal */

/**************************************************************************************
* TEMPLATE IMPLEMENTATION
**************************************************************************************/
Expand Down
13 changes: 13 additions & 0 deletions src/CircularBuffer.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,13 @@
* Contributors: https://github.com/107-systems/107-Arduino-Cyphal/graphs/contributors.
*/

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

namespace cyphal
{

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/
Expand Down Expand Up @@ -60,3 +67,9 @@ void CircularBuffer<T>::pop()
_tail = nextIndex(_tail);
_num_elems--;
}

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

} /* cyphal */
13 changes: 13 additions & 0 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,13 @@
#include "util/registry/Registry.hpp"
#include "util/port/PortListPublisher.hpp"

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

namespace cyphal
{

/**************************************************************************************
* CTOR/DTOR
**************************************************************************************/
Expand Down Expand Up @@ -179,3 +186,9 @@ void Node::processTxQueue()
return;
}
}

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

} /* cyphal */
13 changes: 13 additions & 0 deletions src/Node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,13 @@
#include "libo1heap/o1heap.h"
#include "libcanard/canard.h"

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

namespace cyphal
{

/**************************************************************************************
* CLASS DECLARATION
**************************************************************************************/
Expand Down Expand Up @@ -148,6 +155,12 @@ class Node
void processRxFrame(CanRxQueueItem<MTU_BYTES> const * const rx_queue_item);
};

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

} /* cyphal */

/**************************************************************************************
* TEMPLATE SOURCE FILE
**************************************************************************************/
Expand Down
13 changes: 13 additions & 0 deletions src/Node.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,13 @@
#include "ServiceClient.hpp"
#include "ServiceServer.hpp"

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

namespace cyphal
{

/**************************************************************************************
* PUBLIC MEMBER FUNCTIONS
**************************************************************************************/
Expand Down Expand Up @@ -174,3 +181,9 @@ void Node::processRxFrame(CanRxQueueItem<MTU_BYTES> const * const rx_queue_item)
_canard_hdl.memory_free(&_canard_hdl, rx_transfer.payload);
}
}

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

} /* cyphal */
4 changes: 4 additions & 0 deletions src/Publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
* NAMESPACE
**************************************************************************************/

namespace cyphal
{

namespace impl
{

Expand Down Expand Up @@ -53,6 +56,7 @@ class Publisher final : public PublisherBase<T>
**************************************************************************************/

} /* impl */
} /* cyphal */

/**************************************************************************************
* TEMPLATE IMPLEMENTATION
Expand Down
4 changes: 4 additions & 0 deletions src/Publisher.ipp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,9 @@
* NAMESPACE
**************************************************************************************/

namespace cyphal
{

namespace impl
{

Expand Down Expand Up @@ -59,3 +62,4 @@ bool Publisher<T>::publish(T const & msg)
**************************************************************************************/

} /* impl */
} /* cyphal */
9 changes: 9 additions & 0 deletions src/PublisherBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@
* NAMESPACE
**************************************************************************************/

namespace cyphal
{

namespace impl
{

Expand Down Expand Up @@ -52,4 +55,10 @@ class PublisherBase
template <typename T>
using Publisher = std::shared_ptr<impl::PublisherBase<T>>;

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

} /* cyphal */

#endif /* INC_107_ARDUINO_CYPHAL_PUBLISHER_BASE_H */
4 changes: 4 additions & 0 deletions src/ServiceClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
* NAMESPACE
**************************************************************************************/

namespace cyphal
{

namespace impl
{

Expand Down Expand Up @@ -58,6 +61,7 @@ class ServiceClient final : public ServiceClientBase<T_REQ>
**************************************************************************************/

} /* impl */
} /* cyphal */

/**************************************************************************************
* TEMPLATE IMPLEMENTATION
Expand Down
Loading

0 comments on commit 30da545

Please sign in to comment.