Skip to content

Commit c1fbb09

Browse files
authored
Adopt new IMedia::getTxMemoryResource libcyphal method (#31)
1 parent 2a70a93 commit c1fbb09

File tree

15 files changed

+399
-120
lines changed

15 files changed

+399
-120
lines changed

.gitmodules

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
[submodule "submodules/libcanard"]
22
path = submodules/libcanard
33
url = https://github.com/UAVCAN/libcanard
4+
branch = v4
45
[submodule "submodules/public_regulated_data_types"]
56
path = submodules/public_regulated_data_types
67
url = https://github.com/UAVCAN/public_regulated_data_types
@@ -16,4 +17,4 @@
1617
[submodule "submodules/libcyphal"]
1718
path = submodules/libcyphal
1819
url = https://github.com/OpenCyphal-Garage/libcyphal.git
19-
branch = sshirokov/async_destroy
20+
branch = issue/352_zero_copy

differential_pressure_sensor/src/main.c

Lines changed: 31 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -153,28 +153,24 @@ static void send(State* const state,
153153
const CanardMicrosecond tx_deadline_usec,
154154
const CanardTransferMetadata* const metadata,
155155
const size_t payload_size,
156-
const void* const payload)
156+
const void* const payload_data)
157157
{
158158
for (uint8_t ifidx = 0; ifidx < CAN_REDUNDANCY_FACTOR; ifidx++)
159159
{
160-
(void) canardTxPush(&state->canard_tx_queues[ifidx],
161-
&state->canard,
162-
tx_deadline_usec,
163-
metadata,
164-
payload_size,
165-
payload);
160+
const struct CanardPayload payload = {.size = payload_size, .data = payload_data};
161+
(void) canardTxPush(&state->canard_tx_queues[ifidx], &state->canard, tx_deadline_usec, metadata, payload);
166162
}
167163
}
168164

169165
static void sendResponse(State* const state,
170166
const CanardMicrosecond tx_deadline_usec,
171167
const CanardTransferMetadata* const request_metadata,
172168
const size_t payload_size,
173-
const void* const payload)
169+
const void* const payload_data)
174170
{
175171
CanardTransferMetadata meta = *request_metadata;
176172
meta.transfer_kind = CanardTransferKindResponse;
177-
send(state, tx_deadline_usec, &meta, payload_size, payload);
173+
send(state, tx_deadline_usec, &meta, payload_size, payload_data);
178174
}
179175

180176
/// Invoked at the rate of the fastest loop.
@@ -524,11 +520,11 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
524520
{
525521
if (transfer->metadata.transfer_kind == CanardTransferKindMessage)
526522
{
527-
size_t size = transfer->payload_size;
523+
size_t size = transfer->payload.size;
528524
if (transfer->metadata.port_id == uavcan_pnp_NodeIDAllocationData_2_0_FIXED_PORT_ID_)
529525
{
530526
uavcan_pnp_NodeIDAllocationData_2_0 msg = {0};
531-
if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&msg, transfer->payload, &size) >= 0)
527+
if (uavcan_pnp_NodeIDAllocationData_2_0_deserialize_(&msg, transfer->payload.data, &size) >= 0)
532528
{
533529
processMessagePlugAndPlayNodeIDAllocation(state, &msg);
534530
}
@@ -563,8 +559,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
563559
else if (transfer->metadata.port_id == uavcan_register_Access_1_0_FIXED_PORT_ID_)
564560
{
565561
uavcan_register_Access_Request_1_0 req = {0};
566-
size_t size = transfer->payload_size;
567-
if (uavcan_register_Access_Request_1_0_deserialize_(&req, transfer->payload, &size) >= 0)
562+
size_t size = transfer->payload.size;
563+
if (uavcan_register_Access_Request_1_0_deserialize_(&req, transfer->payload.data, &size) >= 0)
568564
{
569565
const uavcan_register_Access_Response_1_0 resp = processRequestRegisterAccess(&req);
570566
uint8_t serialized[uavcan_register_Access_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
@@ -582,8 +578,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
582578
else if (transfer->metadata.port_id == uavcan_register_List_1_0_FIXED_PORT_ID_)
583579
{
584580
uavcan_register_List_Request_1_0 req = {0};
585-
size_t size = transfer->payload_size;
586-
if (uavcan_register_List_Request_1_0_deserialize_(&req, transfer->payload, &size) >= 0)
581+
size_t size = transfer->payload.size;
582+
if (uavcan_register_List_Request_1_0_deserialize_(&req, transfer->payload.data, &size) >= 0)
587583
{
588584
const uavcan_register_List_Response_1_0 resp = {.name = registerGetNameByIndex(req.index)};
589585
uint8_t serialized[uavcan_register_List_Response_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_];
@@ -601,8 +597,8 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
601597
else if (transfer->metadata.port_id == uavcan_node_ExecuteCommand_1_1_FIXED_PORT_ID_)
602598
{
603599
uavcan_node_ExecuteCommand_Request_1_1 req = {0};
604-
size_t size = transfer->payload_size;
605-
if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_(&req, transfer->payload, &size) >= 0)
600+
size_t size = transfer->payload.size;
601+
if (uavcan_node_ExecuteCommand_Request_1_1_deserialize_(&req, transfer->payload.data, &size) >= 0)
606602
{
607603
const uavcan_node_ExecuteCommand_Response_1_1 resp = processRequestExecuteCommand(&req);
608604
uint8_t serialized[uavcan_node_ExecuteCommand_Response_1_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
@@ -628,16 +624,17 @@ static void processReceivedTransfer(State* const state, const CanardRxTransfer*
628624
}
629625
}
630626

631-
static void* canardAllocate(CanardInstance* const ins, const size_t amount)
627+
static void* canardAllocate(void* const user_reference, const size_t amount)
632628
{
633-
O1HeapInstance* const heap = ((State*) ins->user_reference)->heap;
629+
O1HeapInstance* const heap = ((State*) user_reference)->heap;
634630
assert(o1heapDoInvariantsHold(heap));
635631
return o1heapAllocate(heap, amount);
636632
}
637633

638-
static void canardFree(CanardInstance* const ins, void* const pointer)
634+
static void canardDeallocate(void* const user_reference, const size_t amount, void* const pointer)
639635
{
640-
O1HeapInstance* const heap = ((State*) ins->user_reference)->heap;
636+
(void) amount;
637+
O1HeapInstance* const heap = ((State*) user_reference)->heap;
641638
o1heapFree(heap, pointer);
642639
}
643640

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

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

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

718721
// Load the port-IDs from the registers. You can implement hot-reloading at runtime if desired.
@@ -848,7 +851,8 @@ int main(const int argc, char* const argv[])
848851
return -result; // SocketCAN interface failure (link down?)
849852
}
850853
}
851-
state.canard.memory_free(&state.canard, canardTxPop(que, tqi));
854+
CanardTxQueueItem* const mut_tqi = canardTxPop(que, tqi);
855+
que->memory.deallocate(que->memory.user_reference, mut_tqi->allocated_size, mut_tqi);
852856
tqi = canardTxPeek(que);
853857
}
854858
}
@@ -878,7 +882,9 @@ int main(const int argc, char* const argv[])
878882
if (canard_result > 0)
879883
{
880884
processReceivedTransfer(&state, &transfer);
881-
state.canard.memory_free(&state.canard, (void*) transfer.payload);
885+
state.canard.memory.deallocate(state.canard.memory.user_reference,
886+
transfer.payload.allocated_size,
887+
transfer.payload.data);
882888
}
883889
else if ((canard_result == 0) || (canard_result == -CANARD_ERROR_OUT_OF_MEMORY))
884890
{

libcyphal_demo/CMakeLists.txt

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@ project(libcyphal_demo
1313
set(CMAKE_CXX_STANDARD "14" CACHE STRING "C++ standard to use when compiling.")
1414
set(DISABLE_CPP_EXCEPTIONS ON CACHE STRING "Disable C++ exceptions.")
1515

16+
option(CETL_ENABLE_DEBUG_ASSERT "Enable or disable runtime CETL asserts." ON)
17+
1618
if (CMAKE_CXX_COMPILER_ID STREQUAL "Clang" OR CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
1719
if (DISABLE_CPP_EXCEPTIONS)
1820
message(STATUS "DISABLE_CPP_EXCEPTIONS is true. Adding -fno-exceptions to compiler flags.")
@@ -22,6 +24,10 @@ endif()
2224

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

27+
if (CETL_ENABLE_DEBUG_ASSERT)
28+
add_compile_definitions("CETL_ENABLE_DEBUG_ASSERT=1")
29+
endif()
30+
2531
set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake/modules")
2632
set(submodules "${CMAKE_SOURCE_DIR}/../submodules")
2733

libcyphal_demo/src/application.cpp

Lines changed: 33 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ Application::Application()
3232
: o1_heap_mr_{s_heap_arena}
3333
, storage_{"/tmp/" NODE_NAME}
3434
, registry_{o1_heap_mr_}
35-
, regs_{o1_heap_mr_, registry_}
35+
, regs_{o1_heap_mr_, registry_, media_block_mr_}
3636
{
3737
cetl::pmr::set_default_resource(&o1_heap_mr_);
3838

@@ -60,13 +60,21 @@ Application::~Application()
6060
{
6161
save(storage_, registry_);
6262

63-
const auto mr_diag = o1_heap_mr_.queryDiagnostics();
63+
const auto o1_diag = o1_heap_mr_.queryDiagnostics();
6464
std::cout << "O(1) Heap diagnostics:" << "\n"
65-
<< " capacity=" << mr_diag.capacity << "\n"
66-
<< " allocated=" << mr_diag.allocated << "\n"
67-
<< " peak_allocated=" << mr_diag.peak_allocated << "\n"
68-
<< " peak_request_size=" << mr_diag.peak_request_size << "\n"
69-
<< " oom_count=" << mr_diag.oom_count << "\n";
65+
<< " capacity=" << o1_diag.capacity << "\n"
66+
<< " allocated=" << o1_diag.allocated << "\n"
67+
<< " peak_allocated=" << o1_diag.peak_allocated << "\n"
68+
<< " peak_request_size=" << o1_diag.peak_request_size << "\n"
69+
<< " oom_count=" << o1_diag.oom_count << "\n";
70+
71+
const auto blk_diag = media_block_mr_.queryDiagnostics();
72+
std::cout << "Media block memory diagnostics:" << "\n"
73+
<< " capacity=" << blk_diag.capacity << "\n"
74+
<< " allocated=" << blk_diag.allocated << "\n"
75+
<< " peak_allocated=" << blk_diag.peak_allocated << "\n"
76+
<< " block_size=" << blk_diag.block_size << "\n"
77+
<< " oom_count=" << blk_diag.oom_count << "\n";
7078

7179
cetl::pmr::set_default_resource(cetl::pmr::new_delete_resource());
7280
}
@@ -96,13 +104,29 @@ Application::UniqueId Application::getUniqueId()
96104
return out_unique_id;
97105
}
98106

99-
Application::Regs::Value Application::Regs::getSysInfoMem() const
107+
Application::Regs::Value Application::Regs::getSysInfoMemBlock() const
108+
{
109+
Value value{{&o1_heap_mr_}};
110+
auto& uint64s = value.set_natural64();
111+
112+
const auto diagnostics = media_block_mr_.queryDiagnostics();
113+
uint64s.value.reserve(5); // NOLINT five fields gonna push
114+
uint64s.value.push_back(diagnostics.capacity);
115+
uint64s.value.push_back(diagnostics.allocated);
116+
uint64s.value.push_back(diagnostics.peak_allocated);
117+
uint64s.value.push_back(diagnostics.block_size);
118+
uint64s.value.push_back(diagnostics.oom_count);
119+
120+
return value;
121+
}
122+
123+
Application::Regs::Value Application::Regs::getSysInfoMemGeneral() const
100124
{
101125
Value value{{&o1_heap_mr_}};
102126
auto& uint64s = value.set_natural64();
103127

104128
const auto diagnostics = o1_heap_mr_.queryDiagnostics();
105-
uint64s.value.reserve(5); // five fields gonna push
129+
uint64s.value.reserve(5); // NOLINT five fields gonna push
106130
uint64s.value.push_back(diagnostics.capacity);
107131
uint64s.value.push_back(diagnostics.allocated);
108132
uint64s.value.push_back(diagnostics.peak_allocated);

libcyphal_demo/src/application.hpp

Lines changed: 25 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#ifndef APPLICATION_HPP
88
#define APPLICATION_HPP
99

10+
#include "platform/block_memory_resource.hpp"
1011
#include "platform/linux/epoll_single_threaded_executor.hpp"
1112
#include "platform/o1_heap_memory_resource.hpp"
1213
#include "platform/storage.hpp"
@@ -34,6 +35,11 @@ class Application final
3435
static constexpr std::size_t MaxIfaceLen = 64;
3536
static constexpr std::size_t MaxNodeDesc = 50;
3637

38+
// Defines maximum alignment requirement for media block memory resource.
39+
// Currently, it's `std::max_align_t` but could be as small as 1-byte for raw bytes fragments.
40+
static constexpr std::size_t MediaBlockMaxAlign = alignof(std::max_align_t);
41+
using MediaMemoryResource = platform::BlockMemoryResource<MediaBlockMaxAlign>;
42+
3743
struct Regs
3844
{
3945
using Value = libcyphal::application::registry::IRegister::Value;
@@ -153,27 +159,34 @@ class Application final
153159

154160
}; // Natural16Param
155161

156-
Regs(platform::O1HeapMemoryResource& o1_heap_mr, libcyphal::application::registry::Registry& registry)
162+
Regs(platform::O1HeapMemoryResource& o1_heap_mr,
163+
libcyphal::application::registry::Registry& registry,
164+
MediaMemoryResource& media_block_mr)
157165
: o1_heap_mr_{o1_heap_mr}
158166
, registry_{registry}
159-
, sys_info_mem_{registry.route("sys.info.mem", [this] { return getSysInfoMem(); })}
167+
, media_block_mr_{media_block_mr}
168+
, sys_info_mem_block_{registry.route("sys.info.mem.blk", [this] { return getSysInfoMemBlock(); })}
169+
, sys_info_mem_general_{registry.route("sys.info.mem.gen", [this] { return getSysInfoMemGeneral(); })}
160170
{
161171
}
162172

163173
private:
164174
friend class Application;
165175

166-
Value getSysInfoMem() const;
176+
Value getSysInfoMemBlock() const;
177+
Value getSysInfoMemGeneral() const;
167178

168179
platform::O1HeapMemoryResource& o1_heap_mr_;
169180
libcyphal::application::registry::Registry& registry_;
181+
MediaMemoryResource& media_block_mr_;
170182

171183
// clang-format off
172184
StringParam<MaxIfaceLen> can_iface_ { "uavcan.can.iface", registry_, {"vcan0"}, {true}};
173185
StringParam<MaxNodeDesc> node_desc_ { "uavcan.node.description", registry_, {NODE_NAME}, {true}};
174186
Natural16Param<1> node_id_ { "uavcan.node.id", registry_, {65535U}, {true}};
175187
StringParam<MaxIfaceLen> udp_iface_ { "uavcan.udp.iface", registry_, {"127.0.0.1"}, {true}};
176-
Register<RegisterFootprint> sys_info_mem_;
188+
Register<RegisterFootprint> sys_info_mem_block_;
189+
Register<RegisterFootprint> sys_info_mem_general_;
177190
// clang-format on
178191

179192
}; // Regs
@@ -203,11 +216,16 @@ class Application final
203216
return executor_;
204217
}
205218

206-
CETL_NODISCARD cetl::pmr::memory_resource& memory() noexcept
219+
CETL_NODISCARD platform::O1HeapMemoryResource& general_memory() noexcept
207220
{
208221
return o1_heap_mr_;
209222
}
210223

224+
CETL_NODISCARD MediaMemoryResource& media_block_memory() noexcept
225+
{
226+
return media_block_mr_;
227+
}
228+
211229
CETL_NODISCARD libcyphal::application::registry::Registry& registry() noexcept
212230
{
213231
return registry_;
@@ -225,14 +243,15 @@ class Application final
225243

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

231249
private:
232250
// MARK: Data members:
233251

234252
platform::Linux::EpollSingleThreadedExecutor executor_;
235253
platform::O1HeapMemoryResource o1_heap_mr_;
254+
MediaMemoryResource media_block_mr_;
236255
platform::storage::KeyValue storage_;
237256
libcyphal::application::registry::Registry registry_;
238257
Regs regs_;

0 commit comments

Comments
 (0)