Skip to content

Commit

Permalink
Adopt new IMedia::getTxMemoryResource libcyphal method (#31)
Browse files Browse the repository at this point in the history
  • Loading branch information
serges147 authored Nov 25, 2024
1 parent 2a70a93 commit c1fbb09
Show file tree
Hide file tree
Showing 15 changed files with 399 additions and 120 deletions.
3 changes: 2 additions & 1 deletion .gitmodules
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
[submodule "submodules/libcanard"]
path = submodules/libcanard
url = https://github.com/UAVCAN/libcanard
branch = v4
[submodule "submodules/public_regulated_data_types"]
path = submodules/public_regulated_data_types
url = https://github.com/UAVCAN/public_regulated_data_types
Expand All @@ -16,4 +17,4 @@
[submodule "submodules/libcyphal"]
path = submodules/libcyphal
url = https://github.com/OpenCyphal-Garage/libcyphal.git
branch = sshirokov/async_destroy
branch = issue/352_zero_copy
56 changes: 31 additions & 25 deletions differential_pressure_sensor/src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -153,28 +153,24 @@ static void send(State* const state,
const CanardMicrosecond tx_deadline_usec,
const CanardTransferMetadata* const metadata,
const size_t payload_size,
const void* const payload)
const void* const payload_data)
{
for (uint8_t ifidx = 0; ifidx < CAN_REDUNDANCY_FACTOR; ifidx++)
{
(void) canardTxPush(&state->canard_tx_queues[ifidx],
&state->canard,
tx_deadline_usec,
metadata,
payload_size,
payload);
const struct CanardPayload payload = {.size = payload_size, .data = payload_data};
(void) canardTxPush(&state->canard_tx_queues[ifidx], &state->canard, tx_deadline_usec, metadata, payload);
}
}

static void sendResponse(State* const state,
const CanardMicrosecond tx_deadline_usec,
const CanardTransferMetadata* const request_metadata,
const size_t payload_size,
const void* const payload)
const void* const payload_data)
{
CanardTransferMetadata meta = *request_metadata;
meta.transfer_kind = CanardTransferKindResponse;
send(state, tx_deadline_usec, &meta, payload_size, payload);
send(state, tx_deadline_usec, &meta, payload_size, payload_data);
}

/// Invoked at the rate of the fastest loop.
Expand Down Expand Up @@ -524,11 +520,11 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
{
if (transfer->metadata.transfer_kind == CanardTransferKindMessage)
{
size_t size = transfer->payload_size;
size_t size = transfer->payload.size;
if (transfer->metadata.port_id == uavcan_pnp_NodeIDAllocationData_2_0_FIXED_PORT_ID_)
{
uavcan_pnp_NodeIDAllocationData_2_0 msg = {0};
if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&msg, transfer->payload, &size) >= 0)
if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&msg, transfer->payload.data, &size) >= 0)
{
processMessagePlugAndPlayNodeIDAllocation(state, &msg);
}
Expand Down Expand Up @@ -563,8 +559,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
else if (transfer->metadata.port_id == uavcan_register_Access_1_0_FIXED_PORT_ID_)
{
uavcan_register_Access_Request_1_0 req = {0};
size_t size = transfer->payload_size;
if (uavcan_register_Access_Request_1_0_deserialize_(&req, transfer->payload, &size) >= 0)
size_t size = transfer->payload.size;
if (uavcan_register_Access_Request_1_0_deserialize_(&req, transfer->payload.data, &size) >= 0)
{
const uavcan_register_Access_Response_1_0 resp = processRequestRegisterAccess(&req);
uint8_t serialized[uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
Expand All @@ -582,8 +578,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
else if (transfer->metadata.port_id == uavcan_register_List_1_0_FIXED_PORT_ID_)
{
uavcan_register_List_Request_1_0 req = {0};
size_t size = transfer->payload_size;
if (uavcan_register_List_Request_1_0_deserialize_(&req, transfer->payload, &size) >= 0)
size_t size = transfer->payload.size;
if (uavcan_register_List_Request_1_0_deserialize_(&req, transfer->payload.data, &size) >= 0)
{
const uavcan_register_List_Response_1_0 resp = {.name = registerGetNameByIndex(req.index)};
uint8_t serialized[uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
Expand All @@ -601,8 +597,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
else if (transfer->metadata.port_id == uavcan_node_ExecuteCommand_1_1_FIXED_PORT_ID_)
{
uavcan_node_ExecuteCommand_Request_1_1 req = {0};
size_t size = transfer->payload_size;
if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_(&req, transfer->payload, &size) >= 0)
size_t size = transfer->payload.size;
if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_(&req, transfer->payload.data, &size) >= 0)
{
const uavcan_node_ExecuteCommand_Response_1_1 resp = processRequestExecuteCommand(&req);
uint8_t serialized[uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
Expand All @@ -628,16 +624,17 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
}
}

static void* canardAllocate(CanardInstance* const ins, const size_t amount)
static void* canardAllocate(void* const user_reference, const size_t amount)
{
O1HeapInstance* const heap = ((State*) ins->user_reference)->heap;
O1HeapInstance* const heap = ((State*) user_reference)->heap;
assert(o1heapDoInvariantsHold(heap));
return o1heapAllocate(heap, amount);
}

static void canardFree(CanardInstance* const ins, void* const pointer)
static void canardDeallocate(void* const user_reference, const size_t amount, void* const pointer)
{
O1HeapInstance* const heap = ((State*) ins->user_reference)->heap;
(void) amount;
O1HeapInstance* const heap = ((State*) user_reference)->heap;
o1heapFree(heap, pointer);
}

Expand All @@ -659,9 +656,14 @@ int main(const int argc, char* const argv[])
_Alignas(O1HEAP_ALIGNMENT) static uint8_t heap_arena[1024 * 16] = {0};
state.heap = o1heapInit(heap_arena, sizeof(heap_arena));
assert(NULL != state.heap);
struct CanardMemoryResource canard_memory = {
.user_reference = &state,
.deallocate = canardDeallocate,
.allocate = canardAllocate,
};

// The libcanard instance requires the allocator for managing protocol states.
state.canard = canardInit(&canardAllocate, &canardFree);
state.canard = canardInit(canard_memory);
state.canard.user_reference = &state; // Make the state reachable from the canard instance.

// Restore the node-ID from the corresponding standard register. Default to anonymous.
Expand Down Expand Up @@ -712,7 +714,8 @@ int main(const int argc, char* const argv[])
{
return -sock[ifidx];
}
state.canard_tx_queues[ifidx] = canardTxInit(CAN_TX_QUEUE_CAPACITY, val.natural16.value.elements[0]);
state.canard_tx_queues[ifidx] =
canardTxInit(CAN_TX_QUEUE_CAPACITY, val.natural16.value.elements[0], canard_memory);
}

// Load the port-IDs from the registers. You can implement hot-reloading at runtime if desired.
Expand Down Expand Up @@ -848,7 +851,8 @@ int main(const int argc, char* const argv[])
return -result; // SocketCAN interface failure (link down?)
}
}
state.canard.memory_free(&state.canard, canardTxPop(que, tqi));
CanardTxQueueItem* const mut_tqi = canardTxPop(que, tqi);
que->memory.deallocate(que->memory.user_reference, mut_tqi->allocated_size, mut_tqi);
tqi = canardTxPeek(que);
}
}
Expand Down Expand Up @@ -878,7 +882,9 @@ int main(const int argc, char* const argv[])
if (canard_result > 0)
{
processReceivedTransfer(&state, &transfer);
state.canard.memory_free(&state.canard, (void*) transfer.payload);
state.canard.memory.deallocate(state.canard.memory.user_reference,
transfer.payload.allocated_size,
transfer.payload.data);
}
else if ((canard_result == 0) || (canard_result == -CANARD_ERROR_OUT_OF_MEMORY))
{
Expand Down
6 changes: 6 additions & 0 deletions libcyphal_demo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ project(libcyphal_demo
set(CMAKE_CXX_STANDARD "14" CACHE STRING "C++ standard to use when compiling.")
set(DISABLE_CPP_EXCEPTIONS ON CACHE STRING "Disable C++ exceptions.")

option(CETL_ENABLE_DEBUG_ASSERT "Enable or disable runtime CETL asserts." ON)

if (CMAKE_CXX_COMPILER_ID STREQUAL "Clang" OR CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
if (DISABLE_CPP_EXCEPTIONS)
message(STATUS "DISABLE_CPP_EXCEPTIONS is true. Adding -fno-exceptions to compiler flags.")
Expand All @@ -22,6 +24,10 @@ endif()

add_compile_options("$<$<COMPILE_LANGUAGE:CXX>:${CXX_FLAG_SET}>")

if (CETL_ENABLE_DEBUG_ASSERT)
add_compile_definitions("CETL_ENABLE_DEBUG_ASSERT=1")
endif()

set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake/modules")
set(submodules "${CMAKE_SOURCE_DIR}/../submodules")

Expand Down
42 changes: 33 additions & 9 deletions libcyphal_demo/src/application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ Application::Application()
: o1_heap_mr_{s_heap_arena}
, storage_{"/tmp/" NODE_NAME}
, registry_{o1_heap_mr_}
, regs_{o1_heap_mr_, registry_}
, regs_{o1_heap_mr_, registry_, media_block_mr_}
{
cetl::pmr::set_default_resource(&o1_heap_mr_);

Expand Down Expand Up @@ -60,13 +60,21 @@ Application::~Application()
{
save(storage_, registry_);

const auto mr_diag = o1_heap_mr_.queryDiagnostics();
const auto o1_diag = o1_heap_mr_.queryDiagnostics();
std::cout << "O(1) Heap diagnostics:" << "\n"
<< " capacity=" << mr_diag.capacity << "\n"
<< " allocated=" << mr_diag.allocated << "\n"
<< " peak_allocated=" << mr_diag.peak_allocated << "\n"
<< " peak_request_size=" << mr_diag.peak_request_size << "\n"
<< " oom_count=" << mr_diag.oom_count << "\n";
<< " capacity=" << o1_diag.capacity << "\n"
<< " allocated=" << o1_diag.allocated << "\n"
<< " peak_allocated=" << o1_diag.peak_allocated << "\n"
<< " peak_request_size=" << o1_diag.peak_request_size << "\n"
<< " oom_count=" << o1_diag.oom_count << "\n";

const auto blk_diag = media_block_mr_.queryDiagnostics();
std::cout << "Media block memory diagnostics:" << "\n"
<< " capacity=" << blk_diag.capacity << "\n"
<< " allocated=" << blk_diag.allocated << "\n"
<< " peak_allocated=" << blk_diag.peak_allocated << "\n"
<< " block_size=" << blk_diag.block_size << "\n"
<< " oom_count=" << blk_diag.oom_count << "\n";

cetl::pmr::set_default_resource(cetl::pmr::new_delete_resource());
}
Expand Down Expand Up @@ -96,13 +104,29 @@ Application::UniqueId Application::getUniqueId()
return out_unique_id;
}

Application::Regs::Value Application::Regs::getSysInfoMem() const
Application::Regs::Value Application::Regs::getSysInfoMemBlock() const
{
Value value{{&o1_heap_mr_}};
auto& uint64s = value.set_natural64();

const auto diagnostics = media_block_mr_.queryDiagnostics();
uint64s.value.reserve(5); // NOLINT five fields gonna push
uint64s.value.push_back(diagnostics.capacity);
uint64s.value.push_back(diagnostics.allocated);
uint64s.value.push_back(diagnostics.peak_allocated);
uint64s.value.push_back(diagnostics.block_size);
uint64s.value.push_back(diagnostics.oom_count);

return value;
}

Application::Regs::Value Application::Regs::getSysInfoMemGeneral() const
{
Value value{{&o1_heap_mr_}};
auto& uint64s = value.set_natural64();

const auto diagnostics = o1_heap_mr_.queryDiagnostics();
uint64s.value.reserve(5); // five fields gonna push
uint64s.value.reserve(5); // NOLINT five fields gonna push
uint64s.value.push_back(diagnostics.capacity);
uint64s.value.push_back(diagnostics.allocated);
uint64s.value.push_back(diagnostics.peak_allocated);
Expand Down
31 changes: 25 additions & 6 deletions libcyphal_demo/src/application.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#ifndef APPLICATION_HPP
#define APPLICATION_HPP

#include "platform/block_memory_resource.hpp"
#include "platform/linux/epoll_single_threaded_executor.hpp"
#include "platform/o1_heap_memory_resource.hpp"
#include "platform/storage.hpp"
Expand Down Expand Up @@ -34,6 +35,11 @@ class Application final
static constexpr std::size_t MaxIfaceLen = 64;
static constexpr std::size_t MaxNodeDesc = 50;

// Defines maximum alignment requirement for media block memory resource.
// Currently, it's `std::max_align_t` but could be as small as 1-byte for raw bytes fragments.
static constexpr std::size_t MediaBlockMaxAlign = alignof(std::max_align_t);
using MediaMemoryResource = platform::BlockMemoryResource<MediaBlockMaxAlign>;

struct Regs
{
using Value = libcyphal::application::registry::IRegister::Value;
Expand Down Expand Up @@ -153,27 +159,34 @@ class Application final

}; // Natural16Param

Regs(platform::O1HeapMemoryResource& o1_heap_mr, libcyphal::application::registry::Registry& registry)
Regs(platform::O1HeapMemoryResource& o1_heap_mr,
libcyphal::application::registry::Registry& registry,
MediaMemoryResource& media_block_mr)
: o1_heap_mr_{o1_heap_mr}
, registry_{registry}
, sys_info_mem_{registry.route("sys.info.mem", [this] { return getSysInfoMem(); })}
, media_block_mr_{media_block_mr}
, sys_info_mem_block_{registry.route("sys.info.mem.blk", [this] { return getSysInfoMemBlock(); })}
, sys_info_mem_general_{registry.route("sys.info.mem.gen", [this] { return getSysInfoMemGeneral(); })}
{
}

private:
friend class Application;

Value getSysInfoMem() const;
Value getSysInfoMemBlock() const;
Value getSysInfoMemGeneral() const;

platform::O1HeapMemoryResource& o1_heap_mr_;
libcyphal::application::registry::Registry& registry_;
MediaMemoryResource& media_block_mr_;

// clang-format off
StringParam<MaxIfaceLen> can_iface_ { "uavcan.can.iface", registry_, {"vcan0"}, {true}};
StringParam<MaxNodeDesc> node_desc_ { "uavcan.node.description", registry_, {NODE_NAME}, {true}};
Natural16Param<1> node_id_ { "uavcan.node.id", registry_, {65535U}, {true}};
StringParam<MaxIfaceLen> udp_iface_ { "uavcan.udp.iface", registry_, {"127.0.0.1"}, {true}};
Register<RegisterFootprint> sys_info_mem_;
Register<RegisterFootprint> sys_info_mem_block_;
Register<RegisterFootprint> sys_info_mem_general_;
// clang-format on

}; // Regs
Expand Down Expand Up @@ -203,11 +216,16 @@ class Application final
return executor_;
}

CETL_NODISCARD cetl::pmr::memory_resource& memory() noexcept
CETL_NODISCARD platform::O1HeapMemoryResource& general_memory() noexcept
{
return o1_heap_mr_;
}

CETL_NODISCARD MediaMemoryResource& media_block_memory() noexcept
{
return media_block_mr_;
}

CETL_NODISCARD libcyphal::application::registry::Registry& registry() noexcept
{
return registry_;
Expand All @@ -225,14 +243,15 @@ class Application final

/// Returns the 128-bit unique-ID of the local node. This value is used in `uavcan.node.GetInfo.Response`.
///
using UniqueId = std::array<std::uint8_t, 16>;
using UniqueId = std::array<std::uint8_t, 16>; // NOLINT
UniqueId getUniqueId();

private:
// MARK: Data members:

platform::Linux::EpollSingleThreadedExecutor executor_;
platform::O1HeapMemoryResource o1_heap_mr_;
MediaMemoryResource media_block_mr_;
platform::storage::KeyValue storage_;
libcyphal::application::registry::Registry registry_;
Regs regs_;
Expand Down
Loading

0 comments on commit c1fbb09

Please sign in to comment.