From f42aff8525da06c8d2feecd2c1aac84de5d4e922 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sat, 18 Apr 2026 21:32:09 +0200 Subject: [PATCH 01/38] refactor: replace IDL DDS translation with direct internal CDR serialization --- .clang-tidy | 26 ++ .gitignore | 2 + CMakeLists.txt | 2 + api/dsr_api.cpp | 318 ++++++++------- api/dsr_rt_api.cpp | 10 +- api/include/dsr/api/dsr_api.h | 29 +- api/include/dsr/api/dsr_camera_api.h | 2 +- api/include/dsr/api/dsr_inner_eigen_api.h | 2 +- api/include/dsr/api/dsr_rt_api.h | 2 +- api/include/dsr/api/dsr_utils.h | 2 +- core/include/dsr/core/crdt/delta_crdt.h | 125 +++++- core/include/dsr/core/rtps/CRDTPubSubTypes.h | 140 +++++++ core/include/dsr/core/rtps/dsrparticipant.h | 3 +- core/include/dsr/core/rtps/dsrpublisher.h | 14 +- .../dsr/core/serialization/serializable.h | 36 ++ core/include/dsr/core/types/common_types.h | 89 +---- core/include/dsr/core/types/crdt_types.h | 23 +- core/include/dsr/core/types/internal_types.h | 366 ++++++++++++++++++ core/include/dsr/core/types/translator.h | 263 +++---------- core/rtps/dsrparticipant.cpp | 14 +- core/rtps/dsrpublisher.cpp | 22 +- core/types/common_types.cpp | 153 +++++--- core/types/crdt_types.cpp | 228 +++++------ .../synchronization/graph_synchronization.cpp | 67 +++- tests/synchronization/type_translation.cpp | 138 ++++--- 25 files changed, 1350 insertions(+), 726 deletions(-) create mode 100644 .clang-tidy create mode 100644 core/include/dsr/core/rtps/CRDTPubSubTypes.h create mode 100644 core/include/dsr/core/serialization/serializable.h create mode 100644 core/include/dsr/core/types/internal_types.h diff --git a/.clang-tidy b/.clang-tidy new file mode 100644 index 00000000..842a04b3 --- /dev/null +++ b/.clang-tidy @@ -0,0 +1,26 @@ +--- +Checks: > + clang-diagnostic-*, + clang-analyzer-*, + bugprone-*, + modernize-*, + performance-*, + readability-*, + -modernize-use-trailing-return-type, + -readability-identifier-length, + -readability-magic-numbers, + -bugprone-easily-swappable-parameters + +WarningsAsErrors: "" +HeaderFilterRegex: "(api|core)/include/.*" +FormatStyle: "file" +CheckOptions: + - key: readability-identifier-naming.ClassCase + value: CamelCase + - key: readability-identifier-naming.FunctionCase + value: lower_case + - key: readability-identifier-naming.VariableCase + value: lower_case + - key: modernize-use-default-member-init.UseAssignment + value: "true" +... diff --git a/.gitignore b/.gitignore index a376bd0a..e17a9996 100644 --- a/.gitignore +++ b/.gitignore @@ -9,3 +9,5 @@ experiment/ **.pyc **/_pychache__ .artifacts/ +.vscode/* +.claude/* \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 88515250..5d512c01 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,6 +6,8 @@ project(dsr include(GNUInstallDirs) +set(CMAKE_EXPORT_COMPILE_COMMANDS ON) + # -DTSAN=ON enables ThreadSanitizer across the whole build (library + tests/benchmarks). # Must be applied before any add_subdirectory so every TU is instrumented. # Incompatible with SANITIZER (ASan/UBSan) — enforce that here. diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 6609f922..3c7af5b3 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -3,9 +3,9 @@ // #include "dsr/api/dsr_graph_settings.h" -#include "dsr/core/topics/IDLGraph.hpp" +#include "dsr/core/types/internal_types.h" #include "dsr/core/types/translator.h" -#include "include/dsr/api/dsr_signal_emitter.h" +#include "dsr/api/dsr_signal_emitter.h" #include #include #include @@ -29,6 +29,24 @@ using namespace DSR; using namespace std::literals; +namespace { +bool protocol_version_matches( + DSR::GraphSettings::LOGLEVEL log_level, + const char* channel, + uint32_t remote_version) +{ + if (remote_version == DSR::DSR_PROTOCOL_VERSION) { + return true; + } + + DSR_LOG_ERROR( + "[PROTOCOL] incompatible", channel, + "remote:", remote_version, + "local:", DSR::DSR_PROTOCOL_VERSION); + return false; +} +} + ///////////////////////////////////////////////// ///// PUBLIC METHODS ///////////////////////////////////////////////// @@ -187,7 +205,7 @@ std::optional DSRGraph::get_node(uint64_t id) return {}; } -std::tuple> DSRGraph::insert_node_(CRDTNode &&node) +std::tuple> DSRGraph::insert_node_(CRDTNode &&node) { if (!deleted.contains(node.id())) { @@ -200,7 +218,7 @@ std::tuple> DSRGraph::insert_node_(CRDTNode update_maps_node_insert(id, node); mvreg delta = nodes[id].write(std::move(node)); - return {true, CRDTNode_to_IDL(agent_id, id, delta)}; + return {true, CRDTNode_to_Msg(agent_id, id, delta)}; } return {false, {}}; } @@ -209,7 +227,7 @@ template std::optional DSRGraph::insert_node(No &&node) requires (std::is_same_v, DSR::Node>) { - std::optional delta; + std::optional delta; bool inserted = false; { std::unique_lock lock(_mutex); @@ -249,7 +267,7 @@ template std::optional DSRGraph::insert_node_with_id(No &&node) requires (std::is_same_v, DSR::Node>) { - std::optional delta; + std::optional delta; bool inserted = false; { std::unique_lock lock(_mutex); @@ -287,7 +305,7 @@ std::optional DSRGraph::insert_node_with_id(No &&node) template std::optional DSRGraph::insert_node_with_id(DSR::Node&&); template std::optional DSRGraph::insert_node_with_id(DSR::Node&); -std::tuple>> DSRGraph::update_node_(CRDTNode &&node) +std::tuple> DSRGraph::update_node_(CRDTNode &&node) { if (!deleted.contains(node.id())) @@ -295,15 +313,15 @@ std::tuple>> DSRGraph::updat auto nit = nodes.find(node.id()); if (nit != nodes.end() && !nit->second.empty()) { - std::vector atts_deltas; + DSR::MvregNodeAttrVec atts_deltas; auto &iter = nit->second.read_reg().attrs(); //New attributes and updates. for (auto &[k, att]: node.attrs()) { auto &attr_reg = iter.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); - atts_deltas.emplace_back( - CRDTNodeAttr_to_IDL(agent_id, node.id(), node.id(), k, delta)); + atts_deltas.vec.emplace_back( + CRDTNodeAttr_to_Msg(agent_id, node.id(), node.id(), k, delta)); } } //Remove old attributes. @@ -314,8 +332,8 @@ std::tuple>> DSRGraph::updat it_a = iter.erase(it_a); } else if (!node.attrs().contains(k)) { auto delta = it_a->second.reset(); - atts_deltas.emplace_back( - CRDTNodeAttr_to_IDL(node.agent_id(), node.id(), node.id(), k, delta)); + atts_deltas.vec.emplace_back( + CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, delta)); it_a = iter.erase(it_a); } else { ++it_a; @@ -334,7 +352,7 @@ requires (std::is_same_v, DSR::Node>) { bool updated = false; - std::optional> vec_node_attr; + std::optional vec_node_attr; { std::unique_lock lock(_mutex); @@ -359,11 +377,11 @@ requires (std::is_same_v, DSR::Node>) dsrpub_node_attrs.write(&vec_node_attr.value()); DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - std::vector atts_names(vec_node_attr->size()); - std::transform(std::make_move_iterator(vec_node_attr->begin()), - std::make_move_iterator(vec_node_attr->end()), + std::vector atts_names(vec_node_attr->vec.size()); + std::transform(std::make_move_iterator(vec_node_attr->vec.begin()), + std::make_move_iterator(vec_node_attr->vec.end()), atts_names.begin(), - [](auto &&x) { return x.attr_name(); }); + [](auto &&x) { return x.attr_name; }); emitter.update_node_attr_signal(node.id(), atts_names, SignalInfo{agent_id}); } @@ -379,11 +397,11 @@ template bool DSRGraph::update_node(DSR::Node&&); -std::tuple, std::optional, std::vector> +std::tuple, std::optional, std::vector> DSRGraph::delete_node_(uint64_t id) { std::vector deleted_edges; - std::vector delta_vec; + std::vector delta_vec; //Get and remove node. auto node = get_(id); @@ -394,7 +412,7 @@ DSRGraph::delete_node_(uint64_t id) { } // Get remove delta. auto delta = nodes[id].reset(); - IDL::MvregNode delta_remove = CRDTNode_to_IDL(agent_id, id, delta); + DSR::MvregNodeMsg delta_remove = CRDTNode_to_Msg(agent_id, id, delta); // Search and remove incoming edges using to_edges cache: O(k) instead of O(n). { decltype(to_edges)::mapped_type incoming; @@ -409,7 +427,7 @@ DSRGraph::delete_node_(uint64_t id) { auto &visited_node = nodes.at(from).read_reg(); deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); auto delta_fano = visited_node.fano().at({id, type}).reset(); - delta_vec.emplace_back(CRDTEdge_to_IDL(agent_id, from, id, type, delta_fano)); + delta_vec.emplace_back(CRDTEdge_to_Msg(agent_id, from, id, type, delta_fano)); visited_node.fano().erase({id, type}); update_maps_edge_delete(from, id, type); } @@ -429,8 +447,8 @@ bool DSRGraph::delete_node(const std::string &name) bool result = false; std::vector deleted_edges; - std::optional deleted_node; - std::vector delta_vec; + std::optional deleted_node; + std::vector delta_vec; std::optional node_signal; std::optional id = {}; { @@ -469,9 +487,9 @@ bool DSRGraph::delete_node(uint64_t id) bool result = false; std::vector deleted_edges; - std::optional deleted_node; + std::optional deleted_node; std::optional node_signal; - std::vector delta_vec; + std::vector delta_vec; { node_signal = get_(id); std::unique_lock lock(_mutex); @@ -621,12 +639,12 @@ std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::st } -std::tuple, std::optional>> +std::tuple, std::optional> DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) { - std::optional delta_edge; - std::optional> delta_attrs; + std::optional delta_edge; + std::optional delta_attrs; if (nodes.contains(from)) { @@ -636,14 +654,14 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) if (fano_it != node.fano().end()) { //Update - std::vector atts_deltas; + DSR::MvregEdgeAttrVec atts_deltas; auto &iter_edge = fano_it->second.read_reg().attrs(); for (auto &[k, att]: attrs.attrs()) { auto &attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); - atts_deltas.emplace_back( - CRDTEdgeAttr_to_IDL(agent_id, from, from, to, attrs.type(), k, delta)); + atts_deltas.vec.emplace_back( + CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), k, delta)); } } auto it = iter_edge.begin(); @@ -652,8 +670,8 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) std::string att = it->first; auto delta = it->second.reset(); it = iter_edge.erase(it); - atts_deltas.emplace_back( - CRDTEdgeAttr_to_IDL(agent_id, from, from, to, attrs.type(), att, delta)); + atts_deltas.vec.emplace_back( + CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), att, delta)); } else { ++it; } @@ -661,11 +679,10 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) return {true, {}, std::move(atts_deltas)}; } else { // Insert - //node.fano().insert({{to, attrs.type()}, mvreg()}); std::string att_type = attrs.type(); auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); update_maps_edge_insert(from, to, att_type); - return {true, CRDTEdge_to_IDL(agent_id, from, to, att_type, delta), {}}; + return {true, CRDTEdge_to_Msg(agent_id, from, to, att_type, delta), {}}; } } return {false, {}, {}}; @@ -676,8 +693,8 @@ bool DSRGraph::insert_or_assign_edge(Ed &&attrs) requires (std::is_same_v, DSR::Edge>) { bool result = false; - std::optional delta_edge; - std::optional> delta_attrs; + std::optional delta_edge; + std::optional delta_attrs; { std::unique_lock lock(_mutex); @@ -701,11 +718,11 @@ requires (std::is_same_v, DSR::Edge>) } if (delta_attrs.has_value()) { //Update dsrpub_edge_attrs.write(&delta_attrs.value()); - std::vector atts_names(delta_attrs->size()); - std::transform(std::make_move_iterator(delta_attrs->begin()), - std::make_move_iterator(delta_attrs->end()), + std::vector atts_names(delta_attrs->vec.size()); + std::transform(std::make_move_iterator(delta_attrs->vec.begin()), + std::make_move_iterator(delta_attrs->vec.end()), atts_names.begin(), - [](auto &&x) { return x.attr_name(); }); + [](auto &&x) { return x.attr_name; }); emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), atts_names, SignalInfo{ agent_id }); @@ -722,7 +739,7 @@ template bool DSRGraph::insert_or_assign_edge(DSR::Edge&); template bool DSRGraph::insert_or_assign_edge(const DSR::Edge&); -std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) +std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) { if (nodes.contains(from)) { auto &node = nodes.at(from).read_reg(); @@ -730,7 +747,7 @@ std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, auto delta = node.fano().at({to, key}).reset(); node.fano().erase({to, key}); update_maps_edge_delete(from, to, key); - return CRDTEdge_to_IDL(agent_id, from, to, key, delta); + return CRDTEdge_to_Msg(agent_id, from, to, key, delta); } } return {}; @@ -739,7 +756,7 @@ std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) { - std::optional delta; + std::optional delta; std::optional deleted_edge; { std::unique_lock lock(_mutex); @@ -766,7 +783,7 @@ bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::optional id_from = {}; std::optional id_to = {}; - std::optional delta; + std::optional delta; std::optional deleted_edge; { id_from = get_id_from_name(from); @@ -1030,17 +1047,20 @@ bool DSRGraph::empty(const uint64_t &id) return false; } -void DSRGraph::join_delta_node(IDL::MvregNode &&mvreg) +void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) { std::optional maybe_deleted_node = {}; try { + if (!protocol_version_matches(log_level, "DSR_NODE", mvreg.protocol_version)) { + return; + } bool signal = false, joined = false; - auto id = mvreg.id(); - uint64_t timestamp = mvreg.timestamp(); + auto id = mvreg.id; + uint64_t timestamp = mvreg.timestamp; - DSR_LOG_DEBUG("[JOIN_NODE] id:", id, "timestamp:", timestamp, "agent:", mvreg.agent_id()); - auto crdt_delta = IDLNode_to_CRDT(std::move(mvreg)); + DSR_LOG_DEBUG("[JOIN_NODE] id:", id, "timestamp:", timestamp, "agent:", mvreg.agent_id); + auto crdt_delta = std::move(mvreg.dk); bool d_empty = crdt_delta.empty(); @@ -1160,36 +1180,37 @@ void DSRGraph::join_delta_node(IDL::MvregNode &&mvreg) } } + uint32_t msg_agent_id = mvreg.agent_id; if (joined) { if (signal) { DSR_LOG_DEBUG("[JOIN_NODE] node inserted/updated:", id, node_type_snapshot); - emitter.update_node_signal(id, node_type_snapshot, SignalInfo{ mvreg.agent_id() }); + emitter.update_node_signal(id, node_type_snapshot, SignalInfo{ msg_agent_id }); for (const auto &[to_id, edge_type] : from_edges_snapshot) { DSR_LOG_DEBUG("[JOIN_NODE] add edge FROM:", id, to_id, edge_type); - emitter.update_edge_signal(id, to_id, edge_type, SignalInfo{ mvreg.agent_id() }); + emitter.update_edge_signal(id, to_id, edge_type, SignalInfo{ msg_agent_id }); } for (const auto &[k, v]: map_new_to_edges) { DSR_LOG_DEBUG("[JOIN_NODE] add edge TO:", k, id, v); - emitter.update_edge_signal(k, id, v, SignalInfo{ mvreg.agent_id() }); + emitter.update_edge_signal(k, id, v, SignalInfo{ msg_agent_id }); } for (const auto &[from, to, type]: map_new_from_edges) { DSR_LOG_DEBUG("[JOIN_NODE] add edge FROM (unprocessed_to):", from, to, type); - emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id() }); + emitter.update_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); } } else { DSR_LOG_DEBUG("[JOIN_NODE] node deleted:", id); - emitter.del_node_signal(id, SignalInfo{ mvreg.agent_id() }); + emitter.del_node_signal(id, SignalInfo{ msg_agent_id }); if (maybe_deleted_node.has_value()) { Node tmp_node(*maybe_deleted_node); emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id }); for (const auto &node: maybe_deleted_node->fano()) { DSR_LOG_DEBUG("[JOIN_NODE] delete edge FROM:", node.second.read_reg().from(), node.second.read_reg().to(), node.second.read_reg().type()); emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), - node.second.read_reg().type(), SignalInfo{ mvreg.agent_id() }); + node.second.read_reg().type(), SignalInfo{ msg_agent_id }); Edge tmp_edge(node.second.read_reg()); emitter.deleted_edge_signal(tmp_edge, SignalInfo{ agent_id }); } @@ -1198,7 +1219,7 @@ void DSRGraph::join_delta_node(IDL::MvregNode &&mvreg) //TODO: deleted_edge_signal. update_maps_node_delete was called before so the maps are probably wrong... for (const auto &[from, type] : cache_map_to_edges.value()) { DSR_LOG_DEBUG("[JOIN_NODE] delete edge TO:", from, id, type); - emitter.del_edge_signal(from, id, type, SignalInfo{ mvreg.agent_id() }); + emitter.del_edge_signal(from, id, type, SignalInfo{ msg_agent_id }); //emitter.deleted_edge_signal(Edge(node.second.read_reg())); TODO: fix this } @@ -1228,16 +1249,19 @@ bool DSRGraph::process_delta_edge(uint64_t from, uint64_t to, const std::string& } -void DSRGraph::join_delta_edge(IDL::MvregEdge &&mvreg) +void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) { try { + if (!protocol_version_matches(log_level, "DSR_EDGE", mvreg.protocol_version)) { + return; + } bool signal = false, joined = false; - auto from = mvreg.id(); - auto to = mvreg.to(); - std::string type = mvreg.type(); - DSR_LOG_DEBUG("[JOIN_EDGE] from:", from, "to:", to, "type:", type, "agent:", mvreg.agent_id()); + auto from = mvreg.id; + auto to = mvreg.to; + std::string type = mvreg.type; + DSR_LOG_DEBUG("[JOIN_EDGE] from:", from, "to:", to, "type:", type, "agent:", mvreg.agent_id); - uint64_t timestamp = mvreg.timestamp(); + uint64_t timestamp = mvreg.timestamp; //Clean remaining delta edges. auto delete_unprocessed_deltas = [&](){ @@ -1272,9 +1296,10 @@ void DSRGraph::join_delta_edge(IDL::MvregEdge &&mvreg) [&](auto &it){ return it.first == from && std::get<0>(it.second) == to && std::get<1>(it.second) == type; }); }; + uint32_t msg_agent_id = mvreg.agent_id; std::optional deleted_edge; { - auto crdt_delta = IDLEdge_to_CRDT(std::move(mvreg)); + auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); deleted_edge = get_edge_(from, to, type); //Check if the node where we are joining the edge exist. @@ -1340,10 +1365,10 @@ void DSRGraph::join_delta_edge(IDL::MvregEdge &&mvreg) if (joined) { if (signal) { DSR_LOG_DEBUG("[JOIN_EDGE] add edge:", from, to, type); - emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id() }); + emitter.update_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); } else { DSR_LOG_DEBUG("[JOIN_EDGE] delete edge:", from, to, type); - emitter.del_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id() }); + emitter.del_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); if (deleted_edge.has_value()) { emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id }); } @@ -1368,17 +1393,20 @@ void DSRGraph::process_delta_node_attr(uint64_t id, const std::string& att_name, } } -std::optional DSRGraph::join_delta_node_attr(IDL::MvregNodeAttr &&mvreg) +std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg) { try { + if (!protocol_version_matches(log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { + return std::nullopt; + } bool joined = false; - auto id = mvreg.id(); - std::string att_name = mvreg.attr_name(); - uint64_t timestamp = mvreg.timestamp(); + auto id = mvreg.id; + std::string att_name = mvreg.attr_name; + uint64_t timestamp = mvreg.timestamp; DSR_LOG_DEBUG("[JOIN_NODE_ATTR] node:", id, "attr:", att_name); { - auto crdt_delta = IDLNodeAttr_to_CRDT(std::move(mvreg)); + auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); //Check if the node where we are joining the edge exist. if (nodes.contains(id)) { @@ -1432,19 +1460,22 @@ void DSRGraph::process_delta_edge_attr(uint64_t from, uint64_t to, const std::st } -std::optional DSRGraph::join_delta_edge_attr(IDL::MvregEdgeAttr &&mvreg) +std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg) { try { + if (!protocol_version_matches(log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { + return std::nullopt; + } bool joined = false; - auto from = mvreg.id(); - auto to = mvreg.to(); - std::string type = mvreg.type(); - std::string att_name = mvreg.attr_name(); - uint64_t timestamp = mvreg.timestamp(); + auto from = mvreg.id; + auto to = mvreg.to_node; + std::string type = mvreg.type; + std::string att_name = mvreg.attr_name; + uint64_t timestamp = mvreg.timestamp; DSR_LOG_DEBUG("[JOIN_EDGE_ATTR] edge:", from, to, type, "attr:", att_name); { - auto crdt_delta = IDLEdgeAttr_to_CRDT(std::move(mvreg)); + auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); //Check if the node where we are joining the edge exist. if (nodes.contains(from) and nodes.at(from).read_reg().fano().contains({to, type})) @@ -1487,8 +1518,11 @@ std::optional DSRGraph::join_delta_edge_attr(IDL::MvregEdgeAttr &&m return std::nullopt; } -void DSRGraph::join_full_graph(IDL::OrMap &&full_graph) +void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) { + if (!protocol_version_matches(log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { + return; + } // 5th element: post-join node snapshot captured inside the lock, used for // signal emission after the lock is released to avoid racing with // insert_node_/update_node (same pattern as join_delta_node). @@ -1575,10 +1609,10 @@ void DSRGraph::join_full_graph(IDL::OrMap &&full_graph) { std::unique_lock lock(_mutex); - for (auto &[k, val] : full_graph.m()) { - auto mv = IDLNode_to_CRDT(std::move(val)); + for (auto &[k, val] : full_graph.m) { + auto mv = std::move(val.dk); bool mv_empty = mv.empty(); - agent_id_ch = val.agent_id(); + agent_id_ch = val.agent_id; auto it = nodes.find(k); std::optional nd = (it != nodes.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; @@ -1658,12 +1692,18 @@ void DSRGraph::start_subscription_threads() if (delta_edge_attrs_thread.joinable()) delta_edge_attrs_thread.join(); } -std::map DSRGraph::Map() +std::map DSRGraph::Map() { std::shared_lock lock(_mutex); - std::map m; - for (auto kv : nodes) { - m.emplace(kv.first, CRDTNode_to_IDL(agent_id, kv.first, kv.second)); + std::map m; + for (auto &kv : nodes) { + DSR::MvregNodeMsg msg; + msg.dk = kv.second; + msg.id = kv.first; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; + m.emplace(kv.first, std::move(msg)); } return m; } @@ -1702,19 +1742,22 @@ void DSRGraph::node_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::MvregNode sample; + DSR::MvregNodeMsg sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { - if (sample.agent_id() != agent_id) { - if (sample.id() == CLEAR_DELETED_SIGNAL) { + if (sample.agent_id != agent_id) { + if (!protocol_version_matches(log_level, "DSR_NODE", sample.protocol_version)) { + continue; + } + if (sample.id == CLEAR_DELETED_SIGNAL) { std::unique_lock lock(_mutex); std::unique_lock lck_cache(_mutex_cache_maps); deleted.clear(); continue; } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id()).c_str() << " node from: " + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " << m_info.sample_identity.writer_guid().entityId.value; } tp.spawn_task(&DSRGraph::join_delta_node, this, std::move(sample)); @@ -1742,13 +1785,13 @@ void DSRGraph::edge_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::MvregEdge sample; + DSR::MvregEdgeMsg sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { - if (sample.agent_id() != agent_id) { + if (sample.agent_id != agent_id) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id()).c_str() << " node from: " + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " << m_info.sample_identity.writer_guid().entityId.value; } tp.spawn_task(&DSRGraph::join_delta_edge, this, std::move(sample)); @@ -1777,27 +1820,28 @@ void DSRGraph::edge_attrs_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::MvregEdgeAttrVec samples; + DSR::MvregEdgeAttrVec samples; if (reader->take_next_sample(&samples, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec().size() << " edge attr from: " + qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " << m_info.sample_identity.writer_guid().entityId.value; } - if (!samples.vec().empty() and samples.vec().at(0).agent_id() != agent_id) + if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - if (samples.vec().empty()) return; + if (samples.vec.empty()) return; - auto from = samples.vec().at(0).from(); - auto to = samples.vec().at(0).to(); - auto type = samples.vec().at(0).type(); + auto from = samples.vec.at(0).from_node; + auto to = samples.vec.at(0).to_node; + auto type = samples.vec.at(0).type; + auto sample_agent_id = samples.vec.at(0).agent_id; std::vector>> futures; - for (auto &&sample: samples.vec()) { - if (!ignored_attributes.contains(sample.attr_name())) { + for (auto &&sample: samples.vec) { + if (!ignored_attributes.contains(sample.attr_name)) { futures.emplace_back(tp.spawn_task_waitable([this, sample = std::move(sample)]() mutable { return join_delta_edge_attr(std::move(sample)); })); @@ -1813,8 +1857,8 @@ void DSRGraph::edge_attrs_subscription_thread() } - emitter.update_edge_attr_signal(from, to, type, sig, SignalInfo{samples.vec().at(0).agent_id()}); - emitter.update_edge_signal(from, to, type, SignalInfo{samples.vec().at(0).agent_id()}); + emitter.update_edge_attr_signal(from, to, type, sig, SignalInfo{sample_agent_id}); + emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); }); } @@ -1845,28 +1889,29 @@ void DSRGraph::node_attrs_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::MvregNodeAttrVec samples; + DSR::MvregNodeAttrVec samples; if (reader->take_next_sample(&samples, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec().size() << " node attrs from: " + qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " << m_info.sample_identity.writer_guid().entityId.value; } - if (!samples.vec().empty() and samples.vec().at(0).agent_id() != agent_id) { + if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - if (samples.vec().empty()) return; + if (samples.vec.empty()) return; - auto id = samples.vec().at(0).id(); + auto id = samples.vec.at(0).id; + auto sample_agent_id = samples.vec.at(0).agent_id; std::string type; { std::shared_lock lock(_mutex); if (auto itn = nodes.find(id); itn != nodes.end()) type = itn->second.read_reg().type() ; } std::vector>> futures; - for (auto &&s: samples.vec()) { - if (!ignored_attributes.contains(s.attr_name())) { + for (auto &&s: samples.vec) { + if (!ignored_attributes.contains(s.attr_name)) { futures.emplace_back(tp.spawn_task_waitable([this, samp{std::move(s)}]() mutable { auto f = join_delta_node_attr(std::move(samp)); return f; @@ -1883,8 +1928,8 @@ void DSRGraph::node_attrs_subscription_thread() sig.emplace_back(std::move(opt_str.value())); } - emitter.update_node_attr_signal(id, sig, SignalInfo{samples.vec().at(0).agent_id()}); - emitter.update_node_signal(id, type, SignalInfo{samples.vec().at(0).agent_id()}); + emitter.update_node_attr_signal(id, sig, SignalInfo{sample_agent_id}); + emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); }); } } @@ -1910,20 +1955,24 @@ void DSRGraph::fullgraph_server_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::GraphRequest sample; + DSR::GraphRequest sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); if (m_info.valid_data) { + if (!protocol_version_matches(log_level, "GRAPH_REQUEST", sample.protocol_version)) { + continue; + } { std::unique_lock lck(participant_set_mutex); - if (auto [it, ok] = participant_set.emplace(sample.from(), true); + if (auto [it, ok] = participant_set.emplace(sample.from, true); it->second and !ok) { if (it->second) { lck.unlock(); - IDL::OrMap mp; - mp.id(-1); - mp.to_id(sample.id()); + DSR::OrMap mp; + mp.id = -1; + mp.to_id = static_cast(sample.id); + mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; dsrpub_request_answer.write(&mp); continue; } else {} @@ -1932,13 +1981,14 @@ void DSRGraph::fullgraph_server_thread() lck.unlock(); } } - if (static_cast(sample.id()) != agent_id ) { + if (static_cast(sample.id) != agent_id ) { qDebug() << " Received Full Graph request: from " << m_info.sample_identity.writer_guid().entityId.value; - IDL::OrMap mp; - mp.id(graph->get_agent_id()); - mp.m(graph->Map()); + DSR::OrMap mp; + mp.id = static_cast(graph->get_agent_id()); + mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; + mp.m = graph->Map(); dsrpub_request_answer.write(&mp); qDebug() << "Full graph written"; @@ -1966,21 +2016,26 @@ std::pair DSRGraph::fullgraph_request_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - IDL::OrMap sample; + DSR::OrMap sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); if (m_info.valid_data) { - if (sample.id() != graph->get_agent_id()) { - if (sample.id() != static_cast(-1)) { + if (!protocol_version_matches(log_level, "GRAPH_ANSWER", sample.protocol_version)) { + continue; + } + if (static_cast(sample.id) != graph->get_agent_id()) { + if (sample.id != -1) { qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value << " whith " - << sample.m().size() << " elements"; - tp.spawn_task(&DSRGraph::join_full_graph, this, std::move(sample)); + << sample.m.size() << " elements"; + tp.spawn_task([this, s = std::move(sample)]() mutable { + join_full_graph(std::move(s)); + }); qDebug() << "Synchronized."; sync = true; break; } - else if (!sync && sample.to_id() == agent_id) + else if (!sync && sample.to_id == agent_id) { repeated = true; } @@ -2001,9 +2056,10 @@ std::pair DSRGraph::fullgraph_request_thread() qDebug() << " Requesting the complete graph "; - IDL::GraphRequest gr; - gr.from( dsrparticipant.getParticipant()->get_qos().name().to_string()); - gr.id(static_cast(agent_id)); + DSR::GraphRequest gr; + gr.from = dsrparticipant.getParticipant()->get_qos().name().to_string(); + gr.id = static_cast(agent_id); + gr.protocol_version = DSR::DSR_PROTOCOL_VERSION; dsrpub_graph_request.write(&gr); diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index 9efd41a8..a449fe72 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -392,9 +392,9 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector node1_insert; - std::optional> node1_update; - std::optional> node2; + std::optional node1_insert; + std::optional node1_update; + std::optional node2; std::optional to_n; { std::unique_lock lock(G->_mutex); @@ -557,14 +557,14 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector from: IDL::MvregEdge, to: vector + //Create -> insert edge, update to-node attrs std::tie(r1, node1_insert, std::ignore) = G->insert_or_assign_edge_(std::move(e), n.id(), to); if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n.value())); } else { - //Update -> from: IDL::MvregEdgeAttr, to: vector + //Update -> update edge attrs, update to-node attrs std::tie(r1, std::ignore, node1_update) = G->insert_or_assign_edge_(std::move(e), n.id(), to); if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n.value())); diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 908fd327..654d7a5c 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -490,9 +490,10 @@ namespace DSR } if (!copy) { - IDL::MvregNode signal; - signal.id(CLEAR_DELETED_SIGNAL); - signal.agent_id(agent_id); + DSR::MvregNodeMsg signal; + signal.id = CLEAR_DELETED_SIGNAL; + signal.agent_id = agent_id; + signal.protocol_version = DSR::DSR_PROTOCOL_VERSION; dsrpub_node.write(&signal); } } @@ -657,25 +658,25 @@ namespace DSR ////////////////////////////////////////////////////////////////////////// std::optional get_(uint64_t id); std::optional get_edge_(uint64_t from, uint64_t to, const std::string &key); - std::tuple> insert_node_(CRDTNode &&node); - std::tuple>> update_node_(CRDTNode &&node); - std::tuple, std::optional, std::vector> delete_node_(uint64_t id); - std::optional delete_edge_(uint64_t from, uint64_t t, const std::string &key); - std::tuple, std::optional>> insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to); + std::tuple> insert_node_(CRDTNode &&node); + std::tuple> update_node_(CRDTNode &&node); + std::tuple, std::optional, std::vector> delete_node_(uint64_t id); + std::optional delete_edge_(uint64_t from, uint64_t t, const std::string &key); + std::tuple, std::optional> insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to); ////////////////////////////////////////////////////////////////////////// // Other methods ////////////////////////////////////////////////////////////////////////// - std::map Map(); + std::map Map(); ////////////////////////////////////////////////////////////////////////// // CRDT join operations /////////////////////////////////////////////////////////////////////////// - void join_delta_node(IDL::MvregNode &&mvreg); - void join_delta_edge(IDL::MvregEdge &&mvreg); - std::optional join_delta_node_attr(IDL::MvregNodeAttr &&mvreg); - std::optional join_delta_edge_attr(IDL::MvregEdgeAttr &&mvreg); - void join_full_graph(IDL::OrMap &&full_graph); + void join_delta_node(DSR::MvregNodeMsg &&mvreg); + void join_delta_edge(DSR::MvregEdgeMsg &&mvreg); + std::optional join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg); + std::optional join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg); + void join_full_graph(DSR::OrMap &&full_graph); bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg && delta); void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg && attr); diff --git a/api/include/dsr/api/dsr_camera_api.h b/api/include/dsr/api/dsr_camera_api.h index 48666aac..c41736eb 100644 --- a/api/include/dsr/api/dsr_camera_api.h +++ b/api/include/dsr/api/dsr_camera_api.h @@ -1,7 +1,7 @@ #ifndef CAMERA_API #define CAMERA_API -#include +#include #include #include #include diff --git a/api/include/dsr/api/dsr_inner_eigen_api.h b/api/include/dsr/api/dsr_inner_eigen_api.h index 9ce61bc2..ca58689e 100644 --- a/api/include/dsr/api/dsr_inner_eigen_api.h +++ b/api/include/dsr/api/dsr_inner_eigen_api.h @@ -2,7 +2,7 @@ #define INNER_EIGEN_API #include -#include +#include #include #include #include diff --git a/api/include/dsr/api/dsr_rt_api.h b/api/include/dsr/api/dsr_rt_api.h index b23e7c1c..37e9daeb 100644 --- a/api/include/dsr/api/dsr_rt_api.h +++ b/api/include/dsr/api/dsr_rt_api.h @@ -3,7 +3,7 @@ #include #include -#include +#include #include #include #include diff --git a/api/include/dsr/api/dsr_utils.h b/api/include/dsr/api/dsr_utils.h index 77eacaa4..51b36a91 100644 --- a/api/include/dsr/api/dsr_utils.h +++ b/api/include/dsr/api/dsr_utils.h @@ -4,7 +4,7 @@ #include #include -#include +#include #include #include #include diff --git a/core/include/dsr/core/crdt/delta_crdt.h b/core/include/dsr/core/crdt/delta_crdt.h index 2101647a..1ddb6f62 100644 --- a/core/include/dsr/core/crdt/delta_crdt.h +++ b/core/include/dsr/core/crdt/delta_crdt.h @@ -11,15 +11,23 @@ Reimplementation from https://github.com/CBaquero/delta-enabled-crdts #include #include +#include "dsr/core/serialization/serializable.h" + using key_type = uint64_t; // Autonomous causal context, for context sharing in maps -class dot_context { +class dot_context : public ISerializable { public: std::map cc; // Compact causal context std::set > dc; // Dot cloud + dot_context() = default; + + dot_context(const dot_context &o) : cc(o.cc), dc(o.dc) {} + + dot_context(dot_context &&o) noexcept : cc(std::move(o.cc)), dc(std::move(o.dc)) {} + dot_context &operator=(const dot_context &o) { if (&o == this) return *this; cc = o.cc; @@ -178,12 +186,70 @@ class dot_context { bool operator>=(const dot_context &rhs) const { return !(*this < rhs); } + + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + // cc: serialize as sequence of (uint64_t, int32_t) pairs + auto cc_size = static_cast(cc.size()); + cdr << cc_size; + for (const auto& [k, v] : cc) { + cdr << k; + cdr << static_cast(v); + } + // dc: serialize as sequence of (uint64_t, int32_t) pairs + auto dc_size = static_cast(dc.size()); + cdr << dc_size; + for (const auto& [k, v] : dc) { + cdr << k; + cdr << static_cast(v); + } + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cc.clear(); + uint32_t cc_size = 0; + cdr >> cc_size; + for (uint32_t i = 0; i < cc_size; ++i) { + key_type k = 0; int32_t v = 0; + cdr >> k >> v; + cc.emplace(k, static_cast(v)); + } + dc.clear(); + uint32_t dc_size = 0; + cdr >> dc_size; + for (uint32_t i = 0; i < dc_size; ++i) { + key_type k = 0; int32_t v = 0; + cdr >> k >> v; + dc.emplace(k, static_cast(v)); + } + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t s = 0; + uint32_t dummy_u32 = 0; + key_type dummy_u64 = 0; + int32_t dummy_i32 = 0; + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); + for (const auto& [k, v] : cc) { + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u64, ca); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_i32, ca); + } + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); + for (const auto& [k, v] : dc) { + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u64, ca); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_i32, ca); + } + return s; + } }; template -class dot_kernel { +class dot_kernel : public ISerializable> { public: std::map, T> ds; // Map of dots to vals @@ -341,10 +407,55 @@ class dot_kernel { bool operator>=(const dot_kernel &rhs) const { return !(*this < rhs); } + + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + // ds: sequence of (uint64, int32, T) triples + auto ds_size = static_cast(ds.size()); + cdr << ds_size; + for (const auto& [key, val] : ds) { + cdr << key.first; + cdr << static_cast(key.second); + val.serialize(cdr); + } + c.serialize(cdr); + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + ds.clear(); + uint32_t ds_size = 0; + cdr >> ds_size; + for (uint32_t i = 0; i < ds_size; ++i) { + key_type kf = 0; int32_t ks = 0; + cdr >> kf >> ks; + T val; + val.deserialize(cdr); + ds.emplace(std::make_pair(kf, static_cast(ks)), std::move(val)); + } + c.deserialize(cdr); + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t s = 0; + uint32_t dummy_u32 = 0; + key_type dummy_u64 = 0; + int32_t dummy_i32 = 0; + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); + for (const auto& [key, val] : ds) { + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u64, ca); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_i32, ca); + s += val.serialized_size(calc, ca); + } + s += c.serialized_size(calc, ca); + return s; + } }; template -class mvreg // Multi-value register, Optimized +class mvreg : public ISerializable> // Multi-value register, Optimized { public: key_type id; @@ -460,6 +571,14 @@ class mvreg // Multi-value register, Optimized bool operator>=(const mvreg &rhs) const { return !(*this < rhs); } + + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { dk.serialize(cdr); } + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) { dk.deserialize(cdr); } + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + return dk.serialized_size(calc, ca); + } }; diff --git a/core/include/dsr/core/rtps/CRDTPubSubTypes.h b/core/include/dsr/core/rtps/CRDTPubSubTypes.h new file mode 100644 index 00000000..59b0c1ea --- /dev/null +++ b/core/include/dsr/core/rtps/CRDTPubSubTypes.h @@ -0,0 +1,140 @@ +#pragma once + +#include +#include +#include +#include + +#include +#include + +/** + * Template FastDDS TopicDataType backed by any ISerializable. + * + * Replaces the IDL-generated *PubSubType classes for all DSR topics. + * T must satisfy ISerializable (i.e. implement serialize_impl, + * deserialize_impl, serialized_size_impl). + */ +template +class CRDTPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + explicit CRDTPubSubType(const std::string& type_name) + { + set_name(type_name); + // Generous initial buffer size; FastDDS reallocates as needed. + max_serialized_type_size = 65536 + 4u; /* +4 for encapsulation */ + is_compute_key_provided = false; + } + + ~CRDTPubSubType() override = default; + + bool serialize( + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t& payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override + { + const T* p_type = static_cast(data); + + eprosima::fastcdr::FastBuffer fastbuffer( + reinterpret_cast(payload.data), payload.max_size); + + eprosima::fastcdr::Cdr ser( + fastbuffer, + eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, + data_representation == eprosima::fastdds::dds::DataRepresentationId_t::XCDR_DATA_REPRESENTATION + ? eprosima::fastcdr::CdrVersion::XCDRv1 + : eprosima::fastcdr::CdrVersion::XCDRv2); + + payload.encapsulation = + ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + ser.set_encoding_flag( + data_representation == eprosima::fastdds::dds::DataRepresentationId_t::XCDR_DATA_REPRESENTATION + ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR + : eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); + + try { + ser.serialize_encapsulation(); + p_type->serialize_impl(ser); + } catch (eprosima::fastcdr::exception::Exception& /*e*/) { + return false; + } + + payload.length = static_cast(ser.get_serialized_data_length()); + return true; + } + + bool deserialize( + eprosima::fastdds::rtps::SerializedPayload_t& payload, + void* data) override + { + T* p_type = static_cast(data); + + eprosima::fastcdr::FastBuffer fastbuffer( + reinterpret_cast(payload.data), payload.length); + + eprosima::fastcdr::Cdr deser( + fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); + + try { + deser.read_encapsulation(); + payload.encapsulation = + deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + p_type->deserialize_impl(deser); + } catch (eprosima::fastcdr::exception::Exception& /*e*/) { + return false; + } + + return true; + } + + uint32_t calculate_serialized_size( + const void* const data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override + { + const T* p_type = static_cast(data); + + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == eprosima::fastdds::dds::DataRepresentationId_t::XCDR_DATA_REPRESENTATION + ? eprosima::fastcdr::CdrVersion::XCDRv1 + : eprosima::fastcdr::CdrVersion::XCDRv2); + + size_t current_alignment{0}; + size_t size = 0; + + try { + size += p_type->serialized_size_impl(calculator, current_alignment); + } catch (eprosima::fastcdr::exception::Exception& /*e*/) { + return 0; + } + + return static_cast(size) + 4u; /* encapsulation */ + } + + void* create_data() override + { + return new T(); + } + + void delete_data(void* data) override + { + delete static_cast(data); + } + + bool compute_key( + eprosima::fastdds::rtps::SerializedPayload_t& /*payload*/, + eprosima::fastdds::rtps::InstanceHandle_t& /*handle*/, + bool /*force_md5*/) override + { + return false; + } + + bool compute_key( + const void* const /*data*/, + eprosima::fastdds::rtps::InstanceHandle_t& /*handle*/, + bool /*force_md5*/) override + { + return false; + } +}; diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index e3e59d2c..ee773895 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -7,7 +7,8 @@ #include #include -#include +#include +#include #include #include diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index 65d8707d..1a28bde9 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -9,7 +9,7 @@ #include #include -#include +#include class DSRPublisher { @@ -22,12 +22,12 @@ class DSRPublisher int8_t domain_id, bool isStreamData = false); [[nodiscard]] eprosima::fastdds::rtps::GUID_t getParticipantID() const; - bool write(IDL::GraphRequest *object); - bool write(IDL::MvregNode *object); - bool write(IDL::OrMap *object); - bool write(IDL::MvregEdge *object); - bool write(std::vector *object); - bool write(std::vector *object); + bool write(DSR::GraphRequest *object); + bool write(DSR::MvregNodeMsg *object); + bool write(DSR::OrMap *object); + bool write(DSR::MvregEdgeMsg *object); + bool write(DSR::MvregEdgeAttrVec *object); + bool write(DSR::MvregNodeAttrVec *object); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; diff --git a/core/include/dsr/core/serialization/serializable.h b/core/include/dsr/core/serialization/serializable.h new file mode 100644 index 00000000..c344535b --- /dev/null +++ b/core/include/dsr/core/serialization/serializable.h @@ -0,0 +1,36 @@ +#pragma once + +#include +#include +#include + +/** + * CRTP base for types that can be serialized directly to/from the FastCDR + * binary wire format. + * + * Each Derived class must implement: + * void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; + * void deserialize_impl(eprosima::fastcdr::Cdr& cdr); + * size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& current_alignment) const; + * + * CRDTPubSubType uses these methods as the FastDDS TopicDataType + * implementation, replacing the IDL-generated PubSubType classes. + */ +template +class ISerializable { +public: + void serialize(eprosima::fastcdr::Cdr& cdr) const + { + static_cast(this)->serialize_impl(cdr); + } + + void deserialize(eprosima::fastcdr::Cdr& cdr) + { + static_cast(this)->deserialize_impl(cdr); + } + + size_t serialized_size(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& current_alignment) const + { + return static_cast(this)->serialized_size_impl(calc, current_alignment); + } +}; diff --git a/core/include/dsr/core/types/common_types.h b/core/include/dsr/core/types/common_types.h index fdaf45dd..2407d57c 100644 --- a/core/include/dsr/core/types/common_types.h +++ b/core/include/dsr/core/types/common_types.h @@ -5,11 +5,14 @@ #ifndef DSR_COMMON_TYPES_H #define DSR_COMMON_TYPES_H -#include "../topics/IDLGraph.hpp" +#include "dsr/core/serialization/serializable.h" #include #include #include +#include +#include +#include namespace DSR { @@ -45,7 +48,7 @@ namespace DSR { }; - class Attribute + class Attribute : public ISerializable { public: @@ -70,13 +73,6 @@ namespace DSR { m_value = std::move(attr.m_value); } - explicit Attribute (IDL::Attrib &&x) noexcept - { - m_timestamp = x.timestamp(); - m_value = std::move(get_valtype(std::move(x.value()))); - m_agent_id = x.agent_id(); - } - Attribute& operator= (const Attribute& attr) { m_timestamp = attr.timestamp(); @@ -93,17 +89,10 @@ namespace DSR { return *this; } - Attribute &operator=(IDL::Attrib &&x) - { - m_timestamp = x.timestamp(); - m_value = std::move(get_valtype(std::move(x.value()))); - m_agent_id = x.agent_id(); - return *this; - } - - [[nodiscard]] IDL::Val to_IDL_val(); - - [[nodiscard]] IDL::Attrib to_IDL_attrib(); + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; + void deserialize_impl(eprosima::fastcdr::Cdr& cdr); + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const; /////////////////////// // Members @@ -359,66 +348,6 @@ namespace DSR { return !(*this < rhs); } - [[nodiscard]] static ValType get_valtype(IDL::Val &&x) - { - ValType val; - switch (x._d()) { - case 0: - val = std::move(x.str()); - break; - case 1: - val = x.dec(); - break; - case 2: - val = x.fl(); - break; - case 3: - val = std::move(x.float_vec()); - break; - case 4: - val = x.bl(); - break; - case 5: { - val = std::move(x.byte_vec()); - break; - } - case 6: { - val = x.uint(); - break; - } - case 7: { - val = x.u64(); - break; - } - case 8: { - val = x.dob(); - break; - } - case 9: { - val = std::move(x.uint64_vec()); - break; - } - case 10: { - val = x.vec_float2(); - break; - } - case 11: { - val = x.vec_float3(); - break; - } - case 12: { - val = x.vec_float4(); - break; - } - case 13: { - val = x.vec_float6(); - break; - } - default: - assert(false); - } - return val; - } private: ValType m_value; diff --git a/core/include/dsr/core/types/crdt_types.h b/core/include/dsr/core/types/crdt_types.h index 0542a8f2..1ca0658c 100644 --- a/core/include/dsr/core/types/crdt_types.h +++ b/core/include/dsr/core/types/crdt_types.h @@ -10,14 +10,14 @@ #include #include "../crdt/delta_crdt.h" -#include "../topics/IDLGraph.hpp" +#include "../serialization/serializable.h" #include "common_types.h" namespace DSR { typedef DSR::Attribute CRDTAttribute; - class CRDTEdge + class CRDTEdge : public ISerializable { public: @@ -25,10 +25,6 @@ namespace DSR { ~CRDTEdge() = default; - explicit CRDTEdge (IDL::IDLEdge &&x) noexcept; - - CRDTEdge &operator=(IDL::IDLEdge &&x); - void to(uint64_t _to); [[nodiscard]] uint64_t to() const; @@ -57,8 +53,10 @@ namespace DSR { [[nodiscard]] uint32_t agent_id() const; - [[nodiscard]] IDL::IDLEdge to_IDL_edge(uint64_t id); - + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; + void deserialize_impl(eprosima::fastcdr::Cdr& cdr); + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const; bool operator==(const CRDTEdge &rhs) const { @@ -122,7 +120,7 @@ namespace DSR { uint32_t m_agent_id{}; }; - class CRDTNode { + class CRDTNode : public ISerializable { public: @@ -140,8 +138,6 @@ namespace DSR { m_fano = x.m_fano; } - explicit CRDTNode(IDL::IDLNode &&x); - void type(const std::string &type); void type(std::string &&type); @@ -182,7 +178,10 @@ namespace DSR { [[nodiscard]] const std::map, mvreg> &fano() const; - [[nodiscard]] IDL::IDLNode to_IDL_node(uint64_t id); + // ---- ISerializable implementation ---- + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; + void deserialize_impl(eprosima::fastcdr::Cdr& cdr); + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const; bool operator==(const CRDTNode &rhs) const { diff --git a/core/include/dsr/core/types/internal_types.h b/core/include/dsr/core/types/internal_types.h new file mode 100644 index 00000000..24fcc909 --- /dev/null +++ b/core/include/dsr/core/types/internal_types.h @@ -0,0 +1,366 @@ +#pragma once + +#include "crdt_types.h" +#include "dsr/core/serialization/serializable.h" +#include +#include +#include + +namespace DSR { + + inline constexpr uint32_t DSR_PROTOCOL_VERSION = 1; + + // ---- GraphRequest -------------------------------------------------------- + // Sent by an agent that wants to receive the full graph snapshot. + + struct GraphRequest : public ISerializable + { + std::string from; + int32_t id{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << from; + cdr << id; + cdr << protocol_version; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> from; + cdr >> id; + cdr >> protocol_version; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), protocol_version, ca); + return size; + } + }; + + // ---- MvregNodeMsg -------------------------------------------------------- + // Delta or full mvreg plus routing metadata. + + struct MvregNodeMsg : public ISerializable + { + mvreg dk; + uint64_t id{}; + uint32_t agent_id{}; + uint64_t timestamp{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + dk.serialize(cdr); + cdr << id; + cdr << agent_id; + cdr << timestamp; + cdr << protocol_version; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + dk.deserialize(cdr); + cdr >> id; + cdr >> agent_id; + cdr >> timestamp; + cdr >> protocol_version; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = dk.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), protocol_version, ca); + return size; + } + }; + + // ---- MvregEdgeMsg -------------------------------------------------------- + + struct MvregEdgeMsg : public ISerializable + { + mvreg dk; + uint64_t id{}; // "from" node id + uint64_t to{}; + uint64_t from{}; + std::string type; + uint32_t agent_id{}; + uint64_t timestamp{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + dk.serialize(cdr); + cdr << id; + cdr << to; + cdr << from; + cdr << type; + cdr << agent_id; + cdr << timestamp; + cdr << protocol_version; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + dk.deserialize(cdr); + cdr >> id; + cdr >> to; + cdr >> from; + cdr >> type; + cdr >> agent_id; + cdr >> timestamp; + cdr >> protocol_version; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = dk.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), to, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), protocol_version, ca); + return size; + } + }; + + // ---- MvregNodeAttrMsg ---------------------------------------------------- + + struct MvregNodeAttrMsg : public ISerializable + { + mvreg dk; + uint64_t id{}; // publisher/delta id + uint64_t node{}; // owning node + std::string attr_name; + uint32_t agent_id{}; + uint64_t timestamp{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + dk.serialize(cdr); + cdr << id; + cdr << node; + cdr << attr_name; + cdr << agent_id; + cdr << timestamp; + cdr << protocol_version; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + dk.deserialize(cdr); + cdr >> id; + cdr >> node; + cdr >> attr_name; + cdr >> agent_id; + cdr >> timestamp; + cdr >> protocol_version; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = dk.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), node, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), attr_name, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), protocol_version, ca); + return size; + } + }; + + // ---- MvregEdgeAttrMsg ---------------------------------------------------- + + struct MvregEdgeAttrMsg : public ISerializable + { + mvreg dk; + uint64_t id{}; // "from" node id + uint64_t from_node{}; + uint64_t to_node{}; + std::string type; + std::string attr_name; + uint32_t agent_id{}; + uint64_t timestamp{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + dk.serialize(cdr); + cdr << id; + cdr << from_node; + cdr << to_node; + cdr << type; + cdr << attr_name; + cdr << agent_id; + cdr << timestamp; + cdr << protocol_version; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + dk.deserialize(cdr); + cdr >> id; + cdr >> from_node; + cdr >> to_node; + cdr >> type; + cdr >> attr_name; + cdr >> agent_id; + cdr >> timestamp; + cdr >> protocol_version; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = dk.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), from_node, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), to_node, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), attr_name, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), protocol_version, ca); + return size; + } + }; + + // ---- MvregNodeAttrVec ---------------------------------------------------- + // Batch of node-attribute deltas sent in one DDS message. + + struct MvregNodeAttrVec : public ISerializable + { + std::vector vec; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + auto count = static_cast(vec.size()); + cdr << count; + for (const auto& m : vec) + m.serialize(cdr); + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + uint32_t count = 0; + cdr >> count; + vec.resize(count); + for (auto& m : vec) + m.deserialize(cdr); + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + auto count = static_cast(vec.size()); + size_t size = calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), count, ca); + for (const auto& m : vec) + size += m.serialized_size(calc, ca); + return size; + } + }; + + // ---- MvregEdgeAttrVec ---------------------------------------------------- + + struct MvregEdgeAttrVec : public ISerializable + { + std::vector vec; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + auto count = static_cast(vec.size()); + cdr << count; + for (const auto& m : vec) + m.serialize(cdr); + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + uint32_t count = 0; + cdr >> count; + vec.resize(count); + for (auto& m : vec) + m.deserialize(cdr); + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + auto count = static_cast(vec.size()); + size_t size = calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), count, ca); + for (const auto& m : vec) + size += m.serialized_size(calc, ca); + return size; + } + }; + + // ---- OrMap --------------------------------------------------------------- + // Full graph snapshot exchanged during the join handshake. + + struct OrMap : public ISerializable + { + uint32_t to_id{}; + int32_t id{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + std::map m; + dot_context cbase; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << to_id; + cdr << id; + cdr << protocol_version; + auto count = static_cast(m.size()); + cdr << count; + for (const auto& [k, v] : m) { + cdr << k; + v.serialize(cdr); + } + cbase.serialize(cdr); + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> to_id; + cdr >> id; + cdr >> protocol_version; + uint32_t count = 0; + cdr >> count; + m.clear(); + for (uint32_t i = 0; i < count; ++i) { + uint64_t k = 0; + cdr >> k; + MvregNodeMsg v; + v.deserialize(cdr); + m.emplace(k, std::move(v)); + } + cbase.deserialize(cdr); + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), to_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), protocol_version, ca); + auto count = static_cast(m.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), count, ca); + for (const auto& [k, v] : m) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), k, ca); + size += v.serialized_size(calc, ca); + } + size += cbase.serialized_size(calc, ca); + return size; + } + }; + +} // namespace DSR diff --git a/core/include/dsr/core/types/translator.h b/core/include/dsr/core/types/translator.h index b2da8226..2a180182 100644 --- a/core/include/dsr/core/types/translator.h +++ b/core/include/dsr/core/types/translator.h @@ -7,237 +7,72 @@ #include "user_types.h" #include "crdt_types.h" +#include "internal_types.h" #include namespace DSR { - // Translators - inline static IDL::MvregNode CRDTNode_to_IDL(uint32_t agent_id, uint64_t id, mvreg &data) - { - IDL::MvregNode delta_crdt; - for (auto &kv_dots : data.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - delta_crdt.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_node(id))); - delta_crdt.dk().cbase().cc().emplace(kv_dots.first); - } - - for (auto &kv_dc : data.dk.c.dc) { - IDL::PairInt pi; - pi.first(kv_dc.first); - pi.second(kv_dc.second); - - delta_crdt.dk().cbase().dc().emplace_back(std::move(pi)); - } - - delta_crdt.dk().cbase().cc(data.dk.c.cc); + // ---- CRDT → DSR message type helpers ------------------------------------ - delta_crdt.id(id); - delta_crdt.agent_id(agent_id); - delta_crdt.timestamp(get_unix_timestamp()); - - return delta_crdt; - } - - inline static mvreg IDLNode_to_CRDT(IDL::MvregNode &&data) + inline static DSR::MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg& data) { - // Context - dot_context dotcontext_aux; - std::map m = std::move(data.dk().cbase().cc()); - std::set> s; - for (auto &v : data.dk().cbase().dc()) - s.emplace(std::make_pair(v.first(), v.second())); - dotcontext_aux.setContext(std::move(m), std::move(s)); - // Dots - std::map, CRDTNode> ds_aux; - for (auto &&val : std::move(data.dk().ds())) - ds_aux.emplace(std::pair(val.first.first(), val.first.second()), CRDTNode(std::move(val.second))); - - // Join - mvreg aw; - aw.dk.c = std::move(dotcontext_aux); - aw.dk.dot_map(std::move(ds_aux)); - return aw; + DSR::MvregNodeMsg msg; + msg.dk = data; + msg.id = id; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; + return msg; } - inline static IDL::MvregEdgeAttr - CRDTEdgeAttr_to_IDL(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, const std::string &type, - const std::string &attr, mvreg &data) + inline static DSR::MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, + const std::string& type, mvreg& data) { - IDL::MvregEdgeAttr delta_crdt; - - for (auto &kv_dots : data.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - delta_crdt.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_attrib())); - delta_crdt.dk().cbase().cc().emplace(kv_dots.first); - } - - for (auto &kv_dc : data.context().dc) { - IDL::PairInt pi; - pi.first(kv_dc.first); - pi.second(kv_dc.second); - - delta_crdt.dk().cbase().dc().emplace_back(std::move(pi)); - } - - delta_crdt.dk().cbase().cc(data.dk.c.cc); - - delta_crdt.type(type); - delta_crdt.id(id); - delta_crdt.attr_name(attr); - delta_crdt.from(from); - delta_crdt.to(to); - delta_crdt.agent_id(agent_id); - delta_crdt.timestamp(get_unix_timestamp()); - return delta_crdt; - + DSR::MvregEdgeMsg msg; + msg.dk = data; + msg.id = from; + msg.to = to; + msg.from = from; + msg.type = type; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; + return msg; } - inline static mvreg IDLEdgeAttr_to_CRDT(IDL::MvregEdgeAttr &&data) + inline static DSR::MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, + const std::string& attr, mvreg& data) { - // Context - dot_context dotcontext_aux; - std::map m = std::move(data.dk().cbase().cc()); - - std::set> s; - for (auto &v : data.dk().cbase().dc()) - s.emplace(std::make_pair(v.first(), v.second())); - dotcontext_aux.setContext(std::move(m), std::move(s)); - // Dots - std::map, CRDTAttribute> ds_aux; - for (auto &val : data.dk().ds()) { - auto&& attrib = std::move(val.second); - ds_aux.emplace(std::pair(val.first.first(), val.first.second()), - CRDTAttribute(std::move(attrib))); - } - // Join - mvreg aw; - aw.dk.c = std::move(dotcontext_aux); - aw.dk.dot_map(std::move(ds_aux)); - return aw; + DSR::MvregNodeAttrMsg msg; + msg.dk = data; + msg.id = id; + msg.node = node; + msg.attr_name = attr; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; + return msg; } - inline static IDL::MvregNodeAttr - CRDTNodeAttr_to_IDL(uint32_t agent_id, uint64_t id, uint64_t node, const std::string &attr, - mvreg &data) + inline static DSR::MvregEdgeAttrMsg CRDTEdgeAttr_to_Msg(uint32_t agent_id, uint64_t id, + uint64_t from, uint64_t to, + const std::string& type, const std::string& attr, + mvreg& data) { - IDL::MvregNodeAttr delta_crdt; - - for (auto &kv_dots : data.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - delta_crdt.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_attrib())); - delta_crdt.dk().cbase().cc().emplace(kv_dots.first); - } - - for (auto &kv_dc : data.context().dc) { - IDL::PairInt pi; - pi.first(kv_dc.first); - pi.second(kv_dc.second); - - delta_crdt.dk().cbase().dc().emplace_back(std::move(pi)); - } - - delta_crdt.dk().cbase().cc(data.dk.c.cc); - - - delta_crdt.id(id); - delta_crdt.attr_name(attr); - delta_crdt.node(node); - delta_crdt.agent_id(agent_id); - delta_crdt.timestamp(get_unix_timestamp()); - - return delta_crdt; - } - - inline static mvreg IDLNodeAttr_to_CRDT(IDL::MvregNodeAttr &&data) - { - // Context - dot_context dotcontext_aux; - std::map m = std::move(*(std::map*)&data.dk().cbase().cc()); - - std::set> s; - for (auto &v : data.dk().cbase().dc()) - s.emplace(std::make_pair(v.first(), v.second())); - dotcontext_aux.setContext(std::move(m), std::move(s)); - // Dots - std::map, CRDTAttribute> ds_aux; - for (auto &val : data.dk().ds()) { - auto&& attrib = std::move(val.second); - ds_aux.emplace(std::pair(val.first.first(), val.first.second()), - CRDTAttribute(std::move(attrib))); - } - // Join - mvreg aw; - aw.dk.c = std::move(dotcontext_aux); - aw.dk.dot_map(std::move(ds_aux)); - return aw; - } - - inline static mvreg IDLEdge_to_CRDT(IDL::MvregEdge &&data) - { - // Context - dot_context dotcontext_aux; - std::map m = std::move(*(std::map*)&data.dk().cbase().cc()); - std::set> s; - for (auto &v : data.dk().cbase().dc()) - s.emplace(std::make_pair(v.first(), v.second())); - dotcontext_aux.setContext(std::move(m), std::move(s)); - // Dots - std::map, CRDTEdge> ds_aux; - for (auto &val : data.dk().ds()) { - auto&& attrib = std::move(val.second); - ds_aux.emplace(std::pair(val.first.first(), val.first.second()), - CRDTEdge(std::move(attrib))); - } - mvreg aw; - aw.dk.c = std::move(dotcontext_aux); - aw.dk.dot_map(std::move(ds_aux)); - return aw; + DSR::MvregEdgeAttrMsg msg; + msg.dk = data; + msg.id = id; + msg.from_node = from; + msg.to_node = to; + msg.type = type; + msg.attr_name = attr; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; + return msg; } - inline static IDL::MvregEdge CRDTEdge_to_IDL(uint32_t agent_id, uint64_t from, uint64_t to, const std::string& type, - mvreg &data) - { - IDL::MvregEdge delta_crdt; - - for (auto &kv_dots : data.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - auto edge = kv_dots.second.to_IDL_edge(from); - delta_crdt.dk().ds().emplace(std::make_pair(pi, edge)); - delta_crdt.dk().cbase().cc().emplace(kv_dots.first); - - } - - for (auto &kv_dc : data.context().dc) { - IDL::PairInt pi; - pi.first(kv_dc.first); - pi.second(kv_dc.second); - - delta_crdt.dk().cbase().dc().emplace_back(std::move(pi)); - } - - delta_crdt.dk().cbase().cc(data.dk.c.cc); - - delta_crdt.from(from); - delta_crdt.to(to); - delta_crdt.type(type); - delta_crdt.id(from); - delta_crdt.agent_id(agent_id); - delta_crdt.timestamp(get_unix_timestamp()); - - return delta_crdt; - } + // ---- User ↔ CRDT helpers (kept unchanged) -------------------------------- inline static CRDTEdge user_edge_to_crdt(Edge&& edge) { diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 96789ef2..c03b6d6d 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -6,6 +6,8 @@ #include #include +#include +#include using namespace eprosima::fastdds::dds; using namespace eprosima::fastdds::rtps; @@ -28,12 +30,12 @@ std::vector host_ipv4_interfaces() } DSRParticipant::DSRParticipant() : mp_participant(nullptr), - dsrgraphType(new MvregNodePubSubType()), - graphrequestType(new GraphRequestPubSubType()), - graphRequestAnswerType(new OrMapPubSubType()), - dsrEdgeType(new MvregEdgePubSubType()), - dsrNodeAttrType(new MvregNodeAttrVecPubSubType()), - dsrEdgeAttrType(new MvregEdgeAttrVecPubSubType()), + dsrgraphType(new CRDTPubSubType("MvregNodeMsg")), + graphrequestType(new CRDTPubSubType("GraphRequest")), + graphRequestAnswerType(new CRDTPubSubType("OrMap")), + dsrEdgeType(new CRDTPubSubType("MvregEdgeMsg")), + dsrNodeAttrType(new CRDTPubSubType("MvregNodeAttrVec")), + dsrEdgeAttrType(new CRDTPubSubType("MvregEdgeAttrVec")), m_listener(nullptr) {} diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index ea13b5d5..895f4a17 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -109,7 +109,7 @@ GUID_t DSRPublisher::getParticipantID() const } -bool DSRPublisher::write(IDL::MvregNode *object) +bool DSRPublisher::write(DSR::MvregNodeMsg *object) { ReturnCode_t rt; int retry = 0; @@ -117,12 +117,12 @@ bool DSRPublisher::write(IDL::MvregNode *object) if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing NODE " << object->id() << " after 5 attempts. error code: " << rt; + qInfo() << "Error writing NODE " << object->id << " after 5 attempts. error code: " << rt; return false; } -bool DSRPublisher::write(IDL::MvregEdge *object) +bool DSRPublisher::write(DSR::MvregEdgeMsg *object) { ReturnCode_t rt; int retry = 0; @@ -130,12 +130,12 @@ bool DSRPublisher::write(IDL::MvregEdge *object) if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing EDGE " << object->from() << " " << object->to() << " " << object->type().data() << " after 5 attempts. error code: " << rt; + qInfo() << "Error writing EDGE " << object->from << " " << object->to << " " << object->type.data() << " after 5 attempts. error code: " << rt; return false; } -bool DSRPublisher::write(IDL::OrMap *object) +bool DSRPublisher::write(DSR::OrMap *object) { ReturnCode_t rt; int retry = 0; @@ -143,11 +143,11 @@ bool DSRPublisher::write(IDL::OrMap *object) if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing GRAPH " << object->m().size() << " after 5 attempts. error code: " << rt; + qInfo() << "Error writing GRAPH " << object->m.size() << " after 5 attempts. error code: " << rt; return false; } -bool DSRPublisher::write(IDL::GraphRequest *object) +bool DSRPublisher::write(DSR::GraphRequest *object) { ReturnCode_t rt; int retry = 0; @@ -159,7 +159,7 @@ bool DSRPublisher::write(IDL::GraphRequest *object) return false; } -bool DSRPublisher::write(std::vector *object) +bool DSRPublisher::write(DSR::MvregEdgeAttrVec *object) { ReturnCode_t rt; int retry = 0; @@ -167,18 +167,18 @@ bool DSRPublisher::write(std::vector *object) if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; return false; } -bool DSRPublisher::write(std::vector *object) { +bool DSRPublisher::write(DSR::MvregNodeAttrVec *object) { ReturnCode_t rt; int retry = 0; while (retry < 5) { if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + qInfo() << "Error writing NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; return false; } diff --git a/core/types/common_types.cpp b/core/types/common_types.cpp index 70c123e2..5a308eb2 100644 --- a/core/types/common_types.cpp +++ b/core/types/common_types.cpp @@ -8,72 +8,109 @@ namespace DSR { ///////////////////////////////////////////////////// - /// Attribute + /// Attribute — CDR serialization //////////////////////////////////////////////////// - IDL::Attrib Attribute::to_IDL_attrib() { - IDL::Attrib att; - att.timestamp(m_timestamp); - att.type(m_value.index()); - att.value(to_IDL_val()); - att.agent_id(m_agent_id); - return att; - } - - IDL::Val Attribute::to_IDL_val() - { - IDL::Val value; - - switch (m_value.index()) { - case 0: - value.str(std::get(m_value)); - break; - case 1: - value.dec(std::get(m_value)); - break; - case 2: - value.fl(std::get(m_value)); - break; - case 3: - value.float_vec(std::get>(m_value)); - break; - case 4: - value.bl(std::get(m_value)); - break; - case 5: - value.byte_vec(std::get>(m_value)); - break; - case 6: - value.uint(std::get(m_value)); + void Attribute::serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + auto disc = static_cast(m_value.index()); + cdr << disc; + switch (disc) { + case 0: cdr << std::get(m_value); break; + case 1: cdr << std::get(m_value); break; + case 2: cdr << std::get(m_value); break; + case 3: cdr << std::get>(m_value); break; + case 4: cdr << std::get(m_value); break; + case 5: cdr << std::get>(m_value); break; + case 6: cdr << std::get(m_value); break; + case 7: cdr << std::get(m_value); break; + case 8: cdr << std::get(m_value); break; + case 9: cdr << std::get>(m_value); break; + case 10: { + const auto& a = std::get>(m_value); + for (float f : a) cdr << f; break; - case 7: - value.u64(std::get(m_value)); + } + case 11: { + const auto& a = std::get>(m_value); + for (float f : a) cdr << f; break; - case 8: - value.dob(std::get(m_value)); + } + case 12: { + const auto& a = std::get>(m_value); + for (float f : a) cdr << f; break; - case 9: - value.uint64_vec(std::get>(m_value)); + } + case 13: { + const auto& a = std::get>(m_value); + for (float f : a) cdr << f; break; - case 10: - value.vec_float2(std::get>(m_value)); - break; - case 11: - value.vec_float3(std::get>(m_value)); - break; - case 12: - value.vec_float4(std::get>(m_value)); - break; - case 13: - value.vec_float6(std::get>(m_value)); - break; - default: - throw std::runtime_error( - ("Error converting DSR::Attribute to IDL::Attrib. The Attribute is uninitialized. " + - std::to_string(__LINE__) + " " + __FILE__).data()); + } + default: assert(false); + } + cdr << m_timestamp << m_agent_id; + } + + void Attribute::deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + uint32_t disc = 0; + cdr >> disc; + switch (disc) { + case 0: { std::string v; cdr >> v; m_value = std::move(v); break; } + case 1: { int32_t v; cdr >> v; m_value = v; break; } + case 2: { float v; cdr >> v; m_value = v; break; } + case 3: { std::vector v; cdr >> v; m_value = std::move(v); break; } + case 4: { bool v; cdr >> v; m_value = v; break; } + case 5: { std::vector v; cdr >> v; m_value = std::move(v); break; } + case 6: { uint32_t v; cdr >> v; m_value = v; break; } + case 7: { uint64_t v; cdr >> v; m_value = v; break; } + case 8: { double v; cdr >> v; m_value = v; break; } + case 9: { std::vector v; cdr >> v; m_value = std::move(v); break; } + case 10: { std::array a{}; for (float& f : a) cdr >> f; m_value = a; break; } + case 11: { std::array a{}; for (float& f : a) cdr >> f; m_value = a; break; } + case 12: { std::array a{}; for (float& f : a) cdr >> f; m_value = a; break; } + case 13: { std::array a{}; for (float& f : a) cdr >> f; m_value = a; break; } + default: assert(false); } + cdr >> m_timestamp >> m_agent_id; + } + + size_t Attribute::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t s = 0; + uint32_t dummy_u32 = 0; + uint64_t dummy_u64 = 0; + int32_t dummy_i32 = 0; + float dummy_f = 0.f; + double dummy_d = 0.0; + bool dummy_b = false; - return value; + // discriminant + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); + switch (m_value.index()) { + case 0: { const auto& v = std::get(m_value); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), v, ca); break; } + case 1: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_i32, ca); break; + case 2: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_f, ca); break; + case 3: { const auto& v = std::get>(m_value); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), v, ca); break; } + case 4: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_b, ca); break; + case 5: { const auto& v = std::get>(m_value); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), v, ca); break; } + case 6: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); break; + case 7: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u64, ca); break; + case 8: s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_d, ca); break; + case 9: { const auto& v = std::get>(m_value); + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), v, ca); break; } + case 10: for (int i = 0; i < 2; ++i) s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_f, ca); break; + case 11: for (int i = 0; i < 3; ++i) s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_f, ca); break; + case 12: for (int i = 0; i < 4; ++i) s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_f, ca); break; + case 13: for (int i = 0; i < 6; ++i) s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_f, ca); break; + default: break; + } + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u64, ca); // timestamp + s += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), dummy_u32, ca); // agent_id + return s; } const ValType &Attribute::value() const diff --git a/core/types/crdt_types.cpp b/core/types/crdt_types.cpp index 3c8f4858..f5e89530 100644 --- a/core/types/crdt_types.cpp +++ b/core/types/crdt_types.cpp @@ -4,41 +4,11 @@ #include -#include +#include +#include namespace DSR { - CRDTEdge::CRDTEdge (IDL::IDLEdge &&x) noexcept - { - - m_to = x.to(); - m_type = std::move(x.type()); - m_from = x.from(); - if (!x.attrs().empty()) { - for (auto&[k, v] : x.attrs()) { - m_attrs.emplace(k , IDLEdgeAttr_to_CRDT(std::move(v))); - } - } - m_agent_id = x.agent_id(); - - } - - CRDTEdge &CRDTEdge::operator=(IDL::IDLEdge &&x) - { - - m_to = x.to(); - m_type = std::move(x.type()); - m_from = x.from(); - if (!x.attrs().empty()) { - for (auto&[k, v] : x.attrs()) { - m_attrs.emplace(k , IDLEdgeAttr_to_CRDT(std::move(v))); - } - } - m_agent_id = x.agent_id(); - - return *this; - } - void CRDTEdge::to(uint64_t _to) { m_to = _to; @@ -109,52 +79,56 @@ namespace DSR { return m_agent_id; } - IDL::IDLEdge CRDTEdge::to_IDL_edge(uint64_t id) { - IDL::IDLEdge edge; - edge.from(m_from); - edge.to(m_to); - edge.type(m_type); - edge.agent_id(m_agent_id); - for (auto &[k, v] : m_attrs) { - - IDL::MvregEdgeAttr edgeAttr; - for (auto &kv_dots : v.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - edgeAttr.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_attrib())); - edgeAttr.dk().cbase().cc().emplace(kv_dots.first); - - } - - edgeAttr.from(m_from); - edgeAttr.to(m_to); - edgeAttr.type(m_type); - edgeAttr.agent_id(v.read_reg().agent_id()); - edgeAttr.id(id); - - edge.attrs().emplace(k, std::move(edgeAttr)); + void CRDTEdge::serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << m_to; + cdr << m_from; + cdr << m_type; + cdr << m_agent_id; + // serialize attrs map: uint32_t count, then key + value + auto count = static_cast(m_attrs.size()); + cdr << count; + for (const auto &[k, v] : m_attrs) { + cdr << k; + v.serialize(cdr); } - return edge; } + void CRDTEdge::deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> m_to; + cdr >> m_from; + cdr >> m_type; + cdr >> m_agent_id; + uint32_t count = 0; + cdr >> count; + m_attrs.clear(); + for (uint32_t i = 0; i < count; ++i) { + std::string key; + cdr >> key; + mvreg val; + val.deserialize(cdr); + m_attrs.emplace(std::move(key), std::move(val)); + } + } - CRDTNode::CRDTNode(IDL::IDLNode &&x) + size_t CRDTEdge::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const { - m_type = std::move(x.type()); - m_name = std::move(x.name()); - m_id = x.id(); - m_agent_id = x.agent_id(); - for (auto&[k, v] : x.attrs()) { - m_attrs.emplace(k, IDLNodeAttr_to_CRDT(std::move(v))); - } - for (auto&[k, v] : x.fano()) { - m_fano.emplace(std::pair{k.to(), k.type()}, - IDLEdge_to_CRDT(std::move(v))); + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), m_to, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), m_from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), m_type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), m_agent_id, ca); + auto count = static_cast(m_attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), count, ca); + for (const auto &[k, v] : m_attrs) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), k, ca); + size += v.serialized_size(calc, ca); } + return size; } + void CRDTNode::type(const std::string &type) { m_type = type; @@ -256,52 +230,80 @@ namespace DSR { } - IDL::IDLNode CRDTNode::to_IDL_node(uint64_t id) { - IDL::IDLNode node; - node.id(m_id); - node.name(m_name); - node.type(m_type); - node.agent_id(m_agent_id); - for (auto &[k, v] : m_attrs) { - IDL::MvregNodeAttr nodeAttr; - for (auto &kv_dots : v.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - nodeAttr.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_attrib())); - nodeAttr.dk().cbase().cc().emplace(kv_dots.first); - } - - nodeAttr.id(id); - nodeAttr.attr_name(k); - nodeAttr.agent_id(v.read_reg().agent_id()); - node.attrs().emplace(k, std::move(nodeAttr)); + void CRDTNode::serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << m_id; + cdr << m_type; + cdr << m_name; + cdr << m_agent_id; + // attrs map + auto attr_count = static_cast(m_attrs.size()); + cdr << attr_count; + for (const auto &[k, v] : m_attrs) { + cdr << k; + v.serialize(cdr); + } + // fano map: key is pair + auto fano_count = static_cast(m_fano.size()); + cdr << fano_count; + for (const auto &[k, v] : m_fano) { + cdr << k.first; + cdr << k.second; + v.serialize(cdr); } + } - for (auto &[k, v] : m_fano) { - IDL::MvregEdge mvregCRDTEdge; - for (auto &kv_dots : v.dk.ds) { - IDL::PairInt pi; - pi.first(kv_dots.first.first); - pi.second(kv_dots.first.second); - - mvregCRDTEdge.dk().ds().emplace(std::make_pair(pi, kv_dots.second.to_IDL_edge(id))); - mvregCRDTEdge.dk().cbase().cc().emplace(kv_dots.first); - - } - - mvregCRDTEdge.id(id); - mvregCRDTEdge.agent_id(v.read_reg().agent_id()); - mvregCRDTEdge.to(k.first); - mvregCRDTEdge.from(v.read_reg().from()); - mvregCRDTEdge.type(k.second); - IDL::EdgeKey ek; - ek.to(k.first); - ek.type(k.second); - node.fano().emplace(ek, std::move(mvregCRDTEdge)); + void CRDTNode::deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> m_id; + cdr >> m_type; + cdr >> m_name; + cdr >> m_agent_id; + uint32_t attr_count = 0; + cdr >> attr_count; + m_attrs.clear(); + for (uint32_t i = 0; i < attr_count; ++i) { + std::string key; + cdr >> key; + mvreg val; + val.deserialize(cdr); + m_attrs.emplace(std::move(key), std::move(val)); + } + uint32_t fano_count = 0; + cdr >> fano_count; + m_fano.clear(); + for (uint32_t i = 0; i < fano_count; ++i) { + uint64_t fano_to = 0; + std::string fano_type; + cdr >> fano_to; + cdr >> fano_type; + mvreg val; + val.deserialize(cdr); + m_fano.emplace(std::make_pair(fano_to, std::move(fano_type)), std::move(val)); + } + } + + size_t CRDTNode::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), m_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), m_type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), m_name, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), m_agent_id, ca); + auto attr_count = static_cast(m_attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), attr_count, ca); + for (const auto &[k, v] : m_attrs) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), k, ca); + size += v.serialized_size(calc, ca); + } + auto fano_count = static_cast(m_fano.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), fano_count, ca); + for (const auto &[k, v] : m_fano) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), k.first, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), k.second, ca); + size += v.serialized_size(calc, ca); } - return node; + return size; } } diff --git a/tests/synchronization/graph_synchronization.cpp b/tests/synchronization/graph_synchronization.cpp index c3fba1b9..526a4843 100644 --- a/tests/synchronization/graph_synchronization.cpp +++ b/tests/synchronization/graph_synchronization.cpp @@ -8,7 +8,7 @@ #include "catch2/catch_test_macros.hpp" #include "catch2/generators/catch_generators.hpp" -#include "dsr/core/topics/IDLGraph.hpp" +#include "dsr/core/types/internal_types.h" using namespace DSR; using namespace std::chrono_literals; @@ -18,12 +18,17 @@ namespace DSR class DSRGraphTestAccess { public: - static std::map Map(DSRGraph& graph) + static std::map Map(DSRGraph& graph) { return graph.Map(); } - static void join_full_graph(DSRGraph& graph, IDL::OrMap&& full_graph) + static void join_delta_node(DSRGraph& graph, DSR::MvregNodeMsg&& delta) + { + graph.join_delta_node(std::move(delta)); + } + + static void join_full_graph(DSRGraph& graph, DSR::OrMap&& full_graph) { graph.join_full_graph(std::move(full_graph)); } @@ -108,10 +113,10 @@ TEST_CASE("Full graph join does not leave empty node registers after local delet REQUIRE(graph.insert_node_with_id(node).has_value()); REQUIRE(graph.size() == initial_size + 1); - IDL::OrMap full_graph; - full_graph.id(graph.get_agent_id()); - full_graph.to_id(graph.get_agent_id()); - full_graph.m(DSRGraphTestAccess::Map(graph)); + DSR::OrMap full_graph; + full_graph.id = graph.get_agent_id(); + full_graph.to_id = graph.get_agent_id(); + full_graph.m = DSRGraphTestAccess::Map(graph); REQUIRE(graph.delete_node(node.id())); REQUIRE(graph.size() == initial_size); @@ -122,3 +127,51 @@ TEST_CASE("Full graph join does not leave empty node registers after local delet REQUIRE(graph.size() == initial_size); REQUIRE_FALSE(graph.get_node(node.id()).has_value()); } + +TEST_CASE("Full graph join rejects incompatible protocol versions", "[SYNCHRONIZATION][GRAPH][VERSION]") +{ + auto ctx = make_empty_config_file(); + DSRGraph sender(random_string(10), static_cast(rand() % 2000 + 1000), ctx); + DSRGraph receiver(random_string(10), static_cast(rand() % 1000 + 3000), ctx); + + auto node = Node::create("version_mismatch_node"); + node.id(2000); + node.agent_id(sender.get_agent_id()); + + REQUIRE(sender.insert_node_with_id(node).has_value()); + REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); + + DSR::OrMap full_graph; + full_graph.id = static_cast(sender.get_agent_id()); + full_graph.to_id = receiver.get_agent_id(); + full_graph.protocol_version = DSR::DSR_PROTOCOL_VERSION + 1; + full_graph.m = DSRGraphTestAccess::Map(sender); + + DSRGraphTestAccess::join_full_graph(receiver, std::move(full_graph)); + + REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); +} + +TEST_CASE("Node delta join rejects incompatible protocol versions", "[SYNCHRONIZATION][GRAPH][VERSION]") +{ + auto ctx = make_empty_config_file(); + DSRGraph sender(random_string(10), static_cast(rand() % 2000 + 1000), ctx); + DSRGraph receiver(random_string(10), static_cast(rand() % 1000 + 3000), ctx); + + auto node = Node::create("delta_version_mismatch_node"); + node.id(3000); + node.agent_id(sender.get_agent_id()); + + REQUIRE(sender.insert_node_with_id(node).has_value()); + REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); + + auto map = DSRGraphTestAccess::Map(sender); + auto it = map.find(node.id()); + REQUIRE(it != map.end()); + + auto delta = std::move(it->second); + delta.protocol_version = DSR::DSR_PROTOCOL_VERSION + 1; + DSRGraphTestAccess::join_delta_node(receiver, std::move(delta)); + + REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); +} diff --git a/tests/synchronization/type_translation.cpp b/tests/synchronization/type_translation.cpp index f4148293..ecb1867e 100644 --- a/tests/synchronization/type_translation.cpp +++ b/tests/synchronization/type_translation.cpp @@ -8,19 +8,38 @@ #include "catch2/generators/catch_generators.hpp" #include "dsr/core/crdt/delta_crdt.h" -#include "dsr/core/topics/IDLGraph.hpp" +#include "dsr/core/types/internal_types.h" #include "dsr/core/types/common_types.h" #include "dsr/core/types/crdt_types.h" #include "dsr/core/types/translator.h" #include "dsr/core/types/type_checking/dsr_edge_type.h" #include "dsr/core/types/type_checking/dsr_node_type.h" #include "dsr/core/types/user_types.h" +#include "dsr/core/rtps/CRDTPubSubTypes.h" + +#include +#include using namespace DSR; +// Helper: serialize T to a byte buffer and deserialize into a fresh T. +template +T roundtrip(const T& src) +{ + eprosima::fastcdr::FastBuffer buf; + eprosima::fastcdr::Cdr ser(buf, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); + ser.serialize_encapsulation(); + src.serialize_impl(ser); + + eprosima::fastcdr::Cdr deser(buf, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); + deser.read_encapsulation(); + T dst; + dst.deserialize_impl(deser); + return dst; +} -TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]"){ +TEST_CASE("NODE: from DSR representation to CRDT and back via serialization", "[TRANSLATION][NODE]"){ uint32_t agent_id = random_number(); auto id = random_number(); @@ -30,8 +49,8 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") static auto new_attribute_ = [&]() -> std::pair { const auto val = random_choose(std::vector{ - (int)12, - random_string(), + (int)12, + random_string(), std::vector{1.0, 2.0, 3.0} }); Attribute attr(val, random_number(), static_cast(random_number())); @@ -39,7 +58,7 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") }; - auto attributes = GENERATE(std::map{}, + auto attributes = GENERATE(std::map{}, std::map{new_attribute_(), new_attribute_(), new_attribute_(), new_attribute_()}); static auto new_edge_ = [&]() -> std::pair, DSR::Edge> { @@ -56,13 +75,13 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") return std::make_pair(key, edge); }; - auto fano = GENERATE(std::map, DSR::Edge>{}, + auto fano = GENERATE(std::map, DSR::Edge>{}, std::map, DSR::Edge>{ new_edge_(), new_edge_(),new_edge_() }); SECTION("User Node representation"){ - + auto node = Node::create (attributes, fano); node.id(id); node.name(name); @@ -73,19 +92,19 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") REQUIRE(node.id() == id); REQUIRE(node.name() == name); REQUIRE(node.agent_id() == agent_id); - - - SECTION("Copy node"){ + + + SECTION("Copy node — CRDT round-trip"){ CRDTNode crdt_node = user_node_to_crdt(node); REQUIRE(crdt_node.attrs().size() == attributes.size()); REQUIRE(crdt_node.fano().size() == fano.size()); REQUIRE(crdt_node.id() == id); REQUIRE(crdt_node.name() == name); REQUIRE(crdt_node.agent_id() == agent_id); - + mvreg mvreg_node; auto delta = mvreg_node.write(crdt_node); - + REQUIRE(mvreg_node.read_reg() == crdt_node); REQUIRE(delta.read_reg() == crdt_node); @@ -96,19 +115,18 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") REQUIRE(reg.name() == name); REQUIRE(reg.agent_id() == agent_id); - - IDL::IDLNode idl_node = reg.to_IDL_node(id); - REQUIRE(idl_node.attrs().size() == attributes.size()); - REQUIRE(idl_node.fano().size() == fano.size()); - REQUIRE(idl_node.id() == id); - REQUIRE(idl_node.name() == name); - REQUIRE(idl_node.agent_id() == agent_id); - REQUIRE(idl_node.type() == robot_node_type::attr_name); - + // Serialization round-trip + CRDTNode rt = roundtrip(reg); + REQUIRE(rt.attrs().size() == attributes.size()); + REQUIRE(rt.fano().size() == fano.size()); + REQUIRE(rt.id() == id); + REQUIRE(rt.name() == name); + REQUIRE(rt.agent_id() == agent_id); + REQUIRE(rt.type() == robot_node_type::attr_name); } - SECTION("Move node"){ - + SECTION("Move node — CRDT round-trip"){ + CRDTNode crdt_node = user_node_to_crdt(std::move(node)); REQUIRE(crdt_node.attrs().size() == attributes.size()); REQUIRE(crdt_node.fano().size() == fano.size()); @@ -127,13 +145,14 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") REQUIRE(reg.name() == name); REQUIRE(reg.agent_id() == agent_id); - IDL::IDLNode idl_node = reg.to_IDL_node(id); - REQUIRE(idl_node.attrs().size() == attributes.size()); - REQUIRE(idl_node.fano().size() == fano.size()); - REQUIRE(idl_node.id() == id); - REQUIRE(idl_node.name() == name); - REQUIRE(idl_node.agent_id() == agent_id); - REQUIRE(idl_node.type() == robot_node_type::attr_name); + // Serialization round-trip + CRDTNode rt = roundtrip(reg); + REQUIRE(rt.attrs().size() == attributes.size()); + REQUIRE(rt.fano().size() == fano.size()); + REQUIRE(rt.id() == id); + REQUIRE(rt.name() == name); + REQUIRE(rt.agent_id() == agent_id); + REQUIRE(rt.type() == robot_node_type::attr_name); } } @@ -143,7 +162,7 @@ TEST_CASE("NODE: from DSR representation to CRDT to IDL", "[TRANSLATION][NODE]") -TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]"){ +TEST_CASE("EDGE: from DSR representation to CRDT and back via serialization", "[TRANSLATION][EDGE]"){ uint32_t agent_id = random_number(); auto from = random_number(); @@ -153,8 +172,8 @@ TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]") static auto new_attribute_ = [&]() -> std::pair { auto val = random_choose(std::vector{ - (int)12, - random_string(), + (int)12, + random_string(), std::vector{1.0, 2.0, 3.0} }); Attribute attr(val, random_number(), static_cast(random_number())); @@ -162,11 +181,11 @@ TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]") }; - auto attributes = GENERATE(std::map{}, + auto attributes = GENERATE(std::map{}, std::map{new_attribute_(), new_attribute_(), new_attribute_(), new_attribute_()}); SECTION("User Edge representation"){ - + auto edge = Edge::create (from, to, attributes); edge.agent_id(agent_id); @@ -175,19 +194,19 @@ TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]") REQUIRE(edge.to() == to); REQUIRE(edge.type() == in_edge_type_str); REQUIRE(edge.agent_id() == agent_id); - - - SECTION("Copy edge"){ + + + SECTION("Copy edge — CRDT round-trip"){ CRDTEdge crdt_edge = user_edge_to_crdt(edge); REQUIRE(crdt_edge.attrs().size() == attributes.size()); REQUIRE(crdt_edge.from() == from); REQUIRE(crdt_edge.to() == to); REQUIRE(crdt_edge.type() == in_edge_type_str); REQUIRE(crdt_edge.agent_id() == agent_id); - + mvreg mvreg_edge; auto delta = mvreg_edge.write(crdt_edge); - + REQUIRE(mvreg_edge.read_reg() == crdt_edge); REQUIRE(delta.read_reg() == crdt_edge); @@ -198,28 +217,27 @@ TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]") REQUIRE(reg.type() == in_edge_type_str); REQUIRE(reg.agent_id() == agent_id); - - IDL::IDLEdge idl_node = reg.to_IDL_edge(from); - REQUIRE(idl_node.attrs().size() == attributes.size()); - REQUIRE(idl_node.from() == from); - REQUIRE(idl_node.to() == to); - REQUIRE(idl_node.agent_id() == agent_id); - REQUIRE(idl_node.type() == in_edge_type_str); - + // Serialization round-trip + CRDTEdge rt = roundtrip(reg); + REQUIRE(rt.attrs().size() == attributes.size()); + REQUIRE(rt.from() == from); + REQUIRE(rt.to() == to); + REQUIRE(rt.agent_id() == agent_id); + REQUIRE(rt.type() == in_edge_type_str); } - SECTION("Move edge"){ - + SECTION("Move edge — CRDT round-trip"){ + CRDTEdge crdt_edge = user_edge_to_crdt(edge); REQUIRE(crdt_edge.attrs().size() == attributes.size()); REQUIRE(crdt_edge.from() == from); REQUIRE(crdt_edge.to() == to); REQUIRE(crdt_edge.type() == in_edge_type_str); REQUIRE(crdt_edge.agent_id() == agent_id); - + mvreg mvreg_edge; auto delta = mvreg_edge.write(crdt_edge); - + REQUIRE(delta.read_reg() == mvreg_edge.read_reg()); auto& reg = mvreg_edge.read_reg(); @@ -229,16 +247,16 @@ TEST_CASE("EDGE: from DSR representation to CRDT to IDL", "[TRANSLATION][EDGE]") REQUIRE(reg.type() == in_edge_type_str); REQUIRE(reg.agent_id() == agent_id); - - IDL::IDLEdge idl_node = reg.to_IDL_edge(from); - REQUIRE(idl_node.attrs().size() == attributes.size()); - REQUIRE(idl_node.from() == from); - REQUIRE(idl_node.to() == to); - REQUIRE(idl_node.agent_id() == agent_id); - REQUIRE(idl_node.type() == in_edge_type_str); + // Serialization round-trip + CRDTEdge rt = roundtrip(reg); + REQUIRE(rt.attrs().size() == attributes.size()); + REQUIRE(rt.from() == from); + REQUIRE(rt.to() == to); + REQUIRE(rt.agent_id() == agent_id); + REQUIRE(rt.type() == in_edge_type_str); } } -} \ No newline at end of file +} From a1f7e5dab3889c8d1e5d0c816a3dd19422dee7f9 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sat, 18 Apr 2026 21:51:52 +0200 Subject: [PATCH 02/38] refactor: avoid unnecesary copies in new serialization --- api/dsr_api.cpp | 18 +++++++-------- core/include/dsr/core/types/translator.h | 29 +++++++++++++----------- 2 files changed, 25 insertions(+), 22 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 3c7af5b3..89787854 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -218,7 +218,7 @@ std::tuple> DSRGraph::insert_node_(CRDTNo update_maps_node_insert(id, node); mvreg delta = nodes[id].write(std::move(node)); - return {true, CRDTNode_to_Msg(agent_id, id, delta)}; + return {true, CRDTNode_to_Msg(agent_id, id, std::move(delta))}; } return {false, {}}; } @@ -321,7 +321,7 @@ std::tuple> DSRGraph::update_node_(CR if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(agent_id, node.id(), node.id(), k, delta)); + CRDTNodeAttr_to_Msg(agent_id, node.id(), node.id(), k, std::move(delta))); } } //Remove old attributes. @@ -333,7 +333,7 @@ std::tuple> DSRGraph::update_node_(CR } else if (!node.attrs().contains(k)) { auto delta = it_a->second.reset(); atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, delta)); + CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); it_a = iter.erase(it_a); } else { ++it_a; @@ -412,7 +412,7 @@ DSRGraph::delete_node_(uint64_t id) { } // Get remove delta. auto delta = nodes[id].reset(); - DSR::MvregNodeMsg delta_remove = CRDTNode_to_Msg(agent_id, id, delta); + DSR::MvregNodeMsg delta_remove = CRDTNode_to_Msg(agent_id, id, std::move(delta)); // Search and remove incoming edges using to_edges cache: O(k) instead of O(n). { decltype(to_edges)::mapped_type incoming; @@ -427,7 +427,7 @@ DSRGraph::delete_node_(uint64_t id) { auto &visited_node = nodes.at(from).read_reg(); deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); auto delta_fano = visited_node.fano().at({id, type}).reset(); - delta_vec.emplace_back(CRDTEdge_to_Msg(agent_id, from, id, type, delta_fano)); + delta_vec.emplace_back(CRDTEdge_to_Msg(agent_id, from, id, type, std::move(delta_fano))); visited_node.fano().erase({id, type}); update_maps_edge_delete(from, id, type); } @@ -661,7 +661,7 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), k, delta)); + CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), k, std::move(delta))); } } auto it = iter_edge.begin(); @@ -671,7 +671,7 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) auto delta = it->second.reset(); it = iter_edge.erase(it); atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), att, delta)); + CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); } else { ++it; } @@ -682,7 +682,7 @@ DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) std::string att_type = attrs.type(); auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); update_maps_edge_insert(from, to, att_type); - return {true, CRDTEdge_to_Msg(agent_id, from, to, att_type, delta), {}}; + return {true, CRDTEdge_to_Msg(agent_id, from, to, std::move(att_type), std::move(delta)), {}}; } } return {false, {}, {}}; @@ -747,7 +747,7 @@ std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t auto delta = node.fano().at({to, key}).reset(); node.fano().erase({to, key}); update_maps_edge_delete(from, to, key); - return CRDTEdge_to_Msg(agent_id, from, to, key, delta); + return CRDTEdge_to_Msg(agent_id, from, to, key, std::move(delta)); } } return {}; diff --git a/core/include/dsr/core/types/translator.h b/core/include/dsr/core/types/translator.h index 2a180182..65fd8139 100644 --- a/core/include/dsr/core/types/translator.h +++ b/core/include/dsr/core/types/translator.h @@ -14,10 +14,10 @@ namespace DSR { // ---- CRDT → DSR message type helpers ------------------------------------ - inline static DSR::MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg& data) + inline static DSR::MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg&& data) { DSR::MvregNodeMsg msg; - msg.dk = data; + msg.dk = std::move(data); msg.id = id; msg.agent_id = agent_id; msg.timestamp = get_unix_timestamp(); @@ -25,47 +25,50 @@ namespace DSR { return msg; } + template inline static DSR::MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, - const std::string& type, mvreg& data) + S&& type, mvreg&& data) { DSR::MvregEdgeMsg msg; - msg.dk = data; + msg.dk = std::move(data); msg.id = from; msg.to = to; msg.from = from; - msg.type = type; + msg.type = std::forward(type); msg.agent_id = agent_id; msg.timestamp = get_unix_timestamp(); msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; return msg; } + template inline static DSR::MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, - const std::string& attr, mvreg& data) + S&& attr, mvreg&& data) { DSR::MvregNodeAttrMsg msg; - msg.dk = data; + msg.dk = std::move(data); msg.id = id; msg.node = node; - msg.attr_name = attr; + msg.attr_name = std::forward(attr); msg.agent_id = agent_id; msg.timestamp = get_unix_timestamp(); msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; return msg; } + template inline static DSR::MvregEdgeAttrMsg CRDTEdgeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, - const std::string& type, const std::string& attr, - mvreg& data) + TS&& type, AS&& attr, + mvreg&& data) { DSR::MvregEdgeAttrMsg msg; - msg.dk = data; + msg.dk = std::move(data); msg.id = id; msg.from_node = from; msg.to_node = to; - msg.type = type; - msg.attr_name = attr; + msg.type = std::forward(type); + msg.attr_name = std::forward(attr); msg.agent_id = agent_id; msg.timestamp = get_unix_timestamp(); msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; From 95b4e22ca534dede19b5da810b76da99a189e2ff Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sat, 18 Apr 2026 22:06:50 +0200 Subject: [PATCH 03/38] refactor: remove old files --- core/CMakeLists.txt | 8 +- core/crdt/delta-crdts.cc.old | 2303 ------- core/include/dsr/core/topics/IDLGraph.hpp | 5578 ----------------- .../dsr/core/topics/IDLGraphCdrAux.hpp | 159 - .../dsr/core/topics/IDLGraphPubSubTypes.hpp | 1419 ----- core/include/dsr/core/types/crdt_types.h | 10 +- core/topics/IDLGraph.idl | 169 - core/topics/IDLGraphCdrAux.ipp | 2238 ------- core/topics/IDLGraphPubSubTypes.cxx | 3111 --------- core/topics/regenidl.md | 50 - tests/graph/rt_timestamp.cpp | 18 +- 11 files changed, 16 insertions(+), 15047 deletions(-) delete mode 100644 core/crdt/delta-crdts.cc.old delete mode 100644 core/include/dsr/core/topics/IDLGraph.hpp delete mode 100644 core/include/dsr/core/topics/IDLGraphCdrAux.hpp delete mode 100644 core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp delete mode 100644 core/topics/IDLGraph.idl delete mode 100644 core/topics/IDLGraphCdrAux.ipp delete mode 100644 core/topics/IDLGraphPubSubTypes.cxx delete mode 100644 core/topics/regenidl.md diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 09a5efcb..359128ea 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -32,12 +32,8 @@ target_sources(dsr_core include/dsr/core/rtps/dsrpublisher.h include/dsr/core/rtps/dsrsubscriber.h - topics/IDLGraphPubSubTypes.cxx - #topics/IDLGraph.cxx - topics/IDLGraphCdrAux.ipp - include/dsr/core/topics/IDLGraph.hpp - include/dsr/core/topics/IDLGraphPubSubTypes.hpp - include/dsr/core/topics/IDLGraphCdrAux.hpp + include/dsr/core/rtps/CRDTPubSubTypes.h + include/dsr/core/serialization/serializable.h include/dsr/core/crdt/delta_crdt.h diff --git a/core/crdt/delta-crdts.cc.old b/core/crdt/delta-crdts.cc.old deleted file mode 100644 index bdf7cab3..00000000 --- a/core/crdt/delta-crdts.cc.old +++ /dev/null @@ -1,2303 +0,0 @@ -//------------------------------------------------------------------- -// -// File: delta-crdts.cc -// -// @author Carlos Baquero -// -// @copyright 2014-2016 Carlos Baquero -// -// This file is provided to you under the Apache License, -// Version 2.0 (the "License"); you may not use this file -// except in compliance with the License. You may obtain -// a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, -// software distributed under the License is distributed on an -// "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY -// KIND, either express or implied. See the License for the -// specific language governing permissions and limitations -// under the License. -// -// @doc -// Reference implementation in C++ of delta enabled CRDTs -// @end -// -// -//------------------------------------------------------------------- - -#ifndef DELTA_CRDT -#define DELTA_CRDT - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "../topics/IDLGraph.h" - -using namespace std; - -template< bool b > -struct join_selector { - template< typename T > - static T join( const T& l, const T& r ) - { - T res; - res=l; - res.join(r); - return res; - } -}; - -template<> -struct join_selector { - template - static T join(const T &l, const T &r) { - T res; - res = max(l, r); - return res; - } -}; - - -// Join with C++ traits -template -// Join two objects, deriving a new one -T join(const T &l, const T &r) // assuming copy constructor -{ - return join_selector::value>::join(l, r); -} - -template -// Join two pairs of objects -pair join(const pair &l, const pair &r) { - pair res; - res.first = join(r.first, l.first); - res.second = join(r.second, l.second); - return res; -} - -template -// Join lexicographic of two pairs of objects -pair lexjoin(const pair &l, const pair &r) { - pair res; - if (r == l) return res = r; - if (l.first > r.first) return res = l; - if (r.first > l.first) return res = r; - // Left is equal, so join right - if (r.first == l.first) { - res.first = r.first; - res.second = join(r.second, l.second); - return res; - } - // Otherwise A is not a total order so keep res empty to signal error - return res; -} - -template -// Output a pair -ostream &operator<<(ostream &output, const pair &o) { - try { - output << "(" << o.first << "," << o.second << ")"; - } catch (const std::exception &ex) { - cout << "Error" << endl; - } - return output; -} - -template -// Output a set -ostream &operator<<(ostream &output, const set &o) { - output << "( "; - for (const auto &e : o) output << e << " "; - output << ")"; - return output; -} - -template -// get a point among two points -vector among(const vector &l, const vector &r, int j = 0) { - // Overall strategy is to first try wide advances to the right, - // as compact as possible. If that fails, go with fine grain (less compact) - // advances until eventually succeed. - assert(l < r); - vector res; - // adjust res as forwardly compact as possible - for (int is = 0; is <= l.size(); is++) { - res.assign(l.begin(), l.begin() + is); // get initial segment - if (is < l.size()) // if partial segment, try appending one - { - res.push_back(true); - if (res >= l && res < r) break; // see if we are there - } - } - assert(res >= l && res < r); - if (res > l) return res; - //vector res=l; - // forward finer and finer - for (int i = 0; i < j; i++) { - res.push_back(false); - } - res.push_back(true); - - while (res >= r) { - res.back() = false; - for (int i = 0; i < j; i++) { - res.push_back(false); - } - res.push_back(true); - } - assert(res > l && res < r); - return res; -} - -template -// Output a vector -ostream &operator<<(ostream &output, const vector &o) { - output << "["; - for (const auto &e : o) output << e; - output << "]"; - return output; -} - -// Autonomous causal context, for context sharing in maps -template -class dotcontext { -public: - map cc; // Compact causal context - set > dc; // Dot cloud - - dotcontext &operator=(const dotcontext &o) { - if (&o == this) return *this; - cc = o.cc; - dc = o.dc; - return *this; - } - - friend ostream &operator<<(ostream &output, const dotcontext &o) { - output << "Context:"; - output << " CC ( "; - for (const auto &ki : o.cc) - output << ki.first << ":" << ki.second << " "; - output << ")"; - output << " DC ( "; - for (const auto &ki : o.dc) - output << ki.first << ":" << ki.second << " "; - output << ")"; - return output; - } - - pair, set>> getCcDc() { - return (pair, set>>(cc, dc)); - }; - - - pair>, list>> get() { - list> dataCC; - list> dataDC; - for (const auto &ki : cc) - dataCC.push_back(pair(ki.first, ki.second)); -// cout << " -- Contexto -- \n"<(ki.first, ki.second)); - } - - - return pair>, list>>(dataCC, dataDC);; - } - - list> get(K uid) { - list> l = list>(); - pair p = pair(0, 0); - for (const auto &kcc : cc) { - p.first = 0; - p.second = 0; - if (kcc.first == uid) { - p.first = kcc.second; - for (const auto &kdc : dc) - if (kdc.first == uid) { - p.second = kdc.second; - } - l.push_back(p); - } - } -// cout << "get UID:"<< uid << " "<< p.first << " "<< p.second << endl; - return l; - } - - void setContext(map &cc_, set > &dc_) { - cc = cc_; - dc = dc_; - } - - void setContext(map &&cc_, set > &&dc_) { - cc = std::move(cc_); - dc = std::move(dc_); - } - - bool dotin(const pair &d) const { - const auto itm = cc.find(d.first); - if (itm != cc.end() && d.second <= itm->second) return true; - if (dc.count(d) != 0) return true; - return false; - } - - //TODO: debug this - void compact() { - // Compact DC to CC if possible - //typename map::iterator mit; - //typename set >::iterator sit; - bool flag; // may need to compact several times if ordering not best - do { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << endl; - flag = false; - for (auto sit = dc.begin(); sit != dc.end();) { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ <<*(sit)<<" "<first<<" "<second<first); - if (mit == cc.end()) // No CC entry - if (sit->second == 1) // Can compact - { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << " " << *(sit)<< endl; - cc.insert(*sit); - dc.erase(sit++); - flag = true; - } else ++sit; - else // there is a CC entry already - if (sit->second == cc.at(sit->first) + 1) // Contiguous, can compact - { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << " " << endl; - cc.at(sit->first)++; - dc.erase(sit++); - flag = true; - } else if (sit->second <= cc.at(sit->first)) // dominated, so prune - { - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << " " << endl; - //cout << *(sit)<<" :"<<__LINE__ << " " << endl; - //cout << dc <<" :"<<__LINE__ << " " << endl; - //if (dc.find(*sit) != dc.end()) - dc.erase(sit++); - - // no extra compaction oportunities so flag untouched - } else ++sit; - } - } while (flag == true); - } - - pair makedot(const K &id) { - // On a valid dot generator, all dots should be compact on the used id - // Making the new dot, updates the dot generator and returns the dot - // pair::iterator,bool> ret; - auto p = pair(id, 1); - auto kib = cc.insert(p); - if (kib.second == false) // already there, so update it - (kib.first->second) += 1; - //return dot; - return pair(*kib.first); - } - - void insertdot(const pair &d, bool compactnow = true) { - // Set - dc.insert(d); - if (compactnow) compact(); - } - - - void join(const dotcontext &o) { - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << endl; - if (this == &o) return; // Join is idempotent, but just dont do it. - // CC - //typename map::iterator mit; - //typename map::const_iterator mito; - auto mit = cc.begin(); - auto mito = o.cc.begin(); - do { - if (mit != cc.end() && (mito == o.cc.end() || mit->first < mito->first)) { - // cout << "cc one\n"; - // entry only at here - ++mit; - } else if (mito != o.cc.end() && (mit == cc.end() || mito->first < mit->first)) { - // cout << "cc two\n"; - // entry only at other - cc.insert(*mito); - ++mito; - } else if (mit != cc.end() && mito != o.cc.end()) { - // cout << "cc three\n"; - // in both - cc.at(mit->first) = max(mit->second, mito->second); - ++mit; - ++mito; - } - } while (mit != cc.end() || mito != o.cc.end()); - - // DC - // Set - for (const auto &e : o.dc) - insertdot(e, false); - - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << " " << o.dc << endl; - compact(); - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << " " << o.dc << endl; - - } - - bool operator==(const dotcontext &rhs) const { - return cc == rhs.cc && - dc == rhs.dc; - } - - bool operator!=(const dotcontext &rhs) const { - return !(rhs == *this); - } - - bool operator<(const dotcontext &rhs) const { - if (cc < rhs.cc) - return true; - if (rhs.cc < cc) - return false; - return dc < rhs.dc; - } - - bool operator>(const dotcontext &rhs) const { - return rhs < *this; - } - - bool operator<=(const dotcontext &rhs) const { - return !(rhs < *this); - } - - bool operator>=(const dotcontext &rhs) const { - return !(*this < rhs); - } -}; - -template -class dotkernel { -public: - - map, T> ds; // Map of dots to vals - - //dotcontext cbase; - dotcontext c; - - // if no causal context supplied, used base one - dotkernel() {} - - // if supplied, use a shared causal context - dotkernel(dotcontext &jointc) : c(jointc) {} -// dotkernel(const dotkernel &adk) : c(adk.c), ds(adk.ds) {} - - - void set(map, T> &ds_) { ds = ds_; } - void set(map, T> &&ds_) { ds = std::move(ds_); } - - dotkernel &operator=(const dotkernel &adk) { - if (&adk == this) return *this; - if (&c != &adk.c) c = adk.c; - ds = adk.ds; - return *this; - } - - friend ostream &operator<<(ostream &output, const dotkernel &o) { - output << "Kernel: DS ( "; - for (const auto &dv : o.ds) { - output << dv.first.first << ":" << dv.first.second << - "->" << dv.second << " "; - } - output << ") "; - - output << o.c; - return output; - } - - void join(const dotkernel &o) { - - - if (this == &o) return; // Join is idempotent, but just dont do it. - - // DS - // will iterate over the two sorted sets to compute join - //typename map,T>::iterator it; - //typename map,T>::const_iterator ito; - auto it = ds.begin(); - auto ito = o.ds.begin(); - do { - if (it != ds.end() && (ito == o.ds.end() || it->first < ito->first)) { - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << endl; - // dot only at this - if (o.c.dotin(it->first)) { // other knows dot, must delete here - ds.erase(it++); - //cout <<__FUNCTION__<<":"<<__LINE__ << endl; - } else // keep it - ++it; - } else if (ito != o.ds.end() && (it == ds.end() || ito->first < it->first)) { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << endl; - // dot only at other - if (!c.dotin(ito->first)) { // If I dont know, import - ds.insert(*ito); - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << endl; - } - ++ito; - } else if (it != ds.end() && ito != o.ds.end()) { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << " " << o << endl; - // dot in both - ++it; - ++ito; - } - } while (it != ds.end() || ito != o.ds.end()); - // CC - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ <<" " < &o) { - - - if (this == &o) return; // Join is idempotent, but just dont do it. - - // DS - // will iterate over the two sorted sets to compute join - //typename map,T>::iterator it; - //typename map,T>::const_iterator ito; - auto it = ds.begin(); - auto ito = o.ds.begin(); - do { - if (it != ds.end() && (ito == o.ds.end() || it->first < ito->first)) { - //cout <<__PRETTY_//cout <<__PRETTY<<":"<<__LINE__ << endl; - // dot only at this - if (o.c.dotin(it->first)) { // other knows dot, must delete here - ds.erase(it++); - //cout <<__FUNCTION__<<":"<<__LINE__ << endl; - } else // keep it - ++it; - } else if (ito != o.ds.end() && (it == ds.end() || ito->first < it->first)) { - //cout <<"ITO: "<<":"<< ito->first << endl; - //cout <<"IT: "<<":"<< it->first << endl; - //cout <<"C: "<<":"<< c << endl; - - // dot only at other - if (!c.dotin(ito->first) || ds.empty()) { // If I dont know, import - ds.insert(*ito); - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << endl; - } - ++ito; - } else if (it != ds.end() && ito != o.ds.end()) { - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ << " " << o << endl; - // dot in both - - //if constexpr(is_same::value) { - //cout << "CONFLICTO " << endl; - //replace in case of conflict if the agent id has a lower value - if (it->second.agent_id() > ito->second.agent_id() && *it != *ito) { - ds.erase(it); - ds.insert(*ito); - cout << "CONFLICTO" << endl; - } - //} - ++it; - ++ito; - } - } while (it != ds.end() || ito != o.ds.end()); - // CC - //cout <<__PRETTY_FUNCTION__<<":"<<__LINE__ <<" " < &o) { - if (this == &o) return; // Join is idempotent, but just dont do it. - // DS - // will iterate over the two sorted sets to compute join - //typename map,T>::iterator it; - //typename map,T>::const_iterator ito; - auto it = ds.begin(); - auto ito = o.ds.begin(); - do { - if (it != ds.end() && (ito == o.ds.end() || it->first < ito->first)) { - // dot only at this - if (o.c.dotin(it->first)) // other knows dot, must delete here - ds.erase(it++); - else // keep it - ++it; - } else if (ito != o.ds.end() && (it == ds.end() || ito->first < it->first)) { - // dot only at other - if (!c.dotin(ito->first)) // If I dont know, import - ds.insert(*ito); - ++ito; - } else if (it != ds.end() && ito != o.ds.end()) { - // dot in both - // check it payloads are diferent - if (it->second != ito->second) { - // if payloads are not equal, they must be mergeable - // use the more general binary join - it->second = ::join(it->second, ito->second); - } - ++it; - ++ito; - } - } while (it != ds.end() || ito != o.ds.end()); - // CC - c.join(o.c); - } - - - dotkernel add(const K &id, const T &val) { - - - dotkernel res; - // get new dot - - - pair dot = c.makedot(id); - // add under new dot - ds.insert(pair, T>(dot, val)); - // make delta - res.ds.insert(pair, T>(dot, val)); - res.c.insertdot(dot); - return res; - } - - // Add that returns the added dot, instead of kernel delta - pair dotadd(const K &id, const T &val) { - // get new dot - pair dot = c.makedot(id); - // add under new dot - ds.insert(pair, T>(dot, val)); - return dot; - } - - - void clean() { - //typename map,T>::iterator dsit; - - //if (ds.empty()) return; - - map x; - for (auto dsit = ds.begin(); dsit != ds.end(); dsit++) { - if (x.find(dsit->first.first) != x.end()) // match - { - if (x[dsit->first.first] < dsit->first.second) { - x[dsit->first.first] = dsit->first.second; - } - } else { - x.insert(dsit->first); - } - } - ////cout <<__PRETTY_FUNCTION__ <<":"<<__LINE__<< " " << res << endl; - - for (auto dsit = ds.begin(); dsit != ds.end();) { - if (x[dsit->first.first] != dsit->first.second) - ds.erase(dsit++); - else { - ++dsit; - } - } - - //if (c.dc.rbegin() != c.dc.rend()) { - // c.cc.insert(*c.dc.rbegin()); - // c.dc.clear(); - //} - //TODO: comprobar esto - //c.insertdot(last); - //c.compact(); - - } - - - dotkernel rmv(const T &val) // remove all dots matching value - { - dotkernel res; - //typename map,T>::iterator dsit; - for (auto dsit = ds.begin(); dsit != ds.end();) { - if (dsit->second == val) // match - { - res.c.insertdot(dsit->first, false); // result knows removed dots - ds.erase(dsit++); - } else - ++dsit; - } - ////cout <<__PRETTY_FUNCTION__ <<":"<<__LINE__<< " " << res << endl; - res.c.compact(); // Maybe several dots there, so atempt compactation - return res; - } - - - dotkernel rmv(const pair &dot) // remove a dot - { - dotkernel res; - auto dsit = ds.find(dot); - if (dsit != ds.end()) // found it - { - res.c.insertdot(dsit->first, false); // result knows removed dots - ds.erase(dsit++); - } - ////cout <<__PRETTY_FUNCTION__ <<":"<<__LINE__<< " " << res << endl; - res.c.compact(); // Atempt compactation - return res; - } - - dotkernel rmv() // remove all dots - { - dotkernel res; - for (const auto &dv : ds) - res.c.insertdot(dv.first, false); - res.c.compact(); - ds.clear(); // Clear the payload, but remember context - return res; - } - - bool operator==(const dotkernel &rhs) const { - return ds == rhs.ds;// && - //cbase == rhs.cbase && - //c == rhs.c; - } - - bool operator!=(const dotkernel &rhs) const { - return !(rhs == *this); - } - - bool operator<(const dotkernel &rhs) const { - if (ds < rhs.ds) - return true; - return false; - } - - bool operator>(const dotkernel &rhs) const { - return rhs < *this; - } - - bool operator<=(const dotkernel &rhs) const { - return !(rhs < *this); - } - - bool operator>=(const dotkernel &rhs) const { - return !(*this < rhs); - } -}; - -template -class gcounter { -private: - map m; - K id; - -public: - gcounter() {} // Only for deltas and those should not be mutated - gcounter(K a) : id(a) {} // Mutable replicas need a unique id - - gcounter inc(V tosum = {1}) // argument is optional - { - gcounter res; - m[id] += tosum; - res.m[id] = m[id]; - return res; - } - - bool operator==(const gcounter &o) const { - return m == o.m; - } - - V local() // get local counter value // CBM make this const - { - V res = 0; - res += m[id]; - return res; - } - - V read() const // get counter value - { - V res = 0; - for (const auto &kv : m) // Fold+ on value list - res += kv.second; - return res; - } - - void join(const gcounter &o) { - for (const auto &okv : o.m) - m[okv.first] = max(okv.second, m[okv.first]); - } - - friend ostream &operator<<(ostream &output, const gcounter &o) { - output << "GCounter: ( "; - for (const auto &kv : o.m) - output << kv.first << "->" << kv.second << " "; - output << ")"; - return output; - } - -}; - -template -class pncounter { -private: - gcounter p, n; - -public: - pncounter() {} // Only for deltas and those should not be mutated - pncounter(K a) : p(a), n(a) {} // Mutable replicas need a unique id - - pncounter inc(V tosum = {1}) // Argument is optional - { - pncounter res; - res.p = p.inc(tosum); - return res; - } - - pncounter dec(V tosum = {1}) // Argument is optional - { - pncounter res; - res.n = n.inc(tosum); - return res; - } - - V local() // get local counter value - { - V res = p.local() - n.local(); - return res; - } - - V read() const // get counter value - { - V res = p.read() - n.read(); - return res; - } - - void join(const pncounter &o) { - p.join(o.p); - n.join(o.n); - } - - friend ostream &operator<<(ostream &output, const pncounter &o) { - output << "PNCounter:P:" << o.p << " PNCounter:N:" << o.n; - return output; - } - -}; - -template -class lexcounter { -private: - map > m; - K id; - -public: - lexcounter() {} // Only for deltas and those should not be mutated - lexcounter(K a) : id(a) {} // Mutable replicas need a unique id - - lexcounter inc(V tosum = 1) // Argument is optional - { - lexcounter res; - -// m[id].first+=1; // optional - m[id].second += tosum; - res.m[id] = m[id]; - - return res; - } - - lexcounter dec(V tosum = 1) // Argument is optional - { - lexcounter res; - - m[id].first += 1; // mandatory - m[id].second -= tosum; - res.m[id] = m[id]; - - return res; - } - - V read() const // get counter value - { - V res = 0; - for (const auto &kv : m) // Fold+ on value list - res += kv.second.second; - return res; - } - - void join(const lexcounter &o) { - for (const auto &okv : o.m) - m[okv.first] = lexjoin(okv.second, m[okv.first]); - } - - friend ostream &operator<<(ostream &output, const lexcounter &o) { - output << "LexCounter: ( "; - for (const auto &kv : o.m) - output << kv.first << "->" << kv.second << " "; - output << ")"; - return output; - } - -}; - -template -class ccounter // Causal counter, variation of Riak_dt_emcntr and lexcounter -{ -private: - // To re-use the kernel there is an artificial need for dot-tagged bool payload - dotkernel dk; // Dot kernel - K id; - -public: - ccounter() {} // Only for deltas and those should not be mutated - ccounter(K k) : id(k) {} // Mutable replicas need a unique id - ccounter(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - dotcontext &context() { - return dk.c; - } - - friend ostream &operator<<(ostream &output, const ccounter &o) { - output << "CausalCounter:" << o.dk; - return output; - } - - ccounter inc(const V &val = 1) { - ccounter r; - set > dots; // dots to remove, should be only 1 - V base = {}; // typically 0 - for (const auto &dsit : dk.ds) { - if (dsit.first.first == id) // there should be a single one such - { - base = max(base, dsit.second); - dots.insert(dsit.first); - } - } - for (const auto &dot : dots) - r.dk.join(dk.rmv(dot)); - r.dk.join(dk.add(id, base + val)); - return r; - } - - ccounter dec(const V &val = 1) { - ccounter r; - set > dots; // dots to remove, should be only 1 - V base = {}; // typically 0 - for (const auto &dsit : dk.ds) { - if (dsit.first.first == id) // there should be a single one such - { - base = max(base, dsit.second); - dots.insert(dsit.first); - } - } - for (const auto &dot : dots) - r.dk.join(dk.rmv(dot)); - r.dk.join(dk.add(id, base - val)); - return r; - } - - ccounter reset() // Other nodes might however upgrade their counts - { - ccounter r; - r.dk = dk.rmv(); - return r; - } - - V read() { - V v = {}; // Usually 0 - for (const auto &dse : dk.ds) - v += dse.second; - return v; - } - - void join(ccounter o) { - dk.join(o.dk); - } - -}; - - -template -class gset { -private: - set s; - -public: - - gset() {} -// gset(string id, dotcontext &jointdc) {} - - // For map compliance reply with an empty context -// dotcontext context() -// { -// return dotcontext(); -// } - - set read() const { - return s; - } - - bool operator==(const gset &o) const { - return s == o.s; - } - - bool in(const T &val) { - return s.count(val); - } - - friend ostream &operator<<(ostream &output, const gset &o) { - output << "GSet: " << o.s; - return output; - } - - gset add(const T &val) { - gset res; - s.insert(val); - res.s.insert(val); - return res; - } - - void join(const gset &o) { - s.insert(o.s.begin(), o.s.end()); - } - -}; - - -template // Map embedable datatype -class twopset { -private: - set s; - set t; // removed elements are added to t and removed from s - -public: - - twopset() {} - - twopset(string id, dotcontext &jointdc) {} - - // For map compliance reply with an empty context - dotcontext context() { - return dotcontext(); - } - - set read() { - return s; - } - - - set readRemoves() { - return t; - } - - - bool operator==(const twopset &o) const { - return s == o.s && t == o.t; - } - - bool in(const T &val) { - return s.count(val); - } - - friend ostream &operator<<(ostream &output, const twopset &o) { - output << "2PSet: S" << o.s << " T " << o.t; - return output; - } - - twopset add(const T &val) { - twopset res; - if (t.count(val) == 0) // only add if not in tombstone set - { - s.insert(val); - res.s.insert(val); - } - return res; - } - - twopset rmv(const T &val) { - twopset res; - s.erase(val); - t.insert(val); // add to tombstones - res.t.insert(val); - return res; - } - - twopset reset() { - twopset res; - for (auto const &val : s) { - t.insert(val); - res.t.insert(val); - } - s.clear(); - return res; - } - - void join(const twopset &o) { - for (const auto &ot : o.t) // see other tombstones - { - t.insert(ot); // insert them locally - if (s.count(ot) == 1) // remove val if present - s.erase(ot); - } - for (const auto &os : o.s) // add other vals, if not tombstone - { - if (t.count(os) == 0) s.insert(os); - } - } -}; - - -template // Map embedable datatype -class aworset // Add-Wins Observed-Remove Set -{ - K id; - dotkernel dk; // Dot kernel - -public: - aworset() {} // Only for deltas and those should not be mutated - aworset(K k) : id(k) {} // Mutable replicas need a unique id - aworset(K k, dotcontext &jointc) : id(k), dk(jointc) {} -// - - - - dotcontext &context() { - return dk.c; - } - - void setContext(dotcontext &cbase) { - dk.c = cbase; - } - - dotkernel &dots() { - return dk; - } - - K getId() { return id; } - - friend ostream &operator<<(ostream &output, const aworset &o) { - output << "AWORSet:" << o.dk; - return output; - } - - - set read() { - set < E > res; - for (const auto &dv : dk.ds) { - res.insert(dv.second); - - } - return res; - } - - list readAsList() { - list res; - for (const auto &dv : dk.ds) - res.push_back(dv.second); - return res; - } - - list> readAsListWithId() { - list> res; - for (const auto &dv : dk.ds) { - pair p = pair(dv.first.second, dv.second); - res.push_back(p); - } - return res; - } - - - bool in(const E &val) { - typename map, E>::iterator dsit; - for (dsit = dk.ds.begin(); dsit != dk.ds.end(); ++dsit) { - if (dsit->second == val) - return true; - } - return false; - } - - - //Nosotros guardamos nodos con la misma clave siempre en un aworset. Se puede usar getNodesSimple. - pair > getNodes(const K &uid) { -// cout << "get" << uid << endl; - pair > d; - typename map, E>::iterator dsit; - for (dsit = dk.ds.begin(); dsit != dk.ds.end(); ++dsit) { - if (dsit->first.first == uid) { - list> lp = dk.c.get(uid); - d = pair>(dsit->second, lp.back()); - - } - } - return d; - } - - pair > getNodesSimple(const K &uid) { - pair > d; - if (dk.ds.empty()) { return d; } - auto x = dk.ds.rbegin(); - list> lp = dk.c.get(uid); - d = pair>(x->second, lp.back()); - return d; - } - - - aworset add(const E &val) { - aworset r; - r.dk = dk.rmv(val); // optimization that first deletes val - r.dk.join(dk.add(id, val)); - return r; - } - - - aworset add(const E &val, const K &uid) { - aworset r(uid); - r.dk = dk.rmv(val); // optimization that first deletes val - r.dk.join(dk.add(uid, val)); - dk.clean(); - return r; - } - - - aworset rmv(const E &val) { - aworset r; - r.dk = dk.rmv(val); - return r; - } - - aworset reset() { - aworset r; - r.dk = dk.rmv(); - return r; - } - - void join(aworset o) { - ////cout <<__PRETTY_FUNCTION__ <<" o: "<< o << endl; - dk.join(o.dk); - // Further optimization can be done by keeping for val x and id A - // only the highest dot from A supporting x. - dk.clean(); - - } - - //Replace on conflict - void join_replace(aworset o) { - ////cout <<__PRETTY_FUNCTION__ <<" o: "<< o << endl; - dk.join_replace_conflict(o.dk); - // Further optimization can be done by keeping for val x and id A - // only the highest dot from A supporting x. - dk.clean(); - } -}; - -template // Map embedable datatype -class rworset // Remove-Wins Observed-Remove Set -{ -private: - dotkernel, K> dk; // Dot kernel - K id; - -public: - rworset() {} // Only for deltas and those should not be mutated - rworset(K k) : id(k) {} // Mutable replicas need a unique id - rworset(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - dotcontext &context() { - return dk.c; - } - - - friend ostream &operator<<(ostream &output, const rworset &o) { - output << "RWORSet:" << o.dk; - return output; - } - - set read() { - set < E > res; - map elems; - typename map, pair >::iterator dsit; - pair::iterator, bool> ret; - for (dsit = dk.ds.begin(); dsit != dk.ds.end(); ++dsit) { - ret = elems.insert(pair(dsit->second)); - if (ret.second == false) // val already exists - { - elems.at(ret.first->first) &= dsit->second.second; // Fold by && - } - } - typename map::iterator mit; - for (mit = elems.begin(); mit != elems.end(); ++mit) { - if (mit->second == true) res.insert(mit->first); - } - return res; - } - - bool in(const E &val) // Could - { - // Code could be slightly faster if re-using only part of read code - set < E > s = read(); - if (s.find(val) != s.end()) return true; - return false; - } - - - rworset add(const E &val) { - rworset r; - r.dk = dk.rmv(pair(val, true)); // Remove any observed add token - r.dk.join(dk.rmv(pair(val, false))); // Remove any observed remove token - r.dk.join(dk.add(id, pair(val, true))); - return r; - } - - rworset rmv(const E &val) { - rworset r; - r.dk = dk.rmv(pair(val, true)); // Remove any observed add token - r.dk.join(dk.rmv(pair(val, false))); // Remove any observed remove token - r.dk.join(dk.add(id, pair(val, false))); - return r; - } - - rworset reset() { - rworset r; - r.dk = dk.rmv(); - return r; - } - - - void join(rworset o) { - dk.join(o.dk); - } -}; - - -template -class mvreg // Multi-value register, Optimized -{ -private: - K id; - -public: - dotkernel dk; // Dot kernel - - mvreg() { - if constexpr(std::is_same::value) { id = 0; }; - } // Only for deltas and those should not be mutated - mvreg(K k) : id(k) {} // Mutable replicas need a unique id - mvreg(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - dotcontext &context() { - return dk.c; - } - - void setContext(dotcontext &cbase) { - dk.c = cbase; - } - - friend ostream &operator<<(ostream &output, const mvreg &o) { - output << "MVReg:" << o.dk; - return output; - } - - mvreg write(const V &val) { - mvreg r, a; - //if (!dk.cbase.cc.empty() && dk.c.cc.empty()) dk.c = dk.cbase; - r.dk = dk.rmv(); - a.dk = dk.add(id, val); - r.join(a); - return r; - - } - - bool empty() { - return dk.ds.empty(); - } - - set read() { - set < V > s; - for (const auto &dse : dk.ds) - s.insert(dse.second); - return s; - } - - set read() const { - set < V > s; - for (const auto &dse : dk.ds) - s.insert(dse.second); - return s; - } - - V &read_reg() { - return dk.ds.begin()->second; - } - - - mvreg reset() { - mvreg r; - r.dk = dk.rmv(); - return r; - } - - mvreg resolve() { - mvreg r, v; - set < V > s; // collect all values that are not maximals - for (const auto &dsa : dk.ds) // Naif quadratic comparison - for (const auto &dsb : dk.ds) - if (dsa.second != dsb.second && - ::join(dsa.second, dsb.second) == dsb.second) // < based on join - // if (dsa.second < dsb.second) // values must implement operator< - s.insert(dsa.second); - // remove all non maximals and register deltas for those removals - for (const auto &val : s) { - v.dk = dk.rmv(val); - r.join(v); - } - return r; - } - - // Remove all but the last dotkernel element - void rsv() { - if (dk.ds.empty()) return; - auto b = dk.ds.begin(); - auto e = --dk.ds.end(); - while (b != e) { - b = dk.ds.erase(b); - } - } - - void join(mvreg o) { - dk.join_replace_conflict(o.dk); - //rsv(); - //dk.clean(); - } - - bool operator==(const mvreg &rhs) const { - return id == rhs.id && - dk == rhs.dk; - } - - bool operator!=(const mvreg &rhs) const { - return !(rhs == *this); - } - - bool operator<(const mvreg &rhs) const { - if (id < rhs.id) - return true; - if (rhs.id < id) - return false; - return dk < rhs.dk; - } - - bool operator>(const mvreg &rhs) const { - return rhs < *this; - } - - bool operator<=(const mvreg &rhs) const { - return !(rhs < *this); - } - - bool operator>=(const mvreg &rhs) const { - return !(*this < rhs); - } -}; - - -template -class ewflag // Enable-Wins Flag -{ -private: - // To re-use the kernel there is an artificial need for dot-tagged bool payload - dotkernel dk; // Dot kernel - K id; - -public: - ewflag() {} // Only for deltas and those should not be mutated - ewflag(K k) : id(k) {} // Mutable replicas need a unique id - ewflag(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - dotcontext &context() { - return dk.c; - } - - friend ostream &operator<<(ostream &output, const ewflag &o) { - output << "EWFlag:" << o.dk; - return output; - } - - bool read() { - typename map, bool>::iterator dsit; - if (dk.ds.begin() == dk.ds.end()) - // No active dots - return false; - else - // Some dots - return true; - } - - ewflag enable() { - ewflag r; - r.dk = dk.rmv(true); // optimization that first deletes active dots - r.dk.join(dk.add(id, true)); - return r; - } - - ewflag disable() { - ewflag r; - r.dk = dk.rmv(true); - return r; - } - - ewflag reset() { - ewflag r; - r.dk = dk.rmv(); - return r; - } - - void join(ewflag o) { - dk.join(o.dk); - } -}; - -template -class dwflag // Disable-Wins Flag -{ -private: - // To re-use the kernel there is an artificial need for dot-tagged bool payload - dotkernel dk; // Dot kernel - K id; - -public: - dwflag() {} // Only for deltas and those should not be mutated - dwflag(K k) : id(k) {} // Mutable replicas need a unique id - dwflag(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - dotcontext &context() { - return dk.c; - } - - friend ostream &operator<<(ostream &output, const dwflag &o) { - output << "DWFlag:" << o.dk; - return output; - } - - bool read() { - typename map, bool>::iterator dsit; - if (dk.ds.begin() == dk.ds.end()) - // No active dots - return true; - else - // Some dots - return false; - } - - dwflag disable() { - dwflag r; - r.dk = dk.rmv(false); // optimization that first deletes active dots - r.dk.join(dk.add(id, false)); - return r; - } - - dwflag enable() { - dwflag r; - r.dk = dk.rmv(false); - return r; - } - - dwflag reset() { - dwflag r; - r.dk = dk.rmv(); - return r; - } - - void join(dwflag o) { - dk.join(o.dk); - } -}; - -// U is timestamp, T is payload -template -class rwlwwset // remove wins bias for identical timestamps -{ -private: - map > s; - - rwlwwset addrmv(const U &ts, const T &val, bool b) { - rwlwwset res; - pair a(ts, b); - res.s.insert(pair >(val, a)); - pair >::iterator, bool> ret; - ret = s.insert(pair >(val, a)); - if (ret.second == false) // some value there - { - s.at(ret.first->first) = lexjoin(ret.first->second, a); - } - return res; - } - -public: - - friend ostream &operator<<(ostream &output, const rwlwwset &o) { - output << "RW LWWSet: ( "; - for (typename map >::const_iterator it = o.s.begin(); it != o.s.end(); ++it) { - if (it->second.second == false) - output << it->first << " "; - } - output << ")" << endl; - return output; - } - - rwlwwset add(const U &ts, const T &val) { - return addrmv(ts, val, false); - } - - rwlwwset rmv(const U &ts, const T &val) { - return addrmv(ts, val, true); - } - - - bool in(const T &val) { - typename map >::const_iterator it = s.find(val); - if (it == s.end() || it->second.second == true) - return false; - else - return true; - } - - void join(const rwlwwset &o) { - if (this == &o) return; // Join is idempotent, but just dont do it. - // will iterate over the two sorted sets to compute join - typename map >::iterator it; - typename map >::const_iterator ito; - it = s.begin(); - ito = o.s.begin(); - do { - if (it != s.end() && (ito == o.s.end() || it->first < ito->first)) { - // entry only at this - // keep it - ++it; - } else if (ito != o.s.end() && (it == s.end() || ito->first < it->first)) { - // entry only at other - // import it - s.insert(*ito); - ++ito; - } else if (it != s.end() && ito != o.s.end()) { - // in both - // merge values by lex operator - s.at(it->first) = lexjoin(it->second, ito->second); - ++it; - ++ito; - } - } while (it != s.end() || ito != o.s.end()); - } - - -}; - -template -class lwwreg // U must be comparable -{ -private: - pair r; - -public: - - friend ostream &operator<<(ostream &output, const lwwreg &o) { - output << "LWWReg: " << o.r; - return output; - } - - void join(const lwwreg &o) { - if (o.r.first > r.first) { - r = o.r; - } - } - - lwwreg write(const U &ts, const T &val) { - lwwreg res; - res.r.first = ts; - res.r.second = val; - join(res); // Will only update if ts is greater - return res; - } - - T read() { - return r.second; - } -}; - -template -class ormap { - K id; - map m; - dotcontext cbase; - dotcontext &c; - -public: - - // if no causal context supplied, use base one - ormap() : c(cbase) {} - - ormap(K i) : id(i), c(cbase) {} - - // if supplied, use a shared causal context - ormap(K i, dotcontext &jointc) : id(i), /*c(jointc)*/ c(cbase) {} - -// ormap( const ormap& o ) : id(o.id), m(o.m), c(o.c) {} - - ormap &operator=(const ormap &o) { - if (&o == this) return *this; - if (&c != &o.c) c = o.c; - m = o.m; - id = o.id; - return *this; - } - - /*ormap & operator=(ormap && o) - { - if (&o == this) return *this; - if (&c != &o.c) c=std::move(o.c); - m= std::move(o.m); - id=o.id; - return *this; - }*/ - - - bool operator==(const ormap &o) const { - if (&o == this) return true; - if (m == o.m) return true; - - return false; - } - - bool operator!=(const ormap &o) const { - return !operator==(o); - } - - dotcontext &context() const { - return c; - } - - //Devuelve una referencia en lugar del mapa - std::map &getMapRef() { - return m; - } - - const std::map &getMapRef() const { - return m; - } - - std::map getMap() const { - return m; - } - - - K getId() const { - return id; - } - - pair, dotcontext>> getFullOrMap() { - return pair, dotcontext>>(id, getOrMap()); - } - - pair, dotcontext> getOrMap() { - return pair, dotcontext>(m, c); - } - - bool in(const N &n) const { - return (m.find(n) != m.end()); - } - - - friend ostream &operator<<(ostream &output, const ormap &o) { - output << "Map:" << o.c << "\n"; - for (const auto &kv : o.m) - cout << kv.first << "->" << kv.second << "\n"; - - return output; - } - - // Need to find a way to collect deltas for this interface - V &operator[](const N &n) { - auto i = m.find(n); - if (i == m.end()) // 1st key access - { -// std::cout << "Created" << std::endl; - auto ins = m.insert(i, pair(n, V(id, c))); - return ins->second; - - } else { - return i->second; - } - } - - ormap erase(const N &n) { - ormap r; - if (m.count(n) != 0) { - // need to collect erased dots, and list then in r context - V v; - v = m[n].reset(); - r.c = v.context(); - // now erase - m.erase(n); - - } - return r; - } - - ormap reset() { - ormap r; - if (!m.empty()) { - // need to collect erased dots, and list then in r context - for (auto &kv : m) { - V v; - v = kv.second.reset(); - r.c.join(v.context()); - } - m.clear(); - } - return r; - } - - - void join(const ormap &o) { - const dotcontext ic = c; // need access to an immutable context - - // join all keys - auto mit = m.begin(); - auto mito = o.m.begin(); - do { - // ---- debug - /* - cout << "key left "; - if (mit != m.end()) - cout << mit->first; - else - cout << "[empty]"; - cout << ", key rigth "; - if (mito != o.m.end()) - cout << mito->first; - else - cout << "[empty]"; - cout << endl; - */ - if (mit != m.end() && (mito == o.m.end() || mit->first < mito->first)) { - //cout << "entry left\n"; - // entry only at here - - // creaty and empty payload with the other context, since it might - // obsolete some local entries. - V empty(id, o.context()); - mit->second.join(empty); - c = ic; - - ++mit; - } else if (mito != o.m.end() && (mit == m.end() || mito->first < mit->first)) { - // cout << "entry right\n"; - // entry only at other - - (*this)[mito->first].join(mito->second); - c = ic; - - - ++mito; - } else if (mit != m.end() && mito != o.m.end()) { - // cout << "entry both\n"; - // in both - (*this)[mito->first].join(mito->second); - c = ic; - - ++mit; - ++mito; - } - } while (mit != m.end() || mito != o.m.end()); - c.join(o.c); - - } - - -}; - -// A bag is similar to an RWSet, but allows for CRDT payloads -template -class bag { -private: - dotkernel dk; // Dot kernel - K id; - -public: - - bag() {} // Only for deltas and those should not be mutated - bag(K k) : id(k) {} // Mutable replicas need a unique id - bag(K k, dotcontext &jointc) : id(k), dk(jointc) {} - - bag &operator=(const bag &o) { - if (&o == this) return *this; - if (&dk != &o.dk) dk = o.dk; - id = o.id; - return *this; - } - - - dotcontext &context() { - return dk.c; - } - - void insert(pair, V> t) { - dk.ds.insert(pair, V>(t)); - dk.c.insertdot(t.first); - } - - friend ostream &operator<<(ostream &output, const bag &o) { - output << "Bag:" << o.dk; - return output; - } - - typename map, V>::iterator begin() { - return dk.ds.begin(); - } - - typename map, V>::iterator end() { - return dk.ds.end(); - } - - pair mydot() { - auto me = dk.ds.end(); - for (auto it = dk.ds.begin(); it != dk.ds.end(); ++it) { - if (it->first.first == id) // a candidate - { - if (me == dk.ds.end()) // pick at least one valid - me = it; - else // need to switch if more recent - { - if (it->first.second > me->first.second) - me = it; - } - } - } - if (me != dk.ds.end()) - return me->first; - else { - fresh(); - return mydot(); // After a fresh it must be found - } - } - - V &mydata() { - auto me = dk.ds.end(); - for (auto it = dk.ds.begin(); it != dk.ds.end(); ++it) { - if (it->first.first == id) // a candidate - { - if (me == dk.ds.end()) // pick at least one valid - me = it; - else // need to switch if more recent - { - if (it->first.second > me->first.second) - me = it; - } - } - } - if (me != dk.ds.end()) - return me->second; - else { - fresh(); - return mydata(); // After a fresh it must be found - } - } - - // To protect from concurrent removes, create fresh dot for self - void fresh() { - dk.add(id, V()); - } - - bag reset() { - bag r; - r.dk = dk.rmv(); - return r; - } - - // Using the deep join will try to join different payloads under same dot - void join(const bag &o) { - dk.deepjoin(o.dk); - } -}; - -// Inspired by designs from Carl Lerche and Paulo S. Almeida -template -class rwcounter // Reset Wins Counter -{ -private: - bag, K> b; // Bag of pairs - K id; - -public: - rwcounter() {} // Only for deltas and those should not be mutated - rwcounter(K k) : id(k), b(k) {} // Mutable replicas need a unique id - rwcounter(K k, dotcontext &jointc) : id(k), b(k, jointc) {} - - rwcounter &operator=(const rwcounter &o) { - if (&o == this) return *this; - if (&b != &o.b) b = o.b; - id = o.id; - return *this; - } - - dotcontext &context() { - return b.context(); - } - - friend ostream &operator<<(ostream &output, const rwcounter &o) { - output << "ResetWinsCounter:" << o.b; - return output; - } - - rwcounter inc(const V &val = 1) { - rwcounter r; - b.mydata().first += val; - r.b.insert(pair, pair>(b.mydot(), b.mydata())); - return r; - } - - rwcounter dec(const V &val = 1) { - rwcounter r; - b.mydata().second += val; - r.b.insert(pair, pair>(b.mydot(), b.mydata())); - return r; - } - - rwcounter reset() { - rwcounter r; - r.b = b.reset(); - return r; - } - - void fresh() { - b.fresh(); - } - - V read() { - pair ac; - for (const auto &dv : b) { - ac.first += dv.second.first; - ac.second += dv.second.second; - } - return ac.first - ac.second; - } - - void join(const rwcounter &o) { - b.join(o.b); - } - -}; - -template -class gmap { - -public: - // later make m private by adding a begin() for iterators - map m; - - friend ostream &operator<<(ostream &output, const gmap &o) { - output << "GMap:" << endl; - for (const auto &kv : o.m) - cout << kv.first << "->" << kv.second << endl; - return output; - } - - // Need to find a better way to collect deltas for this interface - V &operator[](const N &n) { - auto i = m.find(n); - if (i == m.end()) // 1st key access - { - auto ins = m.insert(i, pair(n, V())); - return ins->second; - - } else { - return i->second; - } - } - - void join(const gmap &o) { - // join all keys - auto mit = m.begin(); - auto mito = o.m.begin(); - do { - if (mit != m.end() && (mito == o.m.end() || mit->first < mito->first)) { - //cout << "entry left\n"; - // entry only at here - - ++mit; - } else if (mito != o.m.end() && (mit == m.end() || mito->first < mit->first)) { - // cout << "entry right\n"; - // entry only at other - - (*this)[mito->first] = mito->second; - - ++mito; - } else if (mit != m.end() && mito != o.m.end()) { - // cout << "entry both\n"; - // in both - (*this)[mito->first] = ::join((*this)[mito->first], mito->second); - - ++mit; - ++mito; - } - } while (mit != m.end() || mito != o.m.end()); - - } - -}; - - -template -class bcounter { -private: - pncounter c; - gmap, int> m; - K id; - -public: - - bcounter() {} // Only for deltas and those should not be mutated - bcounter(K a) : id(a), c(a) {} // Mutable replicas need a unique id - - bcounter inc(V tosum = {1}) // Argument is optional - { - bcounter res; - res.c = c.inc(tosum); - return res; - } - - bcounter dec(V todec = {1}) // Argument is optional - { - bcounter res; - if (todec <= local()) // Check local capacity - res.c = c.dec(todec); - return res; - } - - bcounter mv(V q, K to) // Quantity V to node id K - { - bcounter res; - if (q <= local()) // Check local capacity - { - m[pair(id, to)] += q; - res.m[pair(id, to)] = m[pair(id, to)]; - } - return res; - } - - V read() // get global counter value - { - V res = c.read(); - return res; - } - - V local() // get local counter available value - { - V res = c.local(); - // Sum incoming flows - for (const auto &kv : m.m) - if (kv.first.second == id) res += kv.second; - // Subtract outgoing flows - for (const auto &kv : m.m) - if (kv.first.first == id) res -= kv.second; - return res; - } - - void join(const bcounter &o) { - c.join(o.c); - m.join(o.m); - } - - friend ostream &operator<<(ostream &output, const bcounter &o) { - output << "BCounter:C:" << o.c << "BCounter:M:" << o.m; - return output; - } - -}; - -template -class orseq { -private: - - // List elements are: (position,dot,payload) - list, pair, T>> l; - I id; - - dotcontext cbase; - dotcontext &c; - -public: - - // if no causal context supplied, used base one - orseq() : c(cbase) {} // Only for deltas and those should not be mutated - orseq(I i) : id(i), c(cbase) {} - - // if supplied, use a shared causal context - orseq(I i, dotcontext &jointc) : id(i), c(jointc) {} - - orseq &operator=(const orseq &aos) { - if (&aos == this) return *this; - if (&c != &aos.c) c = aos.c; - l = aos.l; - id = aos.id; - return *this; - } - - friend ostream &operator<<(ostream &output, const orseq &o) { - output << "ORSeq: " << o.c; - output << " List:"; - for (const auto &t : o.l) - output << "(" << get<0>(t) << " " << get<1>(t) - << " " << get<2>(t) << ")"; - return output; - } - - typename list, pair, T>>::iterator begin() { - return l.begin(); - } - - typename list, pair, T>>::iterator end() { - return l.end(); - } - - orseq erase(typename list, pair, T>>::iterator i) { - orseq res; - if (i != l.end()) { - res.c.insertdot(get<1>(*i)); - l.erase(i); - } - return res; - } - - dotcontext &context() { - return c; - } - - orseq reset() { - orseq res; - for (auto const &t : l) - res.c.insertdot(get<1>(t)); - l.clear(); - return res; - } - - orseq insert(typename list, pair, T>>::iterator i, const T &val) { - orseq res; - if (i == l.end()) - res = push_back(val); - else if (i == l.begin()) - res = push_front(val); - else { - typename list, pair, T>>::iterator j = i; - j--; - vector bl, br, pos; - bl = get<0>(*j); - br = get<0>(*i); - pos = among(bl, br); - // get new dot - auto dot = c.makedot(id); - auto tuple = make_tuple(pos, dot, val); - l.insert(i, tuple); - // delta - res.c.insertdot(dot); - res.l.push_front(tuple); - } - return res; - } - - // add 1st element - orseq makefirst(const T &val) { - assert(l.empty()); - - orseq res; - vector bl, br, pos; - bl.push_back(false); - br.push_back(true); - pos = among(bl, br); - // get new dot - pair dot = c.makedot(id); - l.push_back(make_tuple(pos, dot, val)); - // delta - res.c.insertdot(dot); - res.l = l; - return res; - } - - orseq push_back(const T &val) { - orseq res; - if (l.empty()) - res = makefirst(val); - else { - vector bl, br, pos; - bl = get<0>(l.back()); - br.push_back(true); - pos = among(bl, br); - // get new dot - auto dot = c.makedot(id); - auto tuple = make_tuple(pos, dot, val); - l.push_back(tuple); - // delta - res.c.insertdot(dot); - res.l.push_front(tuple); - } - return res; - } - - orseq push_front(const T &val) { - orseq res; - if (l.empty()) - res = makefirst(val); - else { - vector bl, br, pos; - br = get<0>(l.front()); - bl.push_back(false); - pos = among(bl, br); - // get new dot - auto dot = c.makedot(id); - auto tuple = make_tuple(pos, dot, val); - l.push_front(tuple); - // delta - res.c.insertdot(dot); - res.l.push_front(tuple); - } - return res; - } - - void join(const orseq &o) { - if (this == &o) return; // Join is idempotent, but just don't do it. - auto it = l.begin(); - auto ito = o.l.begin(); - pair, I> e, eo; - do { - if (it != l.end()) { - e.first = get<0>(*it); - e.second = get<1>(*it).first; - } - if (ito != o.l.end()) { - eo.first = get<0>(*ito); - eo.second = get<1>(*ito).first; - } - if (it != l.end() && (ito == o.l.end() || e < eo)) { - // cout << "ds one\n"; - // entry only at this - if (o.c.dotin(get<1>(*it))) // other knows dot, must delete here - l.erase(it++); - else // keep it - ++it; - } else if (ito != o.l.end() && (it == l.end() || eo < e)) { - //cout << "ds two\n"; - // entry only at other - if (!c.dotin(get<1>(*ito))) // If I dont know, import - { - l.insert(it, *ito); // it keeps pointing to next - } - ++ito; - } else if (it != l.end() && ito != o.l.end()) { - // cout << "ds three\n"; - // in both - ++it; - ++ito; - } - } while (it != l.end() || ito != o.l.end()); - // CC - c.join(o.c); - - } - -}; - -#endif \ No newline at end of file diff --git a/core/include/dsr/core/topics/IDLGraph.hpp b/core/include/dsr/core/topics/IDLGraph.hpp deleted file mode 100644 index 65c21888..00000000 --- a/core/include/dsr/core/topics/IDLGraph.hpp +++ /dev/null @@ -1,5578 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/*! - * @file IDLGraph.hpp - * This header file contains the declaration of the described types in the IDL file. - * - * This file was generated by the tool fastddsgen. - */ - -#ifndef FAST_DDS_GENERATED__IDLGRAPH_HPP -#define FAST_DDS_GENERATED__IDLGRAPH_HPP - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#define eProsima_user_DllExport __declspec( dllexport ) -#else -#define eProsima_user_DllExport -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define eProsima_user_DllExport -#endif // _WIN32 - -#if defined(_WIN32) -#if defined(EPROSIMA_USER_DLL_EXPORT) -#if defined(IDLGRAPH_SOURCE) -#define IDLGRAPH_DllAPI __declspec( dllexport ) -#else -#define IDLGRAPH_DllAPI __declspec( dllimport ) -#endif // IDLGRAPH_SOURCE -#else -#define IDLGRAPH_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define IDLGRAPH_DllAPI -#endif // _WIN32 -namespace IDL{ -/*! - * @brief This class represents the union Val defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class Val -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Val() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Val() - { - if (member_destructor_) - { - member_destructor_(); - } - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val( - const Val& x) - { - m__d = x.m__d; - - switch (x.selected_member_) - { - case 0x00000001: - str_() = x.m_str; - break; - - case 0x00000002: - dec_() = x.m_dec; - break; - - case 0x00000003: - fl_() = x.m_fl; - break; - - case 0x00000004: - float_vec_() = x.m_float_vec; - break; - - case 0x00000005: - bl_() = x.m_bl; - break; - - case 0x00000006: - byte_vec_() = x.m_byte_vec; - break; - - case 0x00000007: - uint_() = x.m_uint; - break; - - case 0x00000008: - u64_() = x.m_u64; - break; - - case 0x00000009: - dob_() = x.m_dob; - break; - - case 0x0000000a: - uint64_vec_() = x.m_uint64_vec; - break; - - case 0x0000000b: - vec_float2_() = x.m_vec_float2; - break; - - case 0x0000000c: - vec_float3_() = x.m_vec_float3; - break; - - case 0x0000000d: - vec_float4_() = x.m_vec_float4; - break; - - case 0x0000000e: - vec_float6_() = x.m_vec_float6; - break; - - } - } - - /*! - * @brief Move constructor. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val( - Val&& x) noexcept - { - m__d = x.m__d; - - switch (x.selected_member_) - { - case 0x00000001: - str_() = std::move(x.m_str); - break; - - case 0x00000002: - dec_() = std::move(x.m_dec); - break; - - case 0x00000003: - fl_() = std::move(x.m_fl); - break; - - case 0x00000004: - float_vec_() = std::move(x.m_float_vec); - break; - - case 0x00000005: - bl_() = std::move(x.m_bl); - break; - - case 0x00000006: - byte_vec_() = std::move(x.m_byte_vec); - break; - - case 0x00000007: - uint_() = std::move(x.m_uint); - break; - - case 0x00000008: - u64_() = std::move(x.m_u64); - break; - - case 0x00000009: - dob_() = std::move(x.m_dob); - break; - - case 0x0000000a: - uint64_vec_() = std::move(x.m_uint64_vec); - break; - - case 0x0000000b: - vec_float2_() = std::move(x.m_vec_float2); - break; - - case 0x0000000c: - vec_float3_() = std::move(x.m_vec_float3); - break; - - case 0x0000000d: - vec_float4_() = std::move(x.m_vec_float4); - break; - - case 0x0000000e: - vec_float6_() = std::move(x.m_vec_float6); - break; - - } - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val& operator =( - const Val& x) - { - m__d = x.m__d; - - switch (x.selected_member_) - { - case 0x00000001: - str_() = x.m_str; - break; - - case 0x00000002: - dec_() = x.m_dec; - break; - - case 0x00000003: - fl_() = x.m_fl; - break; - - case 0x00000004: - float_vec_() = x.m_float_vec; - break; - - case 0x00000005: - bl_() = x.m_bl; - break; - - case 0x00000006: - byte_vec_() = x.m_byte_vec; - break; - - case 0x00000007: - uint_() = x.m_uint; - break; - - case 0x00000008: - u64_() = x.m_u64; - break; - - case 0x00000009: - dob_() = x.m_dob; - break; - - case 0x0000000a: - uint64_vec_() = x.m_uint64_vec; - break; - - case 0x0000000b: - vec_float2_() = x.m_vec_float2; - break; - - case 0x0000000c: - vec_float3_() = x.m_vec_float3; - break; - - case 0x0000000d: - vec_float4_() = x.m_vec_float4; - break; - - case 0x0000000e: - vec_float6_() = x.m_vec_float6; - break; - - } - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val& operator =( - Val&& x) noexcept - { - m__d = x.m__d; - - switch (x.selected_member_) - { - case 0x00000001: - str_() = std::move(x.m_str); - break; - - case 0x00000002: - dec_() = std::move(x.m_dec); - break; - - case 0x00000003: - fl_() = std::move(x.m_fl); - break; - - case 0x00000004: - float_vec_() = std::move(x.m_float_vec); - break; - - case 0x00000005: - bl_() = std::move(x.m_bl); - break; - - case 0x00000006: - byte_vec_() = std::move(x.m_byte_vec); - break; - - case 0x00000007: - uint_() = std::move(x.m_uint); - break; - - case 0x00000008: - u64_() = std::move(x.m_u64); - break; - - case 0x00000009: - dob_() = std::move(x.m_dob); - break; - - case 0x0000000a: - uint64_vec_() = std::move(x.m_uint64_vec); - break; - - case 0x0000000b: - vec_float2_() = std::move(x.m_vec_float2); - break; - - case 0x0000000c: - vec_float3_() = std::move(x.m_vec_float3); - break; - - case 0x0000000d: - vec_float4_() = std::move(x.m_vec_float4); - break; - - case 0x0000000e: - vec_float6_() = std::move(x.m_vec_float6); - break; - - } - - return *this; - } - - /*! - * @brief Comparison operator. - * @param x Val object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Val& x) const - { - bool ret_value {false}; - - if (x.selected_member_ == selected_member_) - { - if (0x0FFFFFFFu != selected_member_) - { - if (x.m__d == m__d) - { - switch (selected_member_) - { - case 0x00000001: - ret_value = (x.m_str == m_str); - break; - - case 0x00000002: - ret_value = (x.m_dec == m_dec); - break; - - case 0x00000003: - ret_value = (x.m_fl == m_fl); - break; - - case 0x00000004: - ret_value = (x.m_float_vec == m_float_vec); - break; - - case 0x00000005: - ret_value = (x.m_bl == m_bl); - break; - - case 0x00000006: - ret_value = (x.m_byte_vec == m_byte_vec); - break; - - case 0x00000007: - ret_value = (x.m_uint == m_uint); - break; - - case 0x00000008: - ret_value = (x.m_u64 == m_u64); - break; - - case 0x00000009: - ret_value = (x.m_dob == m_dob); - break; - - case 0x0000000a: - ret_value = (x.m_uint64_vec == m_uint64_vec); - break; - - case 0x0000000b: - ret_value = (x.m_vec_float2 == m_vec_float2); - break; - - case 0x0000000c: - ret_value = (x.m_vec_float3 == m_vec_float3); - break; - - case 0x0000000d: - ret_value = (x.m_vec_float4 == m_vec_float4); - break; - - case 0x0000000e: - ret_value = (x.m_vec_float6 == m_vec_float6); - break; - - } - } - } - else - { - ret_value = true; - } - } - - return ret_value; - } - - /*! - * @brief Comparison operator. - * @param x Val object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Val& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets the discriminator value. - * @param __d New value for the discriminator. - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the new value doesn't correspond to the selected union member. - */ - eProsima_user_DllExport void _d( - int32_t __d) - { - bool valid_discriminator = false; - - switch (__d) - { - case 0: - if (0x00000001 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 1: - if (0x00000002 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 2: - if (0x00000003 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 3: - if (0x00000004 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 4: - if (0x00000005 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 5: - if (0x00000006 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 6: - if (0x00000007 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 7: - if (0x00000008 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 8: - if (0x00000009 == selected_member_) - { - valid_discriminator = true; - } - break; - - case 9: - if (0x0000000a == selected_member_) - { - valid_discriminator = true; - } - break; - - case 10: - if (0x0000000b == selected_member_) - { - valid_discriminator = true; - } - break; - - case 11: - if (0x0000000c == selected_member_) - { - valid_discriminator = true; - } - break; - - case 12: - if (0x0000000d == selected_member_) - { - valid_discriminator = true; - } - break; - - case 13: - if (0x0000000e == selected_member_) - { - valid_discriminator = true; - } - break; - - } - - if (!valid_discriminator) - { - throw eprosima::fastcdr::exception::BadParamException("Discriminator doesn't correspond with the selected union member"); - } - - m__d = __d; - } - - /*! - * @brief This function returns the value of the discriminator. - * @return Value of the discriminator - */ - eProsima_user_DllExport int32_t _d() const - { - return m__d; - } - - /*! - * @brief This function copies the value in member str - * @param _str New value to be copied in member str - */ - eProsima_user_DllExport void str( - const std::string& _str) - { - str_() = _str; - m__d = 0; - } - - /*! - * @brief This function moves the value in member str - * @param _str New value to be moved in member str - */ - eProsima_user_DllExport void str( - std::string&& _str) - { - str_() = _str; - m__d = 0; - } - - /*! - * @brief This function returns a constant reference to member str - * @return Constant reference to member str - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::string& str() const - { - if (0x00000001 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_str; - } - - /*! - * @brief This function returns a reference to member str - * @return Reference to member str - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::string& str() - { - if (0x00000001 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_str; - } - - - /*! - * @brief This function sets a value in member dec - * @param _dec New value for member dec - */ - eProsima_user_DllExport void dec( - int32_t _dec) - { - dec_() = _dec; - m__d = 1; - } - - /*! - * @brief This function returns the value of member dec - * @return Value of member dec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport int32_t dec() const - { - if (0x00000002 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_dec; - } - - /*! - * @brief This function returns a reference to member dec - * @return Reference to member dec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport int32_t& dec() - { - if (0x00000002 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_dec; - } - - - /*! - * @brief This function sets a value in member fl - * @param _fl New value for member fl - */ - eProsima_user_DllExport void fl( - float _fl) - { - fl_() = _fl; - m__d = 2; - } - - /*! - * @brief This function returns the value of member fl - * @return Value of member fl - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport float fl() const - { - if (0x00000003 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_fl; - } - - /*! - * @brief This function returns a reference to member fl - * @return Reference to member fl - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport float& fl() - { - if (0x00000003 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_fl; - } - - - /*! - * @brief This function copies the value in member float_vec - * @param _float_vec New value to be copied in member float_vec - */ - eProsima_user_DllExport void float_vec( - const std::vector& _float_vec) - { - float_vec_() = _float_vec; - m__d = 3; - } - - /*! - * @brief This function moves the value in member float_vec - * @param _float_vec New value to be moved in member float_vec - */ - eProsima_user_DllExport void float_vec( - std::vector&& _float_vec) - { - float_vec_() = _float_vec; - m__d = 3; - } - - /*! - * @brief This function returns a constant reference to member float_vec - * @return Constant reference to member float_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& float_vec() const - { - if (0x00000004 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_float_vec; - } - - /*! - * @brief This function returns a reference to member float_vec - * @return Reference to member float_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& float_vec() - { - if (0x00000004 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_float_vec; - } - - - /*! - * @brief This function sets a value in member bl - * @param _bl New value for member bl - */ - eProsima_user_DllExport void bl( - bool _bl) - { - bl_() = _bl; - m__d = 4; - } - - /*! - * @brief This function returns the value of member bl - * @return Value of member bl - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport bool bl() const - { - if (0x00000005 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_bl; - } - - /*! - * @brief This function returns a reference to member bl - * @return Reference to member bl - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport bool& bl() - { - if (0x00000005 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_bl; - } - - - /*! - * @brief This function copies the value in member byte_vec - * @param _byte_vec New value to be copied in member byte_vec - */ - eProsima_user_DllExport void byte_vec( - const std::vector& _byte_vec) - { - byte_vec_() = _byte_vec; - m__d = 5; - } - - /*! - * @brief This function moves the value in member byte_vec - * @param _byte_vec New value to be moved in member byte_vec - */ - eProsima_user_DllExport void byte_vec( - std::vector&& _byte_vec) - { - byte_vec_() = _byte_vec; - m__d = 5; - } - - /*! - * @brief This function returns a constant reference to member byte_vec - * @return Constant reference to member byte_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& byte_vec() const - { - if (0x00000006 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_byte_vec; - } - - /*! - * @brief This function returns a reference to member byte_vec - * @return Reference to member byte_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& byte_vec() - { - if (0x00000006 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_byte_vec; - } - - - /*! - * @brief This function sets a value in member uint - * @param _uint New value for member uint - */ - eProsima_user_DllExport void uint( - uint32_t _uint) - { - uint_() = _uint; - m__d = 6; - } - - /*! - * @brief This function returns the value of member uint - * @return Value of member uint - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint32_t uint() const - { - if (0x00000007 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_uint; - } - - /*! - * @brief This function returns a reference to member uint - * @return Reference to member uint - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint32_t& uint() - { - if (0x00000007 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_uint; - } - - - /*! - * @brief This function sets a value in member u64 - * @param _u64 New value for member u64 - */ - eProsima_user_DllExport void u64( - uint64_t _u64) - { - u64_() = _u64; - m__d = 7; - } - - /*! - * @brief This function returns the value of member u64 - * @return Value of member u64 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint64_t u64() const - { - if (0x00000008 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_u64; - } - - /*! - * @brief This function returns a reference to member u64 - * @return Reference to member u64 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint64_t& u64() - { - if (0x00000008 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_u64; - } - - - /*! - * @brief This function sets a value in member dob - * @param _dob New value for member dob - */ - eProsima_user_DllExport void dob( - double _dob) - { - dob_() = _dob; - m__d = 8; - } - - /*! - * @brief This function returns the value of member dob - * @return Value of member dob - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport double dob() const - { - if (0x00000009 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_dob; - } - - /*! - * @brief This function returns a reference to member dob - * @return Reference to member dob - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport double& dob() - { - if (0x00000009 != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_dob; - } - - - /*! - * @brief This function copies the value in member uint64_vec - * @param _uint64_vec New value to be copied in member uint64_vec - */ - eProsima_user_DllExport void uint64_vec( - const std::vector& _uint64_vec) - { - uint64_vec_() = _uint64_vec; - m__d = 9; - } - - /*! - * @brief This function moves the value in member uint64_vec - * @param _uint64_vec New value to be moved in member uint64_vec - */ - eProsima_user_DllExport void uint64_vec( - std::vector&& _uint64_vec) - { - uint64_vec_() = _uint64_vec; - m__d = 9; - } - - /*! - * @brief This function returns a constant reference to member uint64_vec - * @return Constant reference to member uint64_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& uint64_vec() const - { - if (0x0000000a != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_uint64_vec; - } - - /*! - * @brief This function returns a reference to member uint64_vec - * @return Reference to member uint64_vec - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& uint64_vec() - { - if (0x0000000a != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_uint64_vec; - } - - - /*! - * @brief This function copies the value in member vec_float2 - * @param _vec_float2 New value to be copied in member vec_float2 - */ - eProsima_user_DllExport void vec_float2( - const std::array& _vec_float2) - { - vec_float2_() = _vec_float2; - m__d = 10; - } - - /*! - * @brief This function moves the value in member vec_float2 - * @param _vec_float2 New value to be moved in member vec_float2 - */ - eProsima_user_DllExport void vec_float2( - std::array&& _vec_float2) - { - vec_float2_() = _vec_float2; - m__d = 10; - } - - /*! - * @brief This function returns a constant reference to member vec_float2 - * @return Constant reference to member vec_float2 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float2() const - { - if (0x0000000b != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float2; - } - - /*! - * @brief This function returns a reference to member vec_float2 - * @return Reference to member vec_float2 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& vec_float2() - { - if (0x0000000b != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float2; - } - - - /*! - * @brief This function copies the value in member vec_float3 - * @param _vec_float3 New value to be copied in member vec_float3 - */ - eProsima_user_DllExport void vec_float3( - const std::array& _vec_float3) - { - vec_float3_() = _vec_float3; - m__d = 11; - } - - /*! - * @brief This function moves the value in member vec_float3 - * @param _vec_float3 New value to be moved in member vec_float3 - */ - eProsima_user_DllExport void vec_float3( - std::array&& _vec_float3) - { - vec_float3_() = _vec_float3; - m__d = 11; - } - - /*! - * @brief This function returns a constant reference to member vec_float3 - * @return Constant reference to member vec_float3 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float3() const - { - if (0x0000000c != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float3; - } - - /*! - * @brief This function returns a reference to member vec_float3 - * @return Reference to member vec_float3 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& vec_float3() - { - if (0x0000000c != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float3; - } - - - /*! - * @brief This function copies the value in member vec_float4 - * @param _vec_float4 New value to be copied in member vec_float4 - */ - eProsima_user_DllExport void vec_float4( - const std::array& _vec_float4) - { - vec_float4_() = _vec_float4; - m__d = 12; - } - - /*! - * @brief This function moves the value in member vec_float4 - * @param _vec_float4 New value to be moved in member vec_float4 - */ - eProsima_user_DllExport void vec_float4( - std::array&& _vec_float4) - { - vec_float4_() = _vec_float4; - m__d = 12; - } - - /*! - * @brief This function returns a constant reference to member vec_float4 - * @return Constant reference to member vec_float4 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float4() const - { - if (0x0000000d != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float4; - } - - /*! - * @brief This function returns a reference to member vec_float4 - * @return Reference to member vec_float4 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& vec_float4() - { - if (0x0000000d != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float4; - } - - - /*! - * @brief This function copies the value in member vec_float6 - * @param _vec_float6 New value to be copied in member vec_float6 - */ - eProsima_user_DllExport void vec_float6( - const std::array& _vec_float6) - { - vec_float6_() = _vec_float6; - m__d = 13; - } - - /*! - * @brief This function moves the value in member vec_float6 - * @param _vec_float6 New value to be moved in member vec_float6 - */ - eProsima_user_DllExport void vec_float6( - std::array&& _vec_float6) - { - vec_float6_() = _vec_float6; - m__d = 13; - } - - /*! - * @brief This function returns a constant reference to member vec_float6 - * @return Constant reference to member vec_float6 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float6() const - { - if (0x0000000e != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float6; - } - - /*! - * @brief This function returns a reference to member vec_float6 - * @return Reference to member vec_float6 - * @exception eprosima::fastcdr::exception::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& vec_float6() - { - if (0x0000000e != selected_member_) - { - throw eprosima::fastcdr::exception::BadParamException("This member has not been selected"); - } - - return m_vec_float6; - } - - - void _default() - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0FFFFFFFu; - } - - -private: - - std::string& str_() - { - if (0x00000001 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000001; - member_destructor_ = [&]() {m_str.~basic_string();}; - new(&m_str) std::string(); - - } - - return m_str; - } - - int32_t& dec_() - { - if (0x00000002 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000002; - member_destructor_ = nullptr; - m_dec = {0}; - - } - - return m_dec; - } - - float& fl_() - { - if (0x00000003 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000003; - member_destructor_ = nullptr; - m_fl = {0.0}; - - } - - return m_fl; - } - - std::vector& float_vec_() - { - if (0x00000004 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000004; - member_destructor_ = [&]() {m_float_vec.~vector();}; - new(&m_float_vec) std::vector(); - - } - - return m_float_vec; - } - - bool& bl_() - { - if (0x00000005 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000005; - member_destructor_ = nullptr; - m_bl = {false}; - - } - - return m_bl; - } - - std::vector& byte_vec_() - { - if (0x00000006 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000006; - member_destructor_ = [&]() {m_byte_vec.~vector();}; - new(&m_byte_vec) std::vector(); - - } - - return m_byte_vec; - } - - uint32_t& uint_() - { - if (0x00000007 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000007; - member_destructor_ = nullptr; - m_uint = {0}; - - } - - return m_uint; - } - - uint64_t& u64_() - { - if (0x00000008 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000008; - member_destructor_ = nullptr; - m_u64 = {0}; - - } - - return m_u64; - } - - double& dob_() - { - if (0x00000009 != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x00000009; - member_destructor_ = nullptr; - m_dob = {0.0}; - - } - - return m_dob; - } - - std::vector& uint64_vec_() - { - if (0x0000000a != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0000000a; - member_destructor_ = [&]() {m_uint64_vec.~vector();}; - new(&m_uint64_vec) std::vector(); - - } - - return m_uint64_vec; - } - - std::array& vec_float2_() - { - if (0x0000000b != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0000000b; - member_destructor_ = [&]() {m_vec_float2.~array();}; - new(&m_vec_float2) std::array(); - - } - - return m_vec_float2; - } - - std::array& vec_float3_() - { - if (0x0000000c != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0000000c; - member_destructor_ = [&]() {m_vec_float3.~array();}; - new(&m_vec_float3) std::array(); - - } - - return m_vec_float3; - } - - std::array& vec_float4_() - { - if (0x0000000d != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0000000d; - member_destructor_ = [&]() {m_vec_float4.~array();}; - new(&m_vec_float4) std::array(); - - } - - return m_vec_float4; - } - - std::array& vec_float6_() - { - if (0x0000000e != selected_member_) - { - if (member_destructor_) - { - member_destructor_(); - } - - selected_member_ = 0x0000000e; - member_destructor_ = [&]() {m_vec_float6.~array();}; - new(&m_vec_float6) std::array(); - - } - - return m_vec_float6; - } - - - int32_t m__d {2147483647}; - - union - { - std::string m_str; - int32_t m_dec; - float m_fl; - std::vector m_float_vec; - bool m_bl; - std::vector m_byte_vec; - uint32_t m_uint; - uint64_t m_u64; - double m_dob; - std::vector m_uint64_vec; - std::array m_vec_float2; - std::array m_vec_float3; - std::array m_vec_float4; - std::array m_vec_float6; - }; - - uint32_t selected_member_ {0x0FFFFFFFu}; - - std::function member_destructor_; -}; -/*! - * @brief This class represents the enumeration Types defined by the user in the IDL file. - * @ingroup IDLGraph - */ -enum class Types : int32_t -{ - STRING, - INT, - FLOAT, - FLOAT_VEC, - BOOL, - BYTE_VEC, - UINT, - UINT64, - DOUBLE, - UINT64_VEC, - VEC_FLOAT2, - VEC_FLOAT3, - VEC_FLOAT4, - VEC_FLOAT6 -}; -/*! - * @brief This class represents the structure Attrib defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class Attrib -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Attrib() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Attrib() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib( - const Attrib& x) - { - m_type = x.m_type; - - m_value = x.m_value; - - m_timestamp = x.m_timestamp; - - m_agent_id = x.m_agent_id; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib( - Attrib&& x) noexcept - { - m_type = x.m_type; - m_value = std::move(x.m_value); - m_timestamp = x.m_timestamp; - m_agent_id = x.m_agent_id; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib& operator =( - const Attrib& x) - { - - m_type = x.m_type; - - m_value = x.m_value; - - m_timestamp = x.m_timestamp; - - m_agent_id = x.m_agent_id; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib& operator =( - Attrib&& x) noexcept - { - - m_type = x.m_type; - m_value = std::move(x.m_value); - m_timestamp = x.m_timestamp; - m_agent_id = x.m_agent_id; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x Attrib object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Attrib& x) const - { - return (m_type == x.m_type && - m_value == x.m_value && - m_timestamp == x.m_timestamp && - m_agent_id == x.m_agent_id); - } - - /*! - * @brief Comparison operator. - * @param x Attrib object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Attrib& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member type - * @param _type New value for member type - */ - eProsima_user_DllExport void type( - uint32_t _type) - { - m_type = _type; - } - - /*! - * @brief This function returns the value of member type - * @return Value of member type - */ - eProsima_user_DllExport uint32_t type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport uint32_t& type() - { - return m_type; - } - - - /*! - * @brief This function copies the value in member value - * @param _value New value to be copied in member value - */ - eProsima_user_DllExport void value( - const Val& _value) - { - m_value = _value; - } - - /*! - * @brief This function moves the value in member value - * @param _value New value to be moved in member value - */ - eProsima_user_DllExport void value( - Val&& _value) - { - m_value = std::move(_value); - } - - /*! - * @brief This function returns a constant reference to member value - * @return Constant reference to member value - */ - eProsima_user_DllExport const Val& value() const - { - return m_value; - } - - /*! - * @brief This function returns a reference to member value - * @return Reference to member value - */ - eProsima_user_DllExport Val& value() - { - return m_value; - } - - - /*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ - eProsima_user_DllExport void timestamp( - uint64_t _timestamp) - { - m_timestamp = _timestamp; - } - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const - { - return m_timestamp; - } - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& timestamp() - { - return m_timestamp; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - -private: - - uint32_t m_type{0}; - Val m_value; - uint64_t m_timestamp{0}; - uint32_t m_agent_id{0}; - -}; -/*! - * @brief This class represents the structure PairInt defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class PairInt -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport PairInt() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~PairInt() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt( - const PairInt& x) - { - m_first = x.m_first; - - m_second = x.m_second; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt( - PairInt&& x) noexcept - { - m_first = x.m_first; - m_second = x.m_second; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt& operator =( - const PairInt& x) - { - - m_first = x.m_first; - - m_second = x.m_second; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt& operator =( - PairInt&& x) noexcept - { - - m_first = x.m_first; - m_second = x.m_second; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x PairInt object to compare. - */ - eProsima_user_DllExport bool operator ==( - const PairInt& x) const - { - return (m_first == x.m_first && - m_second == x.m_second); - } - - /*! - * @brief Comparison operator. - * @param x PairInt object to compare. - */ - eProsima_user_DllExport bool operator !=( - const PairInt& x) const - { - return !(*this == x); - } - - eProsima_user_DllExport bool operator<( - const PairInt &rhs) const - { - if (m_first < rhs.m_first) - return true; - if (rhs.m_first < m_first) - return false; - return m_second < rhs.m_second; - } - - /*! - * @brief This function sets a value in member first - * @param _first New value for member first - */ - eProsima_user_DllExport void first( - uint64_t _first) - { - m_first = _first; - } - - /*! - * @brief This function returns the value of member first - * @return Value of member first - */ - eProsima_user_DllExport uint64_t first() const - { - return m_first; - } - - /*! - * @brief This function returns a reference to member first - * @return Reference to member first - */ - eProsima_user_DllExport uint64_t& first() - { - return m_first; - } - - - /*! - * @brief This function sets a value in member second - * @param _second New value for member second - */ - eProsima_user_DllExport void second( - int32_t _second) - { - m_second = _second; - } - - /*! - * @brief This function returns the value of member second - * @return Value of member second - */ - eProsima_user_DllExport int32_t second() const - { - return m_second; - } - - /*! - * @brief This function returns a reference to member second - * @return Reference to member second - */ - eProsima_user_DllExport int32_t& second() - { - return m_second; - } - - - -private: - - uint64_t m_first{0}; - int32_t m_second{0}; - -}; -/*! - * @brief This class represents the structure DotContext defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotContext -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport DotContext() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~DotContext() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext( - const DotContext& x) - { - m_cc = x.m_cc; - - m_dc = x.m_dc; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext( - DotContext&& x) noexcept - { - m_cc = std::move(x.m_cc); - m_dc = std::move(x.m_dc); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext& operator =( - const DotContext& x) - { - - m_cc = x.m_cc; - - m_dc = x.m_dc; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext& operator =( - DotContext&& x) noexcept - { - - m_cc = std::move(x.m_cc); - m_dc = std::move(x.m_dc); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x DotContext object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotContext& x) const - { - return (m_cc == x.m_cc && - m_dc == x.m_dc); - } - - /*! - * @brief Comparison operator. - * @param x DotContext object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotContext& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member cc - * @param _cc New value to be copied in member cc - */ - eProsima_user_DllExport void cc( - const std::map& _cc) - { - m_cc = _cc; - } - - /*! - * @brief This function moves the value in member cc - * @param _cc New value to be moved in member cc - */ - eProsima_user_DllExport void cc( - std::map&& _cc) - { - m_cc = std::move(_cc); - } - - /*! - * @brief This function returns a constant reference to member cc - * @return Constant reference to member cc - */ - eProsima_user_DllExport const std::map& cc() const - { - return m_cc; - } - - /*! - * @brief This function returns a reference to member cc - * @return Reference to member cc - */ - eProsima_user_DllExport std::map& cc() - { - return m_cc; - } - - - /*! - * @brief This function copies the value in member dc - * @param _dc New value to be copied in member dc - */ - eProsima_user_DllExport void dc( - const std::vector& _dc) - { - m_dc = _dc; - } - - /*! - * @brief This function moves the value in member dc - * @param _dc New value to be moved in member dc - */ - eProsima_user_DllExport void dc( - std::vector&& _dc) - { - m_dc = std::move(_dc); - } - - /*! - * @brief This function returns a constant reference to member dc - * @return Constant reference to member dc - */ - eProsima_user_DllExport const std::vector& dc() const - { - return m_dc; - } - - /*! - * @brief This function returns a reference to member dc - * @return Reference to member dc - */ - eProsima_user_DllExport std::vector& dc() - { - return m_dc; - } - - - -private: - - std::map m_cc; - std::vector m_dc; - -}; -/*! - * @brief This class represents the structure DotKernelAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernelAttr -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport DotKernelAttr() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~DotKernelAttr() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr( - const DotKernelAttr& x) - { - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr( - DotKernelAttr&& x) noexcept - { - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr& operator =( - const DotKernelAttr& x) - { - - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr& operator =( - DotKernelAttr&& x) noexcept - { - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x DotKernelAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernelAttr& x) const - { - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); - } - - /*! - * @brief Comparison operator. - * @param x DotKernelAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernelAttr& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member ds - * @param _ds New value to be copied in member ds - */ - eProsima_user_DllExport void ds( - const std::map& _ds) - { - m_ds = _ds; - } - - /*! - * @brief This function moves the value in member ds - * @param _ds New value to be moved in member ds - */ - eProsima_user_DllExport void ds( - std::map&& _ds) - { - m_ds = std::move(_ds); - } - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const - { - return m_ds; - } - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& ds() - { - return m_ds; - } - - - /*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ - eProsima_user_DllExport void cbase( - const DotContext& _cbase) - { - m_cbase = _cbase; - } - - /*! - * @brief This function moves the value in member cbase - * @param _cbase New value to be moved in member cbase - */ - eProsima_user_DllExport void cbase( - DotContext&& _cbase) - { - m_cbase = std::move(_cbase); - } - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const - { - return m_cbase; - } - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& cbase() - { - return m_cbase; - } - - - -private: - - std::map m_ds; - DotContext m_cbase; - -}; -/*! - * @brief This class represents the structure MvregEdgeAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdgeAttr -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregEdgeAttr() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregEdgeAttr() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr( - const MvregEdgeAttr& x) - { - m_id = x.m_id; - - m_from = x.m_from; - - m_to = x.m_to; - - m_type = x.m_type; - - m_attr_name = x.m_attr_name; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr( - MvregEdgeAttr&& x) noexcept - { - m_id = x.m_id; - m_from = x.m_from; - m_to = x.m_to; - m_type = std::move(x.m_type); - m_attr_name = std::move(x.m_attr_name); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr& operator =( - const MvregEdgeAttr& x) - { - - m_id = x.m_id; - - m_from = x.m_from; - - m_to = x.m_to; - - m_type = x.m_type; - - m_attr_name = x.m_attr_name; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr& operator =( - MvregEdgeAttr&& x) noexcept - { - - m_id = x.m_id; - m_from = x.m_from; - m_to = x.m_to; - m_type = std::move(x.m_type); - m_attr_name = std::move(x.m_attr_name); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdgeAttr& x) const - { - return (m_id == x.m_id && - m_from == x.m_from && - m_to == x.m_to && - m_type == x.m_type && - m_attr_name == x.m_attr_name && - m_dk == x.m_dk && - m_agent_id == x.m_agent_id && - m_timestamp == x.m_timestamp); - } - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdgeAttr& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& id() - { - return m_id; - } - - - /*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ - eProsima_user_DllExport void from( - uint64_t _from) - { - m_from = _from; - } - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const - { - return m_from; - } - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& from() - { - return m_from; - } - - - /*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ - eProsima_user_DllExport void to( - uint64_t _to) - { - m_to = _to; - } - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const - { - return m_to; - } - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& to() - { - return m_to; - } - - - /*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ - eProsima_user_DllExport void type( - const std::string& _type) - { - m_type = _type; - } - - /*! - * @brief This function moves the value in member type - * @param _type New value to be moved in member type - */ - eProsima_user_DllExport void type( - std::string&& _type) - { - m_type = std::move(_type); - } - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& type() - { - return m_type; - } - - - /*! - * @brief This function copies the value in member attr_name - * @param _attr_name New value to be copied in member attr_name - */ - eProsima_user_DllExport void attr_name( - const std::string& _attr_name) - { - m_attr_name = _attr_name; - } - - /*! - * @brief This function moves the value in member attr_name - * @param _attr_name New value to be moved in member attr_name - */ - eProsima_user_DllExport void attr_name( - std::string&& _attr_name) - { - m_attr_name = std::move(_attr_name); - } - - /*! - * @brief This function returns a constant reference to member attr_name - * @return Constant reference to member attr_name - */ - eProsima_user_DllExport const std::string& attr_name() const - { - return m_attr_name; - } - - /*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ - eProsima_user_DllExport std::string& attr_name() - { - return m_attr_name; - } - - - /*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ - eProsima_user_DllExport void dk( - const DotKernelAttr& _dk) - { - m_dk = _dk; - } - - /*! - * @brief This function moves the value in member dk - * @param _dk New value to be moved in member dk - */ - eProsima_user_DllExport void dk( - DotKernelAttr&& _dk) - { - m_dk = std::move(_dk); - } - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelAttr& dk() const - { - return m_dk; - } - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelAttr& dk() - { - return m_dk; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - /*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ - eProsima_user_DllExport void timestamp( - uint64_t _timestamp) - { - m_timestamp = _timestamp; - } - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const - { - return m_timestamp; - } - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& timestamp() - { - return m_timestamp; - } - - - -private: - - uint64_t m_id{0}; - uint64_t m_from{0}; - uint64_t m_to{0}; - std::string m_type; - std::string m_attr_name; - DotKernelAttr m_dk; - uint32_t m_agent_id{0}; - uint64_t m_timestamp{0}; - -}; -/*! - * @brief This class represents the structure IDLEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class IDLEdge -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport IDLEdge() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~IDLEdge() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge( - const IDLEdge& x) - { - m_to = x.m_to; - - m_type = x.m_type; - - m_from = x.m_from; - - m_attrs = x.m_attrs; - - m_agent_id = x.m_agent_id; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge( - IDLEdge&& x) noexcept - { - m_to = x.m_to; - m_type = std::move(x.m_type); - m_from = x.m_from; - m_attrs = std::move(x.m_attrs); - m_agent_id = x.m_agent_id; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge& operator =( - const IDLEdge& x) - { - - m_to = x.m_to; - - m_type = x.m_type; - - m_from = x.m_from; - - m_attrs = x.m_attrs; - - m_agent_id = x.m_agent_id; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge& operator =( - IDLEdge&& x) noexcept - { - - m_to = x.m_to; - m_type = std::move(x.m_type); - m_from = x.m_from; - m_attrs = std::move(x.m_attrs); - m_agent_id = x.m_agent_id; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x IDLEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const IDLEdge& x) const - { - return (m_to == x.m_to && - m_type == x.m_type && - m_from == x.m_from && - m_attrs == x.m_attrs && - m_agent_id == x.m_agent_id); - } - - /*! - * @brief Comparison operator. - * @param x IDLEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const IDLEdge& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ - eProsima_user_DllExport void to( - uint64_t _to) - { - m_to = _to; - } - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const - { - return m_to; - } - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& to() - { - return m_to; - } - - - /*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ - eProsima_user_DllExport void type( - const std::string& _type) - { - m_type = _type; - } - - /*! - * @brief This function moves the value in member type - * @param _type New value to be moved in member type - */ - eProsima_user_DllExport void type( - std::string&& _type) - { - m_type = std::move(_type); - } - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& type() - { - return m_type; - } - - - /*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ - eProsima_user_DllExport void from( - uint64_t _from) - { - m_from = _from; - } - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const - { - return m_from; - } - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& from() - { - return m_from; - } - - - /*! - * @brief This function copies the value in member attrs - * @param _attrs New value to be copied in member attrs - */ - eProsima_user_DllExport void attrs( - const std::map& _attrs) - { - m_attrs = _attrs; - } - - /*! - * @brief This function moves the value in member attrs - * @param _attrs New value to be moved in member attrs - */ - eProsima_user_DllExport void attrs( - std::map&& _attrs) - { - m_attrs = std::move(_attrs); - } - - /*! - * @brief This function returns a constant reference to member attrs - * @return Constant reference to member attrs - */ - eProsima_user_DllExport const std::map& attrs() const - { - return m_attrs; - } - - /*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ - eProsima_user_DllExport std::map& attrs() - { - return m_attrs; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - -private: - - uint64_t m_to{0}; - std::string m_type; - uint64_t m_from{0}; - std::map m_attrs; - uint32_t m_agent_id{0}; - -}; -/*! - * @brief This class represents the structure EdgeKey defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class EdgeKey -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport EdgeKey() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~EdgeKey() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey( - const EdgeKey& x) - { - m_to = x.m_to; - - m_type = x.m_type; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey( - EdgeKey&& x) noexcept - { - m_to = x.m_to; - m_type = std::move(x.m_type); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey& operator =( - const EdgeKey& x) - { - - m_to = x.m_to; - - m_type = x.m_type; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey& operator =( - EdgeKey&& x) noexcept - { - - m_to = x.m_to; - m_type = std::move(x.m_type); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x EdgeKey object to compare. - */ - eProsima_user_DllExport bool operator ==( - const EdgeKey& x) const - { - return (m_to == x.m_to && - m_type == x.m_type); - } - - /*! - * @brief Comparison operator. - * @param x EdgeKey object to compare. - */ - eProsima_user_DllExport bool operator !=( - const EdgeKey& x) const - { - return !(*this == x); - } - - eProsima_user_DllExport bool operator<( - const EdgeKey &rhs) const - { - if (m_to < rhs.m_to) - return true; - if (rhs.m_to < m_to) - return false; - return m_type < rhs.m_type; - } - - /*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ - eProsima_user_DllExport void to( - uint64_t _to) - { - m_to = _to; - } - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const - { - return m_to; - } - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& to() - { - return m_to; - } - - - /*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ - eProsima_user_DllExport void type( - const std::string& _type) - { - m_type = _type; - } - - /*! - * @brief This function moves the value in member type - * @param _type New value to be moved in member type - */ - eProsima_user_DllExport void type( - std::string&& _type) - { - m_type = std::move(_type); - } - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& type() - { - return m_type; - } - - - -private: - - uint64_t m_to{0}; - std::string m_type; - -}; -/*! - * @brief This class represents the structure MvregNodeAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNodeAttr -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregNodeAttr() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregNodeAttr() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr( - const MvregNodeAttr& x) - { - m_id = x.m_id; - - m_node = x.m_node; - - m_attr_name = x.m_attr_name; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr( - MvregNodeAttr&& x) noexcept - { - m_id = x.m_id; - m_node = x.m_node; - m_attr_name = std::move(x.m_attr_name); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr& operator =( - const MvregNodeAttr& x) - { - - m_id = x.m_id; - - m_node = x.m_node; - - m_attr_name = x.m_attr_name; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr& operator =( - MvregNodeAttr&& x) noexcept - { - - m_id = x.m_id; - m_node = x.m_node; - m_attr_name = std::move(x.m_attr_name); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNodeAttr& x) const - { - return (m_id == x.m_id && - m_node == x.m_node && - m_attr_name == x.m_attr_name && - m_dk == x.m_dk && - m_agent_id == x.m_agent_id && - m_timestamp == x.m_timestamp); - } - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNodeAttr& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& id() - { - return m_id; - } - - - /*! - * @brief This function sets a value in member node - * @param _node New value for member node - */ - eProsima_user_DllExport void node( - uint64_t _node) - { - m_node = _node; - } - - /*! - * @brief This function returns the value of member node - * @return Value of member node - */ - eProsima_user_DllExport uint64_t node() const - { - return m_node; - } - - /*! - * @brief This function returns a reference to member node - * @return Reference to member node - */ - eProsima_user_DllExport uint64_t& node() - { - return m_node; - } - - - /*! - * @brief This function copies the value in member attr_name - * @param _attr_name New value to be copied in member attr_name - */ - eProsima_user_DllExport void attr_name( - const std::string& _attr_name) - { - m_attr_name = _attr_name; - } - - /*! - * @brief This function moves the value in member attr_name - * @param _attr_name New value to be moved in member attr_name - */ - eProsima_user_DllExport void attr_name( - std::string&& _attr_name) - { - m_attr_name = std::move(_attr_name); - } - - /*! - * @brief This function returns a constant reference to member attr_name - * @return Constant reference to member attr_name - */ - eProsima_user_DllExport const std::string& attr_name() const - { - return m_attr_name; - } - - /*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ - eProsima_user_DllExport std::string& attr_name() - { - return m_attr_name; - } - - - /*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ - eProsima_user_DllExport void dk( - const DotKernelAttr& _dk) - { - m_dk = _dk; - } - - /*! - * @brief This function moves the value in member dk - * @param _dk New value to be moved in member dk - */ - eProsima_user_DllExport void dk( - DotKernelAttr&& _dk) - { - m_dk = std::move(_dk); - } - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelAttr& dk() const - { - return m_dk; - } - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelAttr& dk() - { - return m_dk; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - /*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ - eProsima_user_DllExport void timestamp( - uint64_t _timestamp) - { - m_timestamp = _timestamp; - } - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const - { - return m_timestamp; - } - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& timestamp() - { - return m_timestamp; - } - - - -private: - - uint64_t m_id{0}; - uint64_t m_node{0}; - std::string m_attr_name; - DotKernelAttr m_dk; - uint32_t m_agent_id{0}; - uint64_t m_timestamp{0}; - -}; -/*! - * @brief This class represents the structure DotKernelEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernelEdge -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport DotKernelEdge() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~DotKernelEdge() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge( - const DotKernelEdge& x) - { - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge( - DotKernelEdge&& x) noexcept - { - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge& operator =( - const DotKernelEdge& x) - { - - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge& operator =( - DotKernelEdge&& x) noexcept - { - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x DotKernelEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernelEdge& x) const - { - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); - } - - /*! - * @brief Comparison operator. - * @param x DotKernelEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernelEdge& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member ds - * @param _ds New value to be copied in member ds - */ - eProsima_user_DllExport void ds( - const std::map& _ds) - { - m_ds = _ds; - } - - /*! - * @brief This function moves the value in member ds - * @param _ds New value to be moved in member ds - */ - eProsima_user_DllExport void ds( - std::map&& _ds) - { - m_ds = std::move(_ds); - } - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const - { - return m_ds; - } - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& ds() - { - return m_ds; - } - - - /*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ - eProsima_user_DllExport void cbase( - const DotContext& _cbase) - { - m_cbase = _cbase; - } - - /*! - * @brief This function moves the value in member cbase - * @param _cbase New value to be moved in member cbase - */ - eProsima_user_DllExport void cbase( - DotContext&& _cbase) - { - m_cbase = std::move(_cbase); - } - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const - { - return m_cbase; - } - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& cbase() - { - return m_cbase; - } - - - -private: - - std::map m_ds; - DotContext m_cbase; - -}; -/*! - * @brief This class represents the structure MvregEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdge -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregEdge() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregEdge() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge( - const MvregEdge& x) - { - m_id = x.m_id; - - m_from = x.m_from; - - m_to = x.m_to; - - m_type = x.m_type; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge( - MvregEdge&& x) noexcept - { - m_id = x.m_id; - m_from = x.m_from; - m_to = x.m_to; - m_type = std::move(x.m_type); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge& operator =( - const MvregEdge& x) - { - - m_id = x.m_id; - - m_from = x.m_from; - - m_to = x.m_to; - - m_type = x.m_type; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge& operator =( - MvregEdge&& x) noexcept - { - - m_id = x.m_id; - m_from = x.m_from; - m_to = x.m_to; - m_type = std::move(x.m_type); - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdge& x) const - { - return (m_id == x.m_id && - m_from == x.m_from && - m_to == x.m_to && - m_type == x.m_type && - m_dk == x.m_dk && - m_agent_id == x.m_agent_id && - m_timestamp == x.m_timestamp); - } - - /*! - * @brief Comparison operator. - * @param x MvregEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdge& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& id() - { - return m_id; - } - - - /*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ - eProsima_user_DllExport void from( - uint64_t _from) - { - m_from = _from; - } - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const - { - return m_from; - } - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& from() - { - return m_from; - } - - - /*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ - eProsima_user_DllExport void to( - uint64_t _to) - { - m_to = _to; - } - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const - { - return m_to; - } - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& to() - { - return m_to; - } - - - /*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ - eProsima_user_DllExport void type( - const std::string& _type) - { - m_type = _type; - } - - /*! - * @brief This function moves the value in member type - * @param _type New value to be moved in member type - */ - eProsima_user_DllExport void type( - std::string&& _type) - { - m_type = std::move(_type); - } - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& type() - { - return m_type; - } - - - /*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ - eProsima_user_DllExport void dk( - const DotKernelEdge& _dk) - { - m_dk = _dk; - } - - /*! - * @brief This function moves the value in member dk - * @param _dk New value to be moved in member dk - */ - eProsima_user_DllExport void dk( - DotKernelEdge&& _dk) - { - m_dk = std::move(_dk); - } - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelEdge& dk() const - { - return m_dk; - } - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelEdge& dk() - { - return m_dk; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - /*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ - eProsima_user_DllExport void timestamp( - uint64_t _timestamp) - { - m_timestamp = _timestamp; - } - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const - { - return m_timestamp; - } - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& timestamp() - { - return m_timestamp; - } - - - -private: - - uint64_t m_id{0}; - uint64_t m_from{0}; - uint64_t m_to{0}; - std::string m_type; - DotKernelEdge m_dk; - uint32_t m_agent_id{0}; - uint64_t m_timestamp{0}; - -}; -/*! - * @brief This class represents the structure IDLNode defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class IDLNode -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport IDLNode() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~IDLNode() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode( - const IDLNode& x) - { - m_type = x.m_type; - - m_name = x.m_name; - - m_id = x.m_id; - - m_agent_id = x.m_agent_id; - - m_attrs = x.m_attrs; - - m_fano = x.m_fano; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode( - IDLNode&& x) noexcept - { - m_type = std::move(x.m_type); - m_name = std::move(x.m_name); - m_id = x.m_id; - m_agent_id = x.m_agent_id; - m_attrs = std::move(x.m_attrs); - m_fano = std::move(x.m_fano); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode& operator =( - const IDLNode& x) - { - - m_type = x.m_type; - - m_name = x.m_name; - - m_id = x.m_id; - - m_agent_id = x.m_agent_id; - - m_attrs = x.m_attrs; - - m_fano = x.m_fano; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode& operator =( - IDLNode&& x) noexcept - { - - m_type = std::move(x.m_type); - m_name = std::move(x.m_name); - m_id = x.m_id; - m_agent_id = x.m_agent_id; - m_attrs = std::move(x.m_attrs); - m_fano = std::move(x.m_fano); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x IDLNode object to compare. - */ - eProsima_user_DllExport bool operator ==( - const IDLNode& x) const - { - return (m_type == x.m_type && - m_name == x.m_name && - m_id == x.m_id && - m_agent_id == x.m_agent_id && - m_attrs == x.m_attrs && - m_fano == x.m_fano); - } - - /*! - * @brief Comparison operator. - * @param x IDLNode object to compare. - */ - eProsima_user_DllExport bool operator !=( - const IDLNode& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ - eProsima_user_DllExport void type( - const std::string& _type) - { - m_type = _type; - } - - /*! - * @brief This function moves the value in member type - * @param _type New value to be moved in member type - */ - eProsima_user_DllExport void type( - std::string&& _type) - { - m_type = std::move(_type); - } - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const - { - return m_type; - } - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& type() - { - return m_type; - } - - - /*! - * @brief This function copies the value in member name - * @param _name New value to be copied in member name - */ - eProsima_user_DllExport void name( - const std::string& _name) - { - m_name = _name; - } - - /*! - * @brief This function moves the value in member name - * @param _name New value to be moved in member name - */ - eProsima_user_DllExport void name( - std::string&& _name) - { - m_name = std::move(_name); - } - - /*! - * @brief This function returns a constant reference to member name - * @return Constant reference to member name - */ - eProsima_user_DllExport const std::string& name() const - { - return m_name; - } - - /*! - * @brief This function returns a reference to member name - * @return Reference to member name - */ - eProsima_user_DllExport std::string& name() - { - return m_name; - } - - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& id() - { - return m_id; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - /*! - * @brief This function copies the value in member attrs - * @param _attrs New value to be copied in member attrs - */ - eProsima_user_DllExport void attrs( - const std::map& _attrs) - { - m_attrs = _attrs; - } - - /*! - * @brief This function moves the value in member attrs - * @param _attrs New value to be moved in member attrs - */ - eProsima_user_DllExport void attrs( - std::map&& _attrs) - { - m_attrs = std::move(_attrs); - } - - /*! - * @brief This function returns a constant reference to member attrs - * @return Constant reference to member attrs - */ - eProsima_user_DllExport const std::map& attrs() const - { - return m_attrs; - } - - /*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ - eProsima_user_DllExport std::map& attrs() - { - return m_attrs; - } - - - /*! - * @brief This function copies the value in member fano - * @param _fano New value to be copied in member fano - */ - eProsima_user_DllExport void fano( - const std::map& _fano) - { - m_fano = _fano; - } - - /*! - * @brief This function moves the value in member fano - * @param _fano New value to be moved in member fano - */ - eProsima_user_DllExport void fano( - std::map&& _fano) - { - m_fano = std::move(_fano); - } - - /*! - * @brief This function returns a constant reference to member fano - * @return Constant reference to member fano - */ - eProsima_user_DllExport const std::map& fano() const - { - return m_fano; - } - - /*! - * @brief This function returns a reference to member fano - * @return Reference to member fano - */ - eProsima_user_DllExport std::map& fano() - { - return m_fano; - } - - - -private: - - std::string m_type; - std::string m_name; - uint64_t m_id{0}; - uint32_t m_agent_id{0}; - std::map m_attrs; - std::map m_fano; - -}; -/*! - * @brief This class represents the structure GraphRequest defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class GraphRequest -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport GraphRequest() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~GraphRequest() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest( - const GraphRequest& x) - { - m_from = x.m_from; - - m_id = x.m_id; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest( - GraphRequest&& x) noexcept - { - m_from = std::move(x.m_from); - m_id = x.m_id; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest& operator =( - const GraphRequest& x) - { - - m_from = x.m_from; - - m_id = x.m_id; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest& operator =( - GraphRequest&& x) noexcept - { - - m_from = std::move(x.m_from); - m_id = x.m_id; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x GraphRequest object to compare. - */ - eProsima_user_DllExport bool operator ==( - const GraphRequest& x) const - { - return (m_from == x.m_from && - m_id == x.m_id); - } - - /*! - * @brief Comparison operator. - * @param x GraphRequest object to compare. - */ - eProsima_user_DllExport bool operator !=( - const GraphRequest& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member from - * @param _from New value to be copied in member from - */ - eProsima_user_DllExport void from( - const std::string& _from) - { - m_from = _from; - } - - /*! - * @brief This function moves the value in member from - * @param _from New value to be moved in member from - */ - eProsima_user_DllExport void from( - std::string&& _from) - { - m_from = std::move(_from); - } - - /*! - * @brief This function returns a constant reference to member from - * @return Constant reference to member from - */ - eProsima_user_DllExport const std::string& from() const - { - return m_from; - } - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport std::string& from() - { - return m_from; - } - - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - int32_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport int32_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport int32_t& id() - { - return m_id; - } - - - -private: - - std::string m_from; - int32_t m_id{0}; - -}; -/*! - * @brief This class represents the structure DotKernel defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernel -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport DotKernel() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~DotKernel() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel( - const DotKernel& x) - { - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel( - DotKernel&& x) noexcept - { - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel& operator =( - const DotKernel& x) - { - - m_ds = x.m_ds; - - m_cbase = x.m_cbase; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel& operator =( - DotKernel&& x) noexcept - { - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x DotKernel object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernel& x) const - { - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); - } - - /*! - * @brief Comparison operator. - * @param x DotKernel object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernel& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member ds - * @param _ds New value to be copied in member ds - */ - eProsima_user_DllExport void ds( - const std::map& _ds) - { - m_ds = _ds; - } - - /*! - * @brief This function moves the value in member ds - * @param _ds New value to be moved in member ds - */ - eProsima_user_DllExport void ds( - std::map&& _ds) - { - m_ds = std::move(_ds); - } - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const - { - return m_ds; - } - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& ds() - { - return m_ds; - } - - - /*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ - eProsima_user_DllExport void cbase( - const DotContext& _cbase) - { - m_cbase = _cbase; - } - - /*! - * @brief This function moves the value in member cbase - * @param _cbase New value to be moved in member cbase - */ - eProsima_user_DllExport void cbase( - DotContext&& _cbase) - { - m_cbase = std::move(_cbase); - } - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const - { - return m_cbase; - } - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& cbase() - { - return m_cbase; - } - - - -private: - - std::map m_ds; - DotContext m_cbase; - -}; -/*! - * @brief This class represents the structure MvregNode defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNode -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregNode() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregNode() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode( - const MvregNode& x) - { - m_id = x.m_id; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode( - MvregNode&& x) noexcept - { - m_id = x.m_id; - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode& operator =( - const MvregNode& x) - { - - m_id = x.m_id; - - m_dk = x.m_dk; - - m_agent_id = x.m_agent_id; - - m_timestamp = x.m_timestamp; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode& operator =( - MvregNode&& x) noexcept - { - - m_id = x.m_id; - m_dk = std::move(x.m_dk); - m_agent_id = x.m_agent_id; - m_timestamp = x.m_timestamp; - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregNode object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNode& x) const - { - return (m_id == x.m_id && - m_dk == x.m_dk && - m_agent_id == x.m_agent_id && - m_timestamp == x.m_timestamp); - } - - /*! - * @brief Comparison operator. - * @param x MvregNode object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNode& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& id() - { - return m_id; - } - - - /*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ - eProsima_user_DllExport void dk( - const DotKernel& _dk) - { - m_dk = _dk; - } - - /*! - * @brief This function moves the value in member dk - * @param _dk New value to be moved in member dk - */ - eProsima_user_DllExport void dk( - DotKernel&& _dk) - { - m_dk = std::move(_dk); - } - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernel& dk() const - { - return m_dk; - } - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernel& dk() - { - return m_dk; - } - - - /*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ - eProsima_user_DllExport void agent_id( - uint32_t _agent_id) - { - m_agent_id = _agent_id; - } - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const - { - return m_agent_id; - } - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& agent_id() - { - return m_agent_id; - } - - - /*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ - eProsima_user_DllExport void timestamp( - uint64_t _timestamp) - { - m_timestamp = _timestamp; - } - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const - { - return m_timestamp; - } - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& timestamp() - { - return m_timestamp; - } - - - -private: - - uint64_t m_id{0}; - DotKernel m_dk; - uint32_t m_agent_id{0}; - uint64_t m_timestamp{0}; - -}; -/*! - * @brief This class represents the structure OrMap defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class OrMap -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport OrMap() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~OrMap() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap( - const OrMap& x) - { - m_to_id = x.m_to_id; - - m_id = x.m_id; - - m_m = x.m_m; - - m_cbase = x.m_cbase; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap( - OrMap&& x) noexcept - { - m_to_id = x.m_to_id; - m_id = x.m_id; - m_m = std::move(x.m_m); - m_cbase = std::move(x.m_cbase); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap& operator =( - const OrMap& x) - { - - m_to_id = x.m_to_id; - - m_id = x.m_id; - - m_m = x.m_m; - - m_cbase = x.m_cbase; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap& operator =( - OrMap&& x) noexcept - { - - m_to_id = x.m_to_id; - m_id = x.m_id; - m_m = std::move(x.m_m); - m_cbase = std::move(x.m_cbase); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x OrMap object to compare. - */ - eProsima_user_DllExport bool operator ==( - const OrMap& x) const - { - return (m_to_id == x.m_to_id && - m_id == x.m_id && - m_m == x.m_m && - m_cbase == x.m_cbase); - } - - /*! - * @brief Comparison operator. - * @param x OrMap object to compare. - */ - eProsima_user_DllExport bool operator !=( - const OrMap& x) const - { - return !(*this == x); - } - - /*! - * @brief This function sets a value in member to_id - * @param _to_id New value for member to_id - */ - eProsima_user_DllExport void to_id( - uint32_t _to_id) - { - m_to_id = _to_id; - } - - /*! - * @brief This function returns the value of member to_id - * @return Value of member to_id - */ - eProsima_user_DllExport uint32_t to_id() const - { - return m_to_id; - } - - /*! - * @brief This function returns a reference to member to_id - * @return Reference to member to_id - */ - eProsima_user_DllExport uint32_t& to_id() - { - return m_to_id; - } - - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint32_t _id) - { - m_id = _id; - } - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint32_t id() const - { - return m_id; - } - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint32_t& id() - { - return m_id; - } - - - /*! - * @brief This function copies the value in member m - * @param _m New value to be copied in member m - */ - eProsima_user_DllExport void m( - const std::map& _m) - { - m_m = _m; - } - - /*! - * @brief This function moves the value in member m - * @param _m New value to be moved in member m - */ - eProsima_user_DllExport void m( - std::map&& _m) - { - m_m = std::move(_m); - } - - /*! - * @brief This function returns a constant reference to member m - * @return Constant reference to member m - */ - eProsima_user_DllExport const std::map& m() const - { - return m_m; - } - - /*! - * @brief This function returns a reference to member m - * @return Reference to member m - */ - eProsima_user_DllExport std::map& m() - { - return m_m; - } - - - /*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ - eProsima_user_DllExport void cbase( - const DotContext& _cbase) - { - m_cbase = _cbase; - } - - /*! - * @brief This function moves the value in member cbase - * @param _cbase New value to be moved in member cbase - */ - eProsima_user_DllExport void cbase( - DotContext&& _cbase) - { - m_cbase = std::move(_cbase); - } - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const - { - return m_cbase; - } - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& cbase() - { - return m_cbase; - } - - - -private: - - uint32_t m_to_id{0}; - uint32_t m_id{0}; - std::map m_m; - DotContext m_cbase; - -}; -/*! - * @brief This class represents the structure MvregEdgeAttrVec defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdgeAttrVec -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregEdgeAttrVec() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregEdgeAttrVec() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec( - const MvregEdgeAttrVec& x) - { - m_vec = x.m_vec; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec( - MvregEdgeAttrVec&& x) noexcept - { - m_vec = std::move(x.m_vec); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec& operator =( - const MvregEdgeAttrVec& x) - { - - m_vec = x.m_vec; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec& operator =( - MvregEdgeAttrVec&& x) noexcept - { - - m_vec = std::move(x.m_vec); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdgeAttrVec& x) const - { - return (m_vec == x.m_vec); - } - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdgeAttrVec& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member vec - * @param _vec New value to be copied in member vec - */ - eProsima_user_DllExport void vec( - const std::vector& _vec) - { - m_vec = _vec; - } - - /*! - * @brief This function moves the value in member vec - * @param _vec New value to be moved in member vec - */ - eProsima_user_DllExport void vec( - std::vector&& _vec) - { - m_vec = std::move(_vec); - } - - /*! - * @brief This function returns a constant reference to member vec - * @return Constant reference to member vec - */ - eProsima_user_DllExport const std::vector& vec() const - { - return m_vec; - } - - /*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ - eProsima_user_DllExport std::vector& vec() - { - return m_vec; - } - - - -private: - - std::vector m_vec; - -}; -/*! - * @brief This class represents the structure MvregNodeAttrVec defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNodeAttrVec -{ -public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport MvregNodeAttrVec() - { - } - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~MvregNodeAttrVec() - { - } - - /*! - * @brief Copy constructor. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec( - const MvregNodeAttrVec& x) - { - m_vec = x.m_vec; - - } - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec( - MvregNodeAttrVec&& x) noexcept - { - m_vec = std::move(x.m_vec); - } - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec& operator =( - const MvregNodeAttrVec& x) - { - - m_vec = x.m_vec; - - return *this; - } - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec& operator =( - MvregNodeAttrVec&& x) noexcept - { - - m_vec = std::move(x.m_vec); - return *this; - } - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNodeAttrVec& x) const - { - return (m_vec == x.m_vec); - } - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNodeAttrVec& x) const - { - return !(*this == x); - } - - /*! - * @brief This function copies the value in member vec - * @param _vec New value to be copied in member vec - */ - eProsima_user_DllExport void vec( - const std::vector& _vec) - { - m_vec = _vec; - } - - /*! - * @brief This function moves the value in member vec - * @param _vec New value to be moved in member vec - */ - eProsima_user_DllExport void vec( - std::vector&& _vec) - { - m_vec = std::move(_vec); - } - - /*! - * @brief This function returns a constant reference to member vec - * @return Constant reference to member vec - */ - eProsima_user_DllExport const std::vector& vec() const - { - return m_vec; - } - - /*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ - eProsima_user_DllExport std::vector& vec() - { - return m_vec; - } - - - -private: - - std::vector m_vec; - -}; -} - -#endif // _FAST_DDS_GENERATED_IDLGRAPH_HPP_ - - diff --git a/core/include/dsr/core/topics/IDLGraphCdrAux.hpp b/core/include/dsr/core/topics/IDLGraphCdrAux.hpp deleted file mode 100644 index f47ead2d..00000000 --- a/core/include/dsr/core/topics/IDLGraphCdrAux.hpp +++ /dev/null @@ -1,159 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/*! - * @file IDLGraphCdrAux.hpp - * This source file contains some definitions of CDR related functions. - * - * This file was generated by the tool fastddsgen. - */ - -#ifndef FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP -#define FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP - -#include "IDLGraph.hpp" - -constexpr uint32_t PairInt_max_cdr_typesize {20UL}; -constexpr uint32_t PairInt_max_key_cdr_typesize {0UL}; - -constexpr uint32_t DotContext_max_cdr_typesize {16UL}; -constexpr uint32_t DotContext_max_key_cdr_typesize {0UL}; - -constexpr uint32_t DotKernelAttr_max_cdr_typesize {28UL}; -constexpr uint32_t DotKernelAttr_max_key_cdr_typesize {0UL}; - - -constexpr uint32_t GraphRequest_max_cdr_typesize {268UL}; -constexpr uint32_t GraphRequest_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregEdge_max_cdr_typesize {336UL}; -constexpr uint32_t MvregEdge_max_key_cdr_typesize {0UL}; - -constexpr uint32_t DotKernel_max_cdr_typesize {28UL}; -constexpr uint32_t DotKernel_max_key_cdr_typesize {0UL}; - -constexpr uint32_t Attrib_max_cdr_typesize {292UL}; -constexpr uint32_t Attrib_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregEdgeAttr_max_cdr_typesize {592UL}; -constexpr uint32_t MvregEdgeAttr_max_key_cdr_typesize {0UL}; - -constexpr uint32_t IDLEdge_max_cdr_typesize {300UL}; -constexpr uint32_t IDLEdge_max_key_cdr_typesize {0UL}; - -constexpr uint32_t EdgeKey_max_cdr_typesize {276UL}; -constexpr uint32_t EdgeKey_max_key_cdr_typesize {0UL}; - -constexpr uint32_t IDLNode_max_cdr_typesize {556UL}; -constexpr uint32_t IDLNode_max_key_cdr_typesize {0UL}; - -constexpr uint32_t OrMap_max_cdr_typesize {36UL}; -constexpr uint32_t OrMap_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregNodeAttr_max_cdr_typesize {328UL}; -constexpr uint32_t MvregNodeAttr_max_key_cdr_typesize {0UL}; - -constexpr uint32_t DotKernelEdge_max_cdr_typesize {28UL}; -constexpr uint32_t DotKernelEdge_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregNode_max_cdr_typesize {56UL}; -constexpr uint32_t MvregNode_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregEdgeAttrVec_max_cdr_typesize {12UL}; -constexpr uint32_t MvregEdgeAttrVec_max_key_cdr_typesize {0UL}; - -constexpr uint32_t MvregNodeAttrVec_max_cdr_typesize {12UL}; -constexpr uint32_t MvregNodeAttrVec_max_key_cdr_typesize {0UL}; - - -namespace eprosima { -namespace fastcdr { - -class Cdr; -class CdrSizeCalculator; - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::Attrib& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::PairInt& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::DotContext& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelAttr& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttr& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::IDLEdge& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::EdgeKey& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttr& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelEdge& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdge& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::IDLNode& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::GraphRequest& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernel& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNode& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::OrMap& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttrVec& data); - -eProsima_user_DllExport void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttrVec& data); - - -} // namespace fastcdr -} // namespace eprosima - -#endif // FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP - diff --git a/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp b/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp deleted file mode 100644 index 517d3aea..00000000 --- a/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp +++ /dev/null @@ -1,1419 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/*! - * @file IDLGraphPubSubTypes.hpp - * This header file contains the declaration of the serialization functions. - * - * This file was generated by the tool fastddsgen. - */ - - -#ifndef FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP -#define FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP - -#include -#include -#include -#include -#include - -#include "IDLGraph.hpp" - - -#if !defined(FASTDDS_GEN_API_VER) || (FASTDDS_GEN_API_VER != 3) -#error \ - Generated IDLGraph is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. -#endif // FASTDDS_GEN_API_VER - - -/*! - * @brief This class represents the TopicDataType of the type Attrib defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::Attrib type; - - eProsima_user_DllExport AttribPubSubType(); - - eProsima_user_DllExport ~AttribPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type PairInt defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::PairInt type; - - eProsima_user_DllExport PairIntPubSubType(); - - eProsima_user_DllExport ~PairIntPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return true; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type DotContext defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::DotContext type; - - eProsima_user_DllExport DotContextPubSubType(); - - eProsima_user_DllExport ~DotContextPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type DotKernelAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::DotKernelAttr type; - - eProsima_user_DllExport DotKernelAttrPubSubType(); - - eProsima_user_DllExport ~DotKernelAttrPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregEdgeAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregEdgeAttr type; - - eProsima_user_DllExport MvregEdgeAttrPubSubType(); - - eProsima_user_DllExport ~MvregEdgeAttrPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type IDLEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::IDLEdge type; - - eProsima_user_DllExport IDLEdgePubSubType(); - - eProsima_user_DllExport ~IDLEdgePubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type EdgeKey defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::EdgeKey type; - - eProsima_user_DllExport EdgeKeyPubSubType(); - - eProsima_user_DllExport ~EdgeKeyPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregNodeAttr defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregNodeAttr type; - - eProsima_user_DllExport MvregNodeAttrPubSubType(); - - eProsima_user_DllExport ~MvregNodeAttrPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type DotKernelEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::DotKernelEdge type; - - eProsima_user_DllExport DotKernelEdgePubSubType(); - - eProsima_user_DllExport ~DotKernelEdgePubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregEdge defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregEdge type; - - eProsima_user_DllExport MvregEdgePubSubType(); - - eProsima_user_DllExport ~MvregEdgePubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type IDLNode defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::IDLNode type; - - eProsima_user_DllExport IDLNodePubSubType(); - - eProsima_user_DllExport ~IDLNodePubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type GraphRequest defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::GraphRequest type; - - eProsima_user_DllExport GraphRequestPubSubType(); - - eProsima_user_DllExport ~GraphRequestPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type DotKernel defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::DotKernel type; - - eProsima_user_DllExport DotKernelPubSubType(); - - eProsima_user_DllExport ~DotKernelPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregNode defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregNode type; - - eProsima_user_DllExport MvregNodePubSubType(); - - eProsima_user_DllExport ~MvregNodePubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type OrMap defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::OrMap type; - - eProsima_user_DllExport OrMapPubSubType(); - - eProsima_user_DllExport ~OrMapPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregEdgeAttrVec defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregEdgeAttrVec type; - - eProsima_user_DllExport MvregEdgeAttrVecPubSubType(); - - eProsima_user_DllExport ~MvregEdgeAttrVecPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -/*! - * @brief This class represents the TopicDataType of the type MvregNodeAttrVec defined by the user in the IDL file. - * @ingroup IDLGraph - */ -class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType -{ -public: - - typedef IDL::MvregNodeAttrVec type; - - eProsima_user_DllExport MvregNodeAttrVecPubSubType(); - - eProsima_user_DllExport ~MvregNodeAttrVecPubSubType() override; - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool deserialize( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - void* data) override; - - eProsima_user_DllExport uint32_t calculate_serialized_size( - const void* const data, - eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - - eProsima_user_DllExport bool compute_key( - eprosima::fastdds::rtps::SerializedPayload_t& payload, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport bool compute_key( - const void* const data, - eprosima::fastdds::rtps::InstanceHandle_t& ihandle, - bool force_md5 = false) override; - - eProsima_user_DllExport void* create_data() override; - - eProsima_user_DllExport void delete_data( - void* data) override; - - //Register TypeObject representation in Fast DDS TypeObjectRegistry - eProsima_user_DllExport void register_type_object_representation() override; - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - eProsima_user_DllExport inline bool is_bounded() const override - { - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED - -#ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - - eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override - { - static_cast(data_representation); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - -#ifdef TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eProsima_user_DllExport inline bool construct_sample( - void* memory) const override - { - static_cast(memory); - return false; - } - -#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - -private: - - eprosima::fastdds::MD5 md5_; - unsigned char* key_buffer_; - -}; - -#endif // FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP - diff --git a/core/include/dsr/core/types/crdt_types.h b/core/include/dsr/core/types/crdt_types.h index 1ca0658c..18a524ae 100644 --- a/core/include/dsr/core/types/crdt_types.h +++ b/core/include/dsr/core/types/crdt_types.h @@ -9,9 +9,9 @@ #include #include -#include "../crdt/delta_crdt.h" -#include "../serialization/serializable.h" -#include "common_types.h" +#include "dsr/core/crdt/delta_crdt.h" +#include "dsr/core/serialization/serializable.h" +#include "dsr/core/types/common_types.h" namespace DSR { @@ -104,7 +104,7 @@ namespace DSR { friend std::ostream &operator<<(std::ostream &output, const CRDTEdge &rhs) { - output << "IDL::EdgeAttribs[" << rhs.m_type << ", from:" << std::to_string(rhs.from()) << "-> to:" << std::to_string(rhs.to()) + output << " CRDTEdge [" << rhs.m_type << ", from:" << std::to_string(rhs.from()) << "-> to:" << std::to_string(rhs.to()) << " Attribs:["; for (const auto &v : rhs.attrs()) output << v.first << ":" << v.second << " - "; @@ -229,7 +229,7 @@ namespace DSR { friend std::ostream &operator<<(std::ostream &output, CRDTNode &rhs) { - output << "IDL::Node:[" << std::to_string(rhs.id()) << "," << rhs.name() << "," << rhs.type() << "], Attribs:["; + output << "CRDTNode: [" << std::to_string(rhs.id()) << "," << rhs.name() << "," << rhs.type() << "], Attribs:["; for (const auto &v : rhs.attrs()) output << v.first << ":(" << v.second << ");"; output << "], FanOut:["; diff --git a/core/topics/IDLGraph.idl b/core/topics/IDLGraph.idl deleted file mode 100644 index e944041f..00000000 --- a/core/topics/IDLGraph.idl +++ /dev/null @@ -1,169 +0,0 @@ - - union Val switch(long) { - case 0: - string str; - case 1: - long dec; - case 2: - float fl; - case 3: - sequence float_vec; - case 4: - boolean bl; - case 5: - sequence byte_vec; - case 6: - unsigned long uint; - case 7: - unsigned long long u64; - case 8: - double dob; - case 9: - sequence uint64_vec; - case 10: - float vec_float2[2]; - case 11: - float vec_float3[3]; - case 12: - float vec_float4[4]; - case 13: - float vec_float6[6]; - }; - - enum Types - { - _STRING, - _INT, - _FLOAT, - _FLOAT_VEC, - _BOOL, - _BYTE_VEC, - _UINT, - _UINT64, - _DOUBLE, - _UINT64_VEC, - _VEC_FLOAT2, - _VEC_FLOAT3, - _VEC_FLOAT4, - _VEC_FLOAT6 - }; - - - struct _Attrib - { - unsigned long type; - Val value; - unsigned long long timestamp; - unsigned long agent_id; - }; - - struct PairInt { - unsigned long long first; - long second; - }; - - struct DotContext { - map cc; - sequence dc; - }; - - struct DotKernelAttr { - map ds; - DotContext cbase; - }; - - struct MvregEdgeAttr { - unsigned long long id; - unsigned long long from; - unsigned long long to; - string type; - string attr_name; // We need it for remove deltas. - DotKernelAttr dk; - unsigned long agent_id; // to skip messages from the same agent in multithreading. - unsigned long long timestamp; - }; - - struct IDLEdge { - unsigned long long to; //key1 - string type; //key2 - unsigned long long from; // Se mantiene para trabajar más fácilmente con los Edges. - map attrs; - unsigned long agent_id; - }; - - struct EdgeKey { - unsigned long long to; - string type; - }; - - struct MvregNodeAttr { - unsigned long long id; - unsigned long long node; - string attr_name; // We need it for remove deltas. - DotKernelAttr dk; - unsigned long agent_id; // to skip messages from the same agent in multithreading. - unsigned long long timestamp; - }; - - - struct DotKernelEdge { - map ds; - DotContext cbase; - }; - - struct MvregEdge { - unsigned long long id; - unsigned long long from; - unsigned long long to; - string type; - DotKernelEdge dk; - unsigned long agent_id; // to skip messages from the same agent in multithread. - unsigned long long timestamp; - }; - - - struct IDLNode { - string type; - string name; - unsigned long long id; - unsigned long agent_id; - map attrs; - map fano; - }; - - struct GraphRequest - { - string from; - long id; - }; - - struct DotKernel { - map ds; - DotContext cbase; - }; - - struct MvregNode { - unsigned long long id; - DotKernel dk; - unsigned long agent_id; // to skip messages from the same agent in multithreading. - unsigned long long timestamp; - }; - - struct OrMap { - unsigned long to_id; //Used to check if a message with -1 m_id is for this agent. - unsigned long id; - map m; - DotContext cbase; - }; - - - struct MvregEdgeAttrVec { - sequence vec; - }; - - struct MvregNodeAttrVec { - sequence vec; - }; - - - diff --git a/core/topics/IDLGraphCdrAux.ipp b/core/topics/IDLGraphCdrAux.ipp deleted file mode 100644 index e011c3ae..00000000 --- a/core/topics/IDLGraphCdrAux.ipp +++ /dev/null @@ -1,2238 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/*! - * @file IDLGraphCdrAux.ipp - * This source file contains some declarations of CDR related functions. - * - * This file was generated by the tool fastddsgen. - */ - -#ifndef FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP -#define FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP - -#include "dsr/core/topics/IDLGraphCdrAux.hpp" - -#include -#include - - -#include -using namespace eprosima::fastcdr::exception; - -namespace eprosima { -namespace fastcdr { - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const Val& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), data._d(), - current_alignment); - - switch (data._d()) - { - case 0: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.str(), current_alignment); - break; - - case 1: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.dec(), current_alignment); - break; - - case 2: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.fl(), current_alignment); - break; - - case 3: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.float_vec(), current_alignment); - break; - - case 4: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), - data.bl(), current_alignment); - break; - - case 5: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), - data.byte_vec(), current_alignment); - break; - - case 6: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), - data.uint(), current_alignment); - break; - - case 7: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), - data.u64(), current_alignment); - break; - - case 8: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), - data.dob(), current_alignment); - break; - - case 9: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), - data.uint64_vec(), current_alignment); - break; - - case 10: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), - data.vec_float2(), current_alignment); - break; - - case 11: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(12), - data.vec_float3(), current_alignment); - break; - - case 12: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(13), - data.vec_float4(), current_alignment); - break; - - case 13: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(14), - data.vec_float6(), current_alignment); - break; - - default: - break; - } - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const Val& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr << eprosima::fastcdr::MemberId(0) << data._d(); - - switch (data._d()) - { - case 0: - scdr << eprosima::fastcdr::MemberId(1) << data.str(); - break; - - case 1: - scdr << eprosima::fastcdr::MemberId(2) << data.dec(); - break; - - case 2: - scdr << eprosima::fastcdr::MemberId(3) << data.fl(); - break; - - case 3: - scdr << eprosima::fastcdr::MemberId(4) << data.float_vec(); - break; - - case 4: - scdr << eprosima::fastcdr::MemberId(5) << data.bl(); - break; - - case 5: - scdr << eprosima::fastcdr::MemberId(6) << data.byte_vec(); - break; - - case 6: - scdr << eprosima::fastcdr::MemberId(7) << data.uint(); - break; - - case 7: - scdr << eprosima::fastcdr::MemberId(8) << data.u64(); - break; - - case 8: - scdr << eprosima::fastcdr::MemberId(9) << data.dob(); - break; - - case 9: - scdr << eprosima::fastcdr::MemberId(10) << data.uint64_vec(); - break; - - case 10: - scdr << eprosima::fastcdr::MemberId(11) << data.vec_float2(); - break; - - case 11: - scdr << eprosima::fastcdr::MemberId(12) << data.vec_float3(); - break; - - case 12: - scdr << eprosima::fastcdr::MemberId(13) << data.vec_float4(); - break; - - case 13: - scdr << eprosima::fastcdr::MemberId(14) << data.vec_float6(); - break; - - default: - break; - } - - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - Val& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - if (0 == mid.id) - { - int32_t discriminator; - dcdr >> discriminator; - - switch (discriminator) - { - case 0: - { - std::string str_value; - data.str(std::move(str_value)); - data._d(discriminator); - break; - } - - case 1: - { - int32_t dec_value{0}; - data.dec(std::move(dec_value)); - data._d(discriminator); - break; - } - - case 2: - { - float fl_value{0.0}; - data.fl(std::move(fl_value)); - data._d(discriminator); - break; - } - - case 3: - { - std::vector float_vec_value; - data.float_vec(std::move(float_vec_value)); - data._d(discriminator); - break; - } - - case 4: - { - bool bl_value{false}; - data.bl(std::move(bl_value)); - data._d(discriminator); - break; - } - - case 5: - { - std::vector byte_vec_value; - data.byte_vec(std::move(byte_vec_value)); - data._d(discriminator); - break; - } - - case 6: - { - uint32_t uint_value{0}; - data.uint(std::move(uint_value)); - data._d(discriminator); - break; - } - - case 7: - { - uint64_t u64_value{0}; - data.u64(std::move(u64_value)); - data._d(discriminator); - break; - } - - case 8: - { - double dob_value{0.0}; - data.dob(std::move(dob_value)); - data._d(discriminator); - break; - } - - case 9: - { - std::vector uint64_vec_value; - data.uint64_vec(std::move(uint64_vec_value)); - data._d(discriminator); - break; - } - - case 10: - { - std::array vec_float2_value{0.0}; - data.vec_float2(std::move(vec_float2_value)); - data._d(discriminator); - break; - } - - case 11: - { - std::array vec_float3_value{0.0}; - data.vec_float3(std::move(vec_float3_value)); - data._d(discriminator); - break; - } - - case 12: - { - std::array vec_float4_value{0.0}; - data.vec_float4(std::move(vec_float4_value)); - data._d(discriminator); - break; - } - - case 13: - { - std::array vec_float6_value{0.0}; - data.vec_float6(std::move(vec_float6_value)); - data._d(discriminator); - break; - } - - default: - data._default(); - break; - } - } - else - { - switch (data._d()) - { - case 0: - dcdr >> data.str(); - break; - - case 1: - dcdr >> data.dec(); - break; - - case 2: - dcdr >> data.fl(); - break; - - case 3: - dcdr >> data.float_vec(); - break; - - case 4: - dcdr >> data.bl(); - break; - - case 5: - dcdr >> data.byte_vec(); - break; - - case 6: - dcdr >> data.uint(); - break; - - case 7: - dcdr >> data.u64(); - break; - - case 8: - dcdr >> data.dob(); - break; - - case 9: - dcdr >> data.uint64_vec(); - break; - - case 10: - dcdr >> data.vec_float2(); - break; - - case 11: - dcdr >> data.vec_float3(); - break; - - case 12: - dcdr >> data.vec_float4(); - break; - - case 13: - dcdr >> data.vec_float6(); - break; - - default: - break; - } - ret_value = false; - } - return ret_value; - }); -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const Attrib& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.type(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.value(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.timestamp(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.agent_id(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const Attrib& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.type() - << eprosima::fastcdr::MemberId(1) << data.value() - << eprosima::fastcdr::MemberId(2) << data.timestamp() - << eprosima::fastcdr::MemberId(3) << data.agent_id() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - Attrib& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.type(); - break; - - case 1: - dcdr >> data.value(); - break; - - case 2: - dcdr >> data.timestamp(); - break; - - case 3: - dcdr >> data.agent_id(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const Attrib& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.type(); - - scdr << data.value(); - - scdr << data.timestamp(); - - scdr << data.agent_id(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const PairInt& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.first(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.second(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const PairInt& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.first() - << eprosima::fastcdr::MemberId(1) << data.second() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - PairInt& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.first(); - break; - - case 1: - dcdr >> data.second(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const PairInt& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.first(); - - scdr << data.second(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const DotContext& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.cc(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.dc(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const DotContext& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.cc() - << eprosima::fastcdr::MemberId(1) << data.dc() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - DotContext& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.cc(); - break; - - case 1: - dcdr >> data.dc(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const DotContext& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.cc(); - - scdr << data.dc(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const DotKernelAttr& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.ds(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.cbase(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const DotKernelAttr& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.ds() - << eprosima::fastcdr::MemberId(1) << data.cbase() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - DotKernelAttr& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.ds(); - break; - - case 1: - dcdr >> data.cbase(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const DotKernelAttr& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotContext& data); - - - static_cast(scdr); - static_cast(data); - scdr << data.ds(); - - serialize_key(scdr, data.cbase()); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregEdgeAttr& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.from(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.to(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.type(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.attr_name(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), - data.dk(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), - data.agent_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), - data.timestamp(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregEdgeAttr& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.id() - << eprosima::fastcdr::MemberId(1) << data.from() - << eprosima::fastcdr::MemberId(2) << data.to() - << eprosima::fastcdr::MemberId(3) << data.type() - << eprosima::fastcdr::MemberId(4) << data.attr_name() - << eprosima::fastcdr::MemberId(5) << data.dk() - << eprosima::fastcdr::MemberId(6) << data.agent_id() - << eprosima::fastcdr::MemberId(7) << data.timestamp() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregEdgeAttr& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.id(); - break; - - case 1: - dcdr >> data.from(); - break; - - case 2: - dcdr >> data.to(); - break; - - case 3: - dcdr >> data.type(); - break; - - case 4: - dcdr >> data.attr_name(); - break; - - case 5: - dcdr >> data.dk(); - break; - - case 6: - dcdr >> data.agent_id(); - break; - - case 7: - dcdr >> data.timestamp(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregEdgeAttr& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotKernelAttr& data); - - - - - static_cast(scdr); - static_cast(data); - scdr << data.id(); - - scdr << data.from(); - - scdr << data.to(); - - scdr << data.type(); - - scdr << data.attr_name(); - - serialize_key(scdr, data.dk()); - - scdr << data.agent_id(); - - scdr << data.timestamp(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDLEdge& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.to(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.type(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.from(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.attrs(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.agent_id(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const IDLEdge& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.to() - << eprosima::fastcdr::MemberId(1) << data.type() - << eprosima::fastcdr::MemberId(2) << data.from() - << eprosima::fastcdr::MemberId(3) << data.attrs() - << eprosima::fastcdr::MemberId(4) << data.agent_id() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - IDLEdge& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.to(); - break; - - case 1: - dcdr >> data.type(); - break; - - case 2: - dcdr >> data.from(); - break; - - case 3: - dcdr >> data.attrs(); - break; - - case 4: - dcdr >> data.agent_id(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDLEdge& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.to(); - - scdr << data.type(); - - scdr << data.from(); - - scdr << data.attrs(); - - scdr << data.agent_id(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const EdgeKey& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.to(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.type(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const EdgeKey& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.to() - << eprosima::fastcdr::MemberId(1) << data.type() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - EdgeKey& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.to(); - break; - - case 1: - dcdr >> data.type(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const EdgeKey& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.to(); - - scdr << data.type(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregNodeAttr& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.node(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.attr_name(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.dk(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.agent_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), - data.timestamp(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregNodeAttr& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.id() - << eprosima::fastcdr::MemberId(1) << data.node() - << eprosima::fastcdr::MemberId(2) << data.attr_name() - << eprosima::fastcdr::MemberId(3) << data.dk() - << eprosima::fastcdr::MemberId(4) << data.agent_id() - << eprosima::fastcdr::MemberId(5) << data.timestamp() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregNodeAttr& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.id(); - break; - - case 1: - dcdr >> data.node(); - break; - - case 2: - dcdr >> data.attr_name(); - break; - - case 3: - dcdr >> data.dk(); - break; - - case 4: - dcdr >> data.agent_id(); - break; - - case 5: - dcdr >> data.timestamp(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregNodeAttr& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotKernelAttr& data); - - - - - static_cast(scdr); - static_cast(data); - scdr << data.id(); - - scdr << data.node(); - - scdr << data.attr_name(); - - serialize_key(scdr, data.dk()); - - scdr << data.agent_id(); - - scdr << data.timestamp(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const DotKernelEdge& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.ds(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.cbase(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const DotKernelEdge& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.ds() - << eprosima::fastcdr::MemberId(1) << data.cbase() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - DotKernelEdge& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.ds(); - break; - - case 1: - dcdr >> data.cbase(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const DotKernelEdge& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotContext& data); - - - static_cast(scdr); - static_cast(data); - scdr << data.ds(); - - serialize_key(scdr, data.cbase()); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregEdge& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.from(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.to(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.type(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.dk(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), - data.agent_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), - data.timestamp(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregEdge& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.id() - << eprosima::fastcdr::MemberId(1) << data.from() - << eprosima::fastcdr::MemberId(2) << data.to() - << eprosima::fastcdr::MemberId(3) << data.type() - << eprosima::fastcdr::MemberId(4) << data.dk() - << eprosima::fastcdr::MemberId(5) << data.agent_id() - << eprosima::fastcdr::MemberId(6) << data.timestamp() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregEdge& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.id(); - break; - - case 1: - dcdr >> data.from(); - break; - - case 2: - dcdr >> data.to(); - break; - - case 3: - dcdr >> data.type(); - break; - - case 4: - dcdr >> data.dk(); - break; - - case 5: - dcdr >> data.agent_id(); - break; - - case 6: - dcdr >> data.timestamp(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregEdge& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotKernelEdge& data); - - - - - static_cast(scdr); - static_cast(data); - scdr << data.id(); - - scdr << data.from(); - - scdr << data.to(); - - scdr << data.type(); - - serialize_key(scdr, data.dk()); - - scdr << data.agent_id(); - - scdr << data.timestamp(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDLNode& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.type(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.name(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.agent_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), - data.attrs(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), - data.fano(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const IDLNode& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.type() - << eprosima::fastcdr::MemberId(1) << data.name() - << eprosima::fastcdr::MemberId(2) << data.id() - << eprosima::fastcdr::MemberId(3) << data.agent_id() - << eprosima::fastcdr::MemberId(4) << data.attrs() - << eprosima::fastcdr::MemberId(5) << data.fano() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - IDLNode& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.type(); - break; - - case 1: - dcdr >> data.name(); - break; - - case 2: - dcdr >> data.id(); - break; - - case 3: - dcdr >> data.agent_id(); - break; - - case 4: - dcdr >> data.attrs(); - break; - - case 5: - dcdr >> data.fano(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const IDLNode& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.type(); - - scdr << data.name(); - - scdr << data.id(); - - scdr << data.agent_id(); - - scdr << data.attrs(); - - scdr << data.fano(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const GraphRequest& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.from(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.id(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const GraphRequest& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.from() - << eprosima::fastcdr::MemberId(1) << data.id() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - GraphRequest& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.from(); - break; - - case 1: - dcdr >> data.id(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const GraphRequest& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.from(); - - scdr << data.id(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const DotKernel& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.ds(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.cbase(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const DotKernel& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.ds() - << eprosima::fastcdr::MemberId(1) << data.cbase() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - DotKernel& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.ds(); - break; - - case 1: - dcdr >> data.cbase(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const DotKernel& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotContext& data); - - - static_cast(scdr); - static_cast(data); - scdr << data.ds(); - - serialize_key(scdr, data.cbase()); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregNode& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.dk(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.agent_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.timestamp(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregNode& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.id() - << eprosima::fastcdr::MemberId(1) << data.dk() - << eprosima::fastcdr::MemberId(2) << data.agent_id() - << eprosima::fastcdr::MemberId(3) << data.timestamp() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregNode& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.id(); - break; - - case 1: - dcdr >> data.dk(); - break; - - case 2: - dcdr >> data.agent_id(); - break; - - case 3: - dcdr >> data.timestamp(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregNode& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotKernel& data); - - - - - static_cast(scdr); - static_cast(data); - scdr << data.id(); - - serialize_key(scdr, data.dk()); - - scdr << data.agent_id(); - - scdr << data.timestamp(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const OrMap& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.to_id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), - data.id(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), - data.m(), current_alignment); - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), - data.cbase(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const OrMap& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.to_id() - << eprosima::fastcdr::MemberId(1) << data.id() - << eprosima::fastcdr::MemberId(2) << data.m() - << eprosima::fastcdr::MemberId(3) << data.cbase() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - OrMap& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.to_id(); - break; - - case 1: - dcdr >> data.id(); - break; - - case 2: - dcdr >> data.m(); - break; - - case 3: - dcdr >> data.cbase(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const OrMap& data) -{ - extern void serialize_key( - Cdr& scdr, - const DotContext& data); - - - static_cast(scdr); - static_cast(data); - scdr << data.to_id(); - - scdr << data.id(); - - scdr << data.m(); - - serialize_key(scdr, data.cbase()); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregEdgeAttrVec& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.vec(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregEdgeAttrVec& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.vec() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregEdgeAttrVec& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.vec(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregEdgeAttrVec& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.vec(); - -} - - -template<> -eProsima_user_DllExport size_t calculate_serialized_size( - eprosima::fastcdr::CdrSizeCalculator& calculator, - const MvregNodeAttrVec& data, - size_t& current_alignment) -{ - static_cast(data); - - eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); - size_t calculated_size {calculator.begin_calculate_type_serialized_size( - eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - current_alignment)}; - - - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), - data.vec(), current_alignment); - - - calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); - - return calculated_size; -} - -template<> -eProsima_user_DllExport void serialize( - eprosima::fastcdr::Cdr& scdr, - const MvregNodeAttrVec& data) -{ - eprosima::fastcdr::Cdr::state current_state(scdr); - scdr.begin_serialize_type(current_state, - eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); - - scdr - << eprosima::fastcdr::MemberId(0) << data.vec() -; - scdr.end_serialize_type(current_state); -} - -template<> -eProsima_user_DllExport void deserialize( - eprosima::fastcdr::Cdr& cdr, - MvregNodeAttrVec& data) -{ - cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, - [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool - { - bool ret_value = true; - switch (mid.id) - { - case 0: - dcdr >> data.vec(); - break; - - default: - ret_value = false; - break; - } - return ret_value; - }); -} - -void serialize_key( - eprosima::fastcdr::Cdr& scdr, - const MvregNodeAttrVec& data) -{ - - static_cast(scdr); - static_cast(data); - scdr << data.vec(); - -} - - - -} // namespace fastcdr -} // namespace eprosima - -#endif // FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP - diff --git a/core/topics/IDLGraphPubSubTypes.cxx b/core/topics/IDLGraphPubSubTypes.cxx deleted file mode 100644 index aa5c0760..00000000 --- a/core/topics/IDLGraphPubSubTypes.cxx +++ /dev/null @@ -1,3111 +0,0 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/*! - * @file IDLGraphPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastddsgen. - */ - -#include "dsr/core/topics/IDLGraphPubSubTypes.hpp" - -#include -#include - -#include "dsr/core/topics/IDLGraphCdrAux.hpp" -using SerializedPayload_t = eprosima::fastdds::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastdds::rtps::InstanceHandle_t; -using namespace IDL;using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; - -AttribPubSubType::AttribPubSubType() -{ - set_name("Attrib"); - uint32_t type_size = Attrib_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = Attrib_max_key_cdr_typesize > 16 ? Attrib_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -AttribPubSubType::~AttribPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool AttribPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const Attrib* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool AttribPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - Attrib* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t AttribPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* AttribPubSubType::create_data() -{ - return reinterpret_cast(new Attrib()); -} - -void AttribPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool AttribPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - Attrib data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool AttribPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const Attrib* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - Attrib_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || Attrib_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void AttribPubSubType::register_type_object_representation() -{ - -} - -PairIntPubSubType::PairIntPubSubType() -{ - set_name("PairInt"); - uint32_t type_size = PairInt_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = PairInt_max_key_cdr_typesize > 16 ? PairInt_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -PairIntPubSubType::~PairIntPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool PairIntPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const PairInt* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool PairIntPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - PairInt* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t PairIntPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* PairIntPubSubType::create_data() -{ - return reinterpret_cast(new PairInt()); -} - -void PairIntPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool PairIntPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - PairInt data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool PairIntPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const PairInt* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - PairInt_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || PairInt_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void PairIntPubSubType::register_type_object_representation() -{ - -} - -DotContextPubSubType::DotContextPubSubType() -{ - set_name("DotContext"); - uint32_t type_size = DotContext_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = DotContext_max_key_cdr_typesize > 16 ? DotContext_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -DotContextPubSubType::~DotContextPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool DotContextPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const DotContext* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool DotContextPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - DotContext* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t DotContextPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* DotContextPubSubType::create_data() -{ - return reinterpret_cast(new DotContext()); -} - -void DotContextPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool DotContextPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - DotContext data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool DotContextPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const DotContext* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - DotContext_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || DotContext_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void DotContextPubSubType::register_type_object_representation() -{ - -} - -DotKernelAttrPubSubType::DotKernelAttrPubSubType() -{ - set_name("DotKernelAttr"); - uint32_t type_size = DotKernelAttr_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = DotKernelAttr_max_key_cdr_typesize > 16 ? DotKernelAttr_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -DotKernelAttrPubSubType::~DotKernelAttrPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool DotKernelAttrPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const DotKernelAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool DotKernelAttrPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - DotKernelAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t DotKernelAttrPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* DotKernelAttrPubSubType::create_data() -{ - return reinterpret_cast(new DotKernelAttr()); -} - -void DotKernelAttrPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool DotKernelAttrPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - DotKernelAttr data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool DotKernelAttrPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const DotKernelAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - DotKernelAttr_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || DotKernelAttr_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void DotKernelAttrPubSubType::register_type_object_representation() -{ - -} - -MvregEdgeAttrPubSubType::MvregEdgeAttrPubSubType() -{ - set_name("MvregEdgeAttr"); - uint32_t type_size = MvregEdgeAttr_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregEdgeAttr_max_key_cdr_typesize > 16 ? MvregEdgeAttr_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregEdgeAttrPubSubType::~MvregEdgeAttrPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregEdgeAttrPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregEdgeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregEdgeAttrPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregEdgeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregEdgeAttrPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregEdgeAttrPubSubType::create_data() -{ - return reinterpret_cast(new MvregEdgeAttr()); -} - -void MvregEdgeAttrPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregEdgeAttrPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregEdgeAttr data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregEdgeAttrPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregEdgeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregEdgeAttr_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregEdgeAttr_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregEdgeAttrPubSubType::register_type_object_representation() -{ - -} - -IDLEdgePubSubType::IDLEdgePubSubType() -{ - set_name("IDLEdge"); - uint32_t type_size = IDLEdge_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = IDLEdge_max_key_cdr_typesize > 16 ? IDLEdge_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -IDLEdgePubSubType::~IDLEdgePubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool IDLEdgePubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const IDLEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool IDLEdgePubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - IDLEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t IDLEdgePubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* IDLEdgePubSubType::create_data() -{ - return reinterpret_cast(new IDLEdge()); -} - -void IDLEdgePubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool IDLEdgePubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - IDLEdge data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool IDLEdgePubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const IDLEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - IDLEdge_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || IDLEdge_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void IDLEdgePubSubType::register_type_object_representation() -{ - -} - -EdgeKeyPubSubType::EdgeKeyPubSubType() -{ - set_name("EdgeKey"); - uint32_t type_size = EdgeKey_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = EdgeKey_max_key_cdr_typesize > 16 ? EdgeKey_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -EdgeKeyPubSubType::~EdgeKeyPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool EdgeKeyPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const EdgeKey* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool EdgeKeyPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - EdgeKey* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t EdgeKeyPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* EdgeKeyPubSubType::create_data() -{ - return reinterpret_cast(new EdgeKey()); -} - -void EdgeKeyPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool EdgeKeyPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - EdgeKey data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool EdgeKeyPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const EdgeKey* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - EdgeKey_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || EdgeKey_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void EdgeKeyPubSubType::register_type_object_representation() -{ - -} - -MvregNodeAttrPubSubType::MvregNodeAttrPubSubType() -{ - set_name("MvregNodeAttr"); - uint32_t type_size = MvregNodeAttr_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregNodeAttr_max_key_cdr_typesize > 16 ? MvregNodeAttr_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregNodeAttrPubSubType::~MvregNodeAttrPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregNodeAttrPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregNodeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregNodeAttrPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregNodeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregNodeAttrPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregNodeAttrPubSubType::create_data() -{ - return reinterpret_cast(new MvregNodeAttr()); -} - -void MvregNodeAttrPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregNodeAttrPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregNodeAttr data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregNodeAttrPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregNodeAttr* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregNodeAttr_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregNodeAttr_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregNodeAttrPubSubType::register_type_object_representation() -{ - -} - -DotKernelEdgePubSubType::DotKernelEdgePubSubType() -{ - set_name("DotKernelEdge"); - uint32_t type_size = DotKernelEdge_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = DotKernelEdge_max_key_cdr_typesize > 16 ? DotKernelEdge_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -DotKernelEdgePubSubType::~DotKernelEdgePubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool DotKernelEdgePubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const DotKernelEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool DotKernelEdgePubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - DotKernelEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t DotKernelEdgePubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* DotKernelEdgePubSubType::create_data() -{ - return reinterpret_cast(new DotKernelEdge()); -} - -void DotKernelEdgePubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool DotKernelEdgePubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - DotKernelEdge data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool DotKernelEdgePubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const DotKernelEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - DotKernelEdge_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || DotKernelEdge_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void DotKernelEdgePubSubType::register_type_object_representation() -{ - -} - -MvregEdgePubSubType::MvregEdgePubSubType() -{ - set_name("MvregEdge"); - uint32_t type_size = MvregEdge_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregEdge_max_key_cdr_typesize > 16 ? MvregEdge_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregEdgePubSubType::~MvregEdgePubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregEdgePubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregEdgePubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregEdgePubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregEdgePubSubType::create_data() -{ - return reinterpret_cast(new MvregEdge()); -} - -void MvregEdgePubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregEdgePubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregEdge data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregEdgePubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregEdge* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregEdge_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregEdge_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregEdgePubSubType::register_type_object_representation() -{ - -} - -IDLNodePubSubType::IDLNodePubSubType() -{ - set_name("IDLNode"); - uint32_t type_size = IDLNode_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = IDLNode_max_key_cdr_typesize > 16 ? IDLNode_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -IDLNodePubSubType::~IDLNodePubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool IDLNodePubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const IDLNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool IDLNodePubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - IDLNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t IDLNodePubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* IDLNodePubSubType::create_data() -{ - return reinterpret_cast(new IDLNode()); -} - -void IDLNodePubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool IDLNodePubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - IDLNode data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool IDLNodePubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const IDLNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - IDLNode_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || IDLNode_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void IDLNodePubSubType::register_type_object_representation() -{ - -} - -GraphRequestPubSubType::GraphRequestPubSubType() -{ - set_name("GraphRequest"); - uint32_t type_size = GraphRequest_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = GraphRequest_max_key_cdr_typesize > 16 ? GraphRequest_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -GraphRequestPubSubType::~GraphRequestPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool GraphRequestPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const GraphRequest* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool GraphRequestPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - GraphRequest* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t GraphRequestPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* GraphRequestPubSubType::create_data() -{ - return reinterpret_cast(new GraphRequest()); -} - -void GraphRequestPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool GraphRequestPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - GraphRequest data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool GraphRequestPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const GraphRequest* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - GraphRequest_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || GraphRequest_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void GraphRequestPubSubType::register_type_object_representation() -{ - -} - -DotKernelPubSubType::DotKernelPubSubType() -{ - set_name("DotKernel"); - uint32_t type_size = DotKernel_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = DotKernel_max_key_cdr_typesize > 16 ? DotKernel_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -DotKernelPubSubType::~DotKernelPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool DotKernelPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const DotKernel* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool DotKernelPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - DotKernel* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t DotKernelPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* DotKernelPubSubType::create_data() -{ - return reinterpret_cast(new DotKernel()); -} - -void DotKernelPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool DotKernelPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - DotKernel data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool DotKernelPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const DotKernel* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - DotKernel_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || DotKernel_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void DotKernelPubSubType::register_type_object_representation() -{ - -} - -MvregNodePubSubType::MvregNodePubSubType() -{ - set_name("MvregNode"); - uint32_t type_size = MvregNode_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregNode_max_key_cdr_typesize > 16 ? MvregNode_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregNodePubSubType::~MvregNodePubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregNodePubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregNodePubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregNodePubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregNodePubSubType::create_data() -{ - return reinterpret_cast(new MvregNode()); -} - -void MvregNodePubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregNodePubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregNode data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregNodePubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregNode* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregNode_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregNode_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregNodePubSubType::register_type_object_representation() -{ - -} - -OrMapPubSubType::OrMapPubSubType() -{ - set_name("OrMap"); - uint32_t type_size = OrMap_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = OrMap_max_key_cdr_typesize > 16 ? OrMap_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -OrMapPubSubType::~OrMapPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool OrMapPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const OrMap* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool OrMapPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - OrMap* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t OrMapPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* OrMapPubSubType::create_data() -{ - return reinterpret_cast(new OrMap()); -} - -void OrMapPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool OrMapPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - OrMap data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool OrMapPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const OrMap* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - OrMap_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || OrMap_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void OrMapPubSubType::register_type_object_representation() -{ - -} - -MvregEdgeAttrVecPubSubType::MvregEdgeAttrVecPubSubType() -{ - set_name("MvregEdgeAttrVec"); - uint32_t type_size = MvregEdgeAttrVec_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregEdgeAttrVec_max_key_cdr_typesize > 16 ? MvregEdgeAttrVec_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregEdgeAttrVecPubSubType::~MvregEdgeAttrVecPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregEdgeAttrVecPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregEdgeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregEdgeAttrVecPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregEdgeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregEdgeAttrVecPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregEdgeAttrVecPubSubType::create_data() -{ - return reinterpret_cast(new MvregEdgeAttrVec()); -} - -void MvregEdgeAttrVecPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregEdgeAttrVecPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregEdgeAttrVec data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregEdgeAttrVecPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregEdgeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregEdgeAttrVec_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregEdgeAttrVec_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregEdgeAttrVecPubSubType::register_type_object_representation() -{ - -} - -MvregNodeAttrVecPubSubType::MvregNodeAttrVecPubSubType() -{ - set_name("MvregNodeAttrVec"); - uint32_t type_size = MvregNodeAttrVec_max_cdr_typesize; - type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ - max_serialized_type_size = type_size + 4; /*encapsulation*/ - is_compute_key_provided = false; - uint32_t key_length = MvregNodeAttrVec_max_key_cdr_typesize > 16 ? MvregNodeAttrVec_max_key_cdr_typesize : 16; - key_buffer_ = reinterpret_cast(malloc(key_length)); - memset(key_buffer_, 0, key_length); -} - -MvregNodeAttrVecPubSubType::~MvregNodeAttrVecPubSubType() -{ - if (key_buffer_ != nullptr) - { - free(key_buffer_); - } -} - -bool MvregNodeAttrVecPubSubType::serialize( - const void* const data, - SerializedPayload_t& payload, - DataRepresentationId_t data_representation) -{ - const MvregNodeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.max_size); - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN, - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); - payload.encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - ser.set_encoding_flag( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : - eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - ser << *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload.length = static_cast(ser.get_serialized_data_length()); - return true; -} - -bool MvregNodeAttrVecPubSubType::deserialize( - SerializedPayload_t& payload, - void* data) -{ - try - { - // Convert DATA to pointer of your type - MvregNodeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload.data), payload.length); - - // Object that deserializes the data. - eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN); - - // Deserialize encapsulation. - deser.read_encapsulation(); - payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; - - // Deserialize the object. - deser >> *p_type; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - return true; -} - -uint32_t MvregNodeAttrVecPubSubType::calculate_serialized_size( - const void* const data, - DataRepresentationId_t data_representation) -{ - try - { - eprosima::fastcdr::CdrSizeCalculator calculator( - data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? - eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); - size_t current_alignment {0}; - return static_cast(calculator.calculate_serialized_size( - *static_cast(data), current_alignment)) + - 4u /*encapsulation*/; - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return 0; - } -} - -void* MvregNodeAttrVecPubSubType::create_data() -{ - return reinterpret_cast(new MvregNodeAttrVec()); -} - -void MvregNodeAttrVecPubSubType::delete_data( - void* data) -{ - delete(reinterpret_cast(data)); -} - -bool MvregNodeAttrVecPubSubType::compute_key( - SerializedPayload_t& payload, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - MvregNodeAttrVec data; - if (deserialize(payload, static_cast(&data))) - { - return compute_key(static_cast(&data), handle, force_md5); - } - - return false; -} - -bool MvregNodeAttrVecPubSubType::compute_key( - const void* const data, - InstanceHandle_t& handle, - bool force_md5) -{ - if (!is_compute_key_provided) - { - return false; - } - - const MvregNodeAttrVec* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(key_buffer_), - MvregNodeAttrVec_max_key_cdr_typesize); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv2); - ser.set_encoding_flag(eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR2); - eprosima::fastcdr::serialize_key(ser, *p_type); - if (force_md5 || MvregNodeAttrVec_max_key_cdr_typesize > 16) - { - md5_.init(); - md5_.update(key_buffer_, static_cast(ser.get_serialized_data_length())); - md5_.finalize(); - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = md5_.digest[i]; - } - } - else - { - for (uint8_t i = 0; i < 16; ++i) - { - handle.value[i] = key_buffer_[i]; - } - } - return true; -} - -void MvregNodeAttrVecPubSubType::register_type_object_representation() -{ - -} - - -// Include auxiliary functions like for serializing/deserializing. -#include "IDLGraphCdrAux.ipp" diff --git a/core/topics/regenidl.md b/core/topics/regenidl.md deleted file mode 100644 index 9a32e8a6..00000000 --- a/core/topics/regenidl.md +++ /dev/null @@ -1,50 +0,0 @@ -``` bash -cd ~/software/Fast-DDS-Gen -git pull -./gradlew clean -./gradlew jar -mv ./build/libs/fastddsgen.jar ./share/fastddsgen/java/fastddsgen.jar -scripts/fastddsgen ~/robocomp_ws/src/robocomp/robocomp_cortex/core/topics/IDLGraph.idl -no-typeobjectsupport -sed -i 's\IDLGraphCdrAux.hpp\dsr/core/topics/IDLGraphCdrAux.hpp\g' IDLGraphCdrAux.ipp -sed -i 's\IDLGraphPubSubTypes.hpp\dsr/core/topics/IDLGraphPubSubTypes.hpp\g' IDLGraphPubSubTypes.cxx -sed -i 's\IDLGraphCdrAux.hpp\dsr/core/topics/IDLGraphCdrAux.hpp\g' IDLGraphPubSubTypes.cxx -sed -i 's/\(const \)\(.*\&\) data/\1IDL::\2 data/' IDLGraphCdrAux.hpp -sed -i '31s/^/using namespace IDL;/' IDLGraphPubSubTypes.cxx #reemplazar 31 con un numero de linea vacio -sed -i 's\typedef \typedef IDL::\g' IDLGraphPubSubTypes.hpp -sed -i '60s/^/namespace IDL{/' IDLGraph.hpp # reemplazar 60 con un numero de linea justo antes de la clase Val -sed -i "$(wc -l IDLGraph.hpp | awk '{print $1-3}')s/$/}\n/" IDLGraph.hpp # pone el cierre del namespace } tres lineas antes del final del fichero. -cp *.hpp ~/robocomp_ws/src/robocomp/robocomp_cortex/core/include/dsr/core/topics/ -cp *cxx ~/robocomp_ws/src/robocomp/robocomp_cortex/core/topics/ -cp *ipp ~/robocomp_ws/src/robocomp/robocomp_cortex/core/topics/ - -``` - -En la clase PairInt en /core/include/dsr/core/topics/IDLGraph.hpp - -``` cpp - eProsima_user_DllExport bool operator<( - const PairInt &rhs) const - { - if (m_first < rhs.m_first) - return true; - if (rhs.m_first < m_first) - return false; - return m_second < rhs.m_second; - } -``` - -En la clase EdgeKey en /core/include/dsr/core/topics/IDLGraph.hpp - -```cpp - - eProsima_user_DllExport bool operator<( - const EdgeKey &rhs) const - { - if (m_to < rhs.m_to) - return true; - if (rhs.m_to < m_to) - return false; - return m_type < rhs.m_type; - } -``` - diff --git a/tests/graph/rt_timestamp.cpp b/tests/graph/rt_timestamp.cpp index 47828cd0..60bf3677 100644 --- a/tests/graph/rt_timestamp.cpp +++ b/tests/graph/rt_timestamp.cpp @@ -42,7 +42,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { auto edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -56,7 +56,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -70,7 +70,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -84,7 +84,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -97,7 +97,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -111,7 +111,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -124,7 +124,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -138,7 +138,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; @@ -151,7 +151,7 @@ TEST_CASE("RT api timestamp", "[GRAPH][RT]") { edge_rt = rt->get_edge_RT(n, *r2); REQUIRE(edge_rt.has_value()); - std::cout << "IDL::EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) + std::cout << "EdgeAttribs[" << edge_rt->type() << ", from:" << std::to_string(edge_rt->from()) << "-> to:" << std::to_string(edge_rt->to()) << " Attribs:["; for (const auto &v : edge_rt->attrs()) std::cout << v.first << ":" << v.second << " - \n"; From ba0263bf06e171505dc2a571abc7dc59500e043d Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sun, 19 Apr 2026 17:54:17 +0200 Subject: [PATCH 04/38] fix: unsynchronized rad to graph in delete_node --- api/dsr_api.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 89787854..9b83d207 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -454,8 +454,8 @@ bool DSRGraph::delete_node(const std::string &name) { id = get_id_from_name(name); if (id.has_value()) { - node_signal = get_(*id); std::unique_lock lock(_mutex); + node_signal = get_(*id); std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id.value()); } else { return false; From d98412a111b18cda124b7e500c992b98f8fc14f1 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sun, 19 Apr 2026 17:54:50 +0200 Subject: [PATCH 05/38] fix: incorrect vector initialization in get_connected_agents --- api/include/dsr/api/dsr_api.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 654d7a5c..ebe49646 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -558,7 +558,8 @@ namespace DSR std::vector get_connected_agents() { std::unique_lock lck(participant_set_mutex); - std::vector ret_vec(participant_set.size()); + std::vector ret_vec; + ret_vec.reserve(participant_set.size()); for (auto &[k, _]: participant_set) { ret_vec.emplace_back(k); From ccc7e5eff7bd365c204c2285fe10e8cf3a9641ee Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sun, 19 Apr 2026 18:34:15 +0200 Subject: [PATCH 06/38] perf: avoid full node copies when accessing only attributes avoid second node copy in delete_node methods --- api/dsr_api.cpp | 49 ++++++++++++++----------- api/dsr_rt_api.cpp | 36 +++++++++++------- api/include/dsr/api/dsr_api.h | 13 +++---- core/include/dsr/core/crdt/delta_crdt.h | 4 ++ 4 files changed, 59 insertions(+), 43 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 9b83d207..5b9cd96b 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -191,8 +191,7 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional id = get_id_from_name(name); if (id.has_value()) { - std::optional n = get_(id.value()); - if (n.has_value()) return Node(std::move(n.value())); + if (const auto* n = get_node_ptr_(id.value()); n != nullptr) return Node(*n); } return {}; } @@ -200,8 +199,7 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional DSRGraph::get_node(uint64_t id) { std::shared_lock lock(_mutex); - std::optional n = get_(id); - if (n.has_value()) return Node(std::move(n.value())); + if (const auto* n = get_node_ptr_(id); n != nullptr) return Node(*n); return {}; } @@ -398,16 +396,13 @@ template bool DSRGraph::update_node(DSR::Node&&); std::tuple, std::optional, std::vector> -DSRGraph::delete_node_(uint64_t id) { +DSRGraph::delete_node_(uint64_t id, const CRDTNode &node) { std::vector deleted_edges; std::vector delta_vec; - //Get and remove node. - auto node = get_(id); - if (!node.has_value()) return make_tuple(false, deleted_edges, std::nullopt, delta_vec); // Delete all edges from this node. - for (const auto &v : node.value().fano()) { + for (const auto &v : node.fano()) { deleted_edges.emplace_back(v.second.read_reg()); } // Get remove delta. @@ -432,7 +427,7 @@ DSRGraph::delete_node_(uint64_t id) { update_maps_edge_delete(from, id, type); } } - update_maps_node_delete(id, node.value()); + update_maps_node_delete(id, node); return make_tuple(true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)); @@ -450,13 +445,16 @@ bool DSRGraph::delete_node(const std::string &name) std::optional deleted_node; std::vector delta_vec; std::optional node_signal; + std::optional node_snapshot; std::optional id = {}; { id = get_id_from_name(name); if (id.has_value()) { std::unique_lock lock(_mutex); - node_signal = get_(*id); - std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id.value()); + node_snapshot = get_(*id); + if (!node_snapshot.has_value()) return false; + node_signal = Node(*node_snapshot); + std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id.value(), *node_snapshot); } else { return false; } @@ -489,11 +487,14 @@ bool DSRGraph::delete_node(uint64_t id) std::vector deleted_edges; std::optional deleted_node; std::optional node_signal; + std::optional node_snapshot; std::vector delta_vec; { - node_signal = get_(id); std::unique_lock lock(_mutex); - std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id); + node_snapshot = get_(id); + if (!node_snapshot.has_value()) return false; + node_signal = Node(*node_snapshot); + std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id, *node_snapshot); } if (result) { @@ -531,7 +532,7 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) { std::optional n = get_(id); if (n.has_value()) - nodes_.emplace_back(std::move(n.value())); + nodes_.emplace_back(std::move(*n)); } } return nodes_; @@ -573,7 +574,7 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector n = get_(id); if (n.has_value()) - nodes_.emplace_back(std::move(n.value())); + nodes_.emplace_back(std::move(*n)); } } } @@ -894,13 +895,18 @@ std::map DSRGraph::getCopy() const ////////////////////////////////////////////////////////////////////////////// std::optional DSRGraph::get_(uint64_t id) +{ + if (const auto* node = get_node_ptr_(id); node != nullptr) + return std::make_optional(*node); + return {}; +} + +const CRDTNode* DSRGraph::get_node_ptr_(uint64_t id) const { auto it = nodes.find(id); if (it != nodes.end() and !it->second.empty()) - { - return std::make_optional(it->second.read_reg()); - } - return {}; + return &it->second.read_reg(); + return nullptr; } std::optional DSRGraph::get_node_level(const Node &n) @@ -919,8 +925,7 @@ std::optional DSRGraph::get_parent_node(const Node &n) if (p.has_value()) { std::shared_lock lock(_mutex); - auto tmp = get_(p.value()); - if (tmp.has_value()) return Node(tmp.value()); + if (const auto* tmp = get_node_ptr_(p.value()); tmp != nullptr) return Node(*tmp); } return {}; } diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index a449fe72..2276a5f1 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -395,11 +395,15 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector node1_insert; std::optional node1_update; std::optional node2; - std::optional to_n; + std::optional to_n_mut; + std::optional to_n_id; + std::optional to_n_type; { std::unique_lock lock(G->_mutex); - if (G->nodes.contains(to)) + if (const auto* to_n = G->get_node_ptr_(to); to_n != nullptr) { + to_n_id = to_n->id(); + to_n_type = to_n->type(); CRDTEdge e; if (HISTORY_SIZE <= 0) { @@ -529,29 +533,33 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectorsecond.write(std::move(timestamps)); } - to_n = G->get_(to).value(); - if (auto x = G->get_crdt_attrib_by_name(to_n.value()); x.has_value()) + const auto ensure_mutable_to_n = [&]() -> CRDTNode& { + if (!to_n_mut.has_value()) to_n_mut = *to_n; + return to_n_mut.value(); + }; + + if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) { if (x.value() != n.id()) { - no_send = !G->modify_attrib_local(to_n.value(), n.id()); + no_send = !G->modify_attrib_local(ensure_mutable_to_n(), n.id()); } } else { - no_send = !G->add_attrib_local(to_n.value(), n.id()); + no_send = !G->add_attrib_local(ensure_mutable_to_n(), n.id()); } - if (auto x = G->get_crdt_attrib_by_name(to_n.value()); x.has_value()) + if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) { if (x.value() != G->get_node_level(n).value() + 1) { - no_send = !G->modify_attrib_local(to_n.value(), G->get_node_level(n).value() + 1 ); + no_send = !G->modify_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); } } else { - no_send = !G->add_attrib_local(to_n.value(), G->get_node_level(n).value() + 1 ); + no_send = !G->add_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); } //Check if RT edge exist. @@ -559,14 +567,14 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector insert edge, update to-node attrs std::tie(r1, node1_insert, std::ignore) = G->insert_or_assign_edge_(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n.value())); + if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n_mut.value())); } else { //Update -> update edge attrs, update to-node attrs std::tie(r1, std::ignore, node1_update) = G->insert_or_assign_edge_(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n.value())); + if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n_mut.value())); } if (!r1) @@ -578,7 +586,7 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectorid()) + " in G in insert_or_assign_edge_RT() " + + "Could not insert Node " + std::to_string(to_n_id.value()) + " in G in insert_or_assign_edge_RT() " + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); } } else @@ -604,8 +612,8 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectoremitter.update_edge_signal(n.id(), to, "RT", SignalInfo{ G->agent_id }); if (!no_send) { - G->emitter.update_node_signal(to_n->id(), to_n->type(), SignalInfo{ G->agent_id }); - G->emitter.update_node_attr_signal(to_n->id(), {"level", "parent"}, SignalInfo{ G->agent_id }); + G->emitter.update_node_signal(to_n_id.value(), to_n_type.value(), SignalInfo{ G->agent_id }); + G->emitter.update_node_attr_signal(to_n_id.value(), {"level", "parent"}, SignalInfo{ G->agent_id }); } } } diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index ebe49646..cf4412e8 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -212,9 +212,8 @@ namespace DSR { using ret_type = std::remove_cvref_t>; std::shared_lock lock(_mutex); - std::optional n = get_(id); - if (n.has_value()) { - auto tmp = get_attrib_by_name(n.value()); + if (const auto* n = get_node_ptr_(id); n != nullptr) { + auto tmp = get_attrib_by_name(*n); if (tmp.has_value()) { if constexpr(is_reference_wrapper::value) { @@ -256,12 +255,11 @@ namespace DSR { using ret_type = std::tuple>> ...>; std::shared_lock lock(_mutex); - std::optional node = get_(id); - if (node.has_value()) + if (const auto* node = get_node_ptr_(id); node != nullptr) { auto get_by_name = [&](n* dummy) -> std::optional>> { - auto tmp = get_attrib_by_name(node.value()); + auto tmp = get_attrib_by_name(*node); if (tmp.has_value()) { if constexpr(is_reference_wrapper::value) { @@ -657,11 +655,12 @@ namespace DSR ////////////////////////////////////////////////////////////////////////// // Non-blocking graph operations ////////////////////////////////////////////////////////////////////////// + const CRDTNode* get_node_ptr_(uint64_t id) const; std::optional get_(uint64_t id); std::optional get_edge_(uint64_t from, uint64_t to, const std::string &key); std::tuple> insert_node_(CRDTNode &&node); std::tuple> update_node_(CRDTNode &&node); - std::tuple, std::optional, std::vector> delete_node_(uint64_t id); + std::tuple, std::optional, std::vector> delete_node_(uint64_t id, const CRDTNode &node); std::optional delete_edge_(uint64_t from, uint64_t t, const std::string &key); std::tuple, std::optional> insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to); diff --git a/core/include/dsr/core/crdt/delta_crdt.h b/core/include/dsr/core/crdt/delta_crdt.h index 1ddb6f62..90efedd9 100644 --- a/core/include/dsr/core/crdt/delta_crdt.h +++ b/core/include/dsr/core/crdt/delta_crdt.h @@ -527,6 +527,10 @@ class mvreg : public ISerializable> // Multi-value register, Optimize return dk.ds.empty(); } + bool empty() const { + return dk.ds.empty(); + } + friend std::ostream &operator<<(std::ostream &output, const mvreg &o) { output << "MVReg:" << o.dk; return output; From 59e9b598e1c1a8a1ba29a97e142a745497116a6e Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sun, 19 Apr 2026 23:47:55 +0200 Subject: [PATCH 07/38] tracing: add initial support for perfetto/tracy --- .gitignore | 3 +- CMakeLists.txt | 4 + PROFILING.md | 101 ++++++++ api/CMakeLists.txt | 2 + api/dsr_api.cpp | 298 ++++++++++++++++-------- api/dsr_rt_api.cpp | 6 + benchmarks/CMakeLists.txt | 1 + cmake/profiling.cmake | 160 +++++++++++++ core/CMakeLists.txt | 5 +- core/include/dsr/core/crdt/delta_crdt.h | 7 + core/include/dsr/core/profiling.h | 73 ++++++ core/include/threadpool/threadpool.h | 182 +++++++++++++++ core/profiling.cpp | 154 ++++++++++++ tests/CMakeLists.txt | 1 + 14 files changed, 896 insertions(+), 101 deletions(-) create mode 100644 PROFILING.md create mode 100644 cmake/profiling.cmake create mode 100644 core/include/dsr/core/profiling.h create mode 100644 core/include/threadpool/threadpool.h create mode 100644 core/profiling.cpp diff --git a/.gitignore b/.gitignore index e17a9996..b5710abf 100644 --- a/.gitignore +++ b/.gitignore @@ -10,4 +10,5 @@ experiment/ **/_pychache__ .artifacts/ .vscode/* -.claude/* \ No newline at end of file +.claude/* +build-* \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 5d512c01..449fc3cc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -5,6 +5,8 @@ project(dsr LANGUAGES CXX) include(GNUInstallDirs) +include(FetchContent) +find_package(Threads REQUIRED) set(CMAKE_EXPORT_COMPILE_COMMANDS ON) @@ -21,6 +23,8 @@ if (TSAN) add_link_options(-fsanitize=thread) endif() +include(cmake/profiling.cmake) + add_definitions(-I/usr/include/x86_64-linux-gnu/qt6/QtOpenGLWidgets/) include_directories(/home/robocomp/robocomp/classes) diff --git a/PROFILING.md b/PROFILING.md new file mode 100644 index 00000000..7a307710 --- /dev/null +++ b/PROFILING.md @@ -0,0 +1,101 @@ +# Profiling Backends + +The repository supports multiple profiling backends through CMake. + +## Backend Selection + +Use: + +```bash +-DCORTEX_PROFILING_BACKEND=NONE +-DCORTEX_PROFILING_BACKEND=TRACY +-DCORTEX_PROFILING_BACKEND=PERFETTO +``` + +### `NONE` + +No profiling backend is enabled. + +### `TRACY` + +Uses the interactive Tracy client/profiler flow. + +If `CORTEX_ENABLE_TRACY` is not explicitly configured, the build falls back to the `DEFAULT` Tracy preset. + +What you need: + +- an instrumented build with `-DCORTEX_PROFILING_BACKEND=TRACY` +- the Tracy Profiler GUI +- a live connection between the running process and the profiler + +Important: + +- Tracy is mainly an interactive workflow +- traces are not written automatically to disk by the client +- if you want a saved trace, connect with the profiler and save the session from the UI + +Typical usage: + +```bash +cmake -S . -B build \ + -DWITH_TESTS=ON \ + -DCORTEX_PROFILING_BACKEND=TRACY \ + -DCORTEX_ENABLE_TRACY=DEFAULT +cmake --build build --target tests +./build/tests/tests "[SYNCHRONIZATION][GRAPH]" +``` + +Tracy options are OFF, ON, DEFAULT, MEDIUM, EXTRA, WSL, WSL_EXTRA + +### `PERFETTO` + +Uses Perfetto's in-process backend and writes an offline trace file automatically at process exit. + +What you need: + +- an instrumented build with `-DCORTEX_PROFILING_BACKEND=PERFETTO` +- a generated `.pftrace` file +- either the web UI at `https://ui.perfetto.dev/` or another Perfetto-compatible viewer + +Typical usage: + +```bash +cmake -S . -B build-perfetto \ + -DWITH_TESTS=ON \ + -DCORTEX_PROFILING_BACKEND=PERFETTO +cmake --build build-perfetto --target tests +export CORTEX_PERFETTO_TRACE_FILE=.artifacts/output.pftrace +./build-perfetto/tests/tests "[SYNCHRONIZATION][GRAPH]" +``` + +The trace file path can be overridden with: + +```bash +export CORTEX_PERFETTO_TRACE_FILE=/path/to/output.pftrace +``` + +If not set, the default output path is: + +```text +.artifacts/perfetto/--.pftrace +``` + +relative to the process working directory. + +The generated trace file can be opened with: + +- https://ui.perfetto.dev/ +- the standalone Perfetto UI / trace processor tools + +Recommended flow on this repository: + +1. Run the instrumented binary or test. +2. Wait for the process to exit cleanly. +3. Open `https://ui.perfetto.dev/`. +4. Use `Open trace file` and load the `.pftrace`. + +Notes: + +- Perfetto is the better fit for offline captures that you want to inspect later. +- The trace is flushed on shutdown, so if the process is killed hard you may lose the file. +- The current instrumentation covers graph, RT, CRDT, bootstrap, and synchronization paths. diff --git a/api/CMakeLists.txt b/api/CMakeLists.txt index 074d55f5..0ee45a4f 100644 --- a/api/CMakeLists.txt +++ b/api/CMakeLists.txt @@ -55,6 +55,8 @@ target_link_libraries(dsr_api Eigen3::Eigen ) +target_link_libraries(dsr_api PRIVATE cortex_profiling) + target_include_directories(dsr_api PUBLIC # Headers of DSR Core diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 5b9cd96b..a7e1032a 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -5,6 +5,7 @@ #include "dsr/api/dsr_graph_settings.h" #include "dsr/core/types/internal_types.h" #include "dsr/core/types/translator.h" +#include "dsr/core/profiling.h" #include "dsr/api/dsr_signal_emitter.h" #include #include @@ -55,85 +56,100 @@ DSRGraph::DSRGraph(GraphSettings settings) : agent_id(settings.agent_id), agent_name(std::move(settings.graph_name)), copy(false), - tp(settings.theradpool_threads), - tp_delta_attr(settings.attribute_threadpool_threads), + tp(settings.theradpool_threads, "join"), + tp_delta_attr(settings.attribute_threadpool_threads, "attr"), same_host(settings.same_host), generator(settings.agent_id), log_level(settings.log_level) { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph"); qDebug() << "Agent name: " << QString::fromStdString(agent_name); - utils = std::make_unique(this); - if (settings.signal_mode == SignalMode::QT) { - set_qt_signals(); - } else { - set_queued_signals(); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph setup utils/signals"); + utils = std::make_unique(this); + if (settings.signal_mode == SignalMode::QT) { + set_qt_signals(); + } else { + set_queued_signals(); + } } // RTPS Create participant - auto[suc, participant_handle] = dsrparticipant.init(agent_id, agent_name, settings.same_host, - ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph, - eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, - const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) - { - if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT) - { - std::unique_lock lck(participant_set_mutex); - std::cout << "Participant matched [" << info.participant_name.to_string() << "]" << std::endl; - graph->participant_set.emplace(info.participant_name.to_string(), false); - } - else if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::REMOVED_PARTICIPANT || - status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DROPPED_PARTICIPANT) - { - std::unique_lock lck(participant_set_mutex); - graph->participant_set.erase(info.participant_name.to_string()); - std::cout << "Participant unmatched [" << info.participant_name.to_string() << "]" << std::endl; - // Participant name is "Participant_ ( )" which doesn't - // match the DSR node name " ". Find the agent node by - // its agent_id attribute instead. - const std::string pname = info.participant_name.to_string(); - const std::string prefix = "Participant_"; - bool deleted = false; - if (pname.size() > prefix.size() && pname.substr(0, prefix.size()) == prefix) { - try { - uint32_t peer_id = static_cast(std::stoul(pname.substr(prefix.size()))); - for (auto& node : graph->get_nodes_by_type("agent")) { - auto attr = graph->get_attrib_by_name(node); - if (attr.has_value() && attr.value() == peer_id) { - graph->delete_node(node.id()); - deleted = true; - break; - } - } - } catch (...) {} - } - if (!deleted) - graph->delete_node(pname); - } - }), settings.domain_id); + auto participant_init_result = [&]() { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init participant"); + return dsrparticipant.init(agent_id, agent_name, settings.same_host, + ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph, + eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, + const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) + { + CORTEX_PROFILE_ZONE_N("DSRGraph::participant discovery callback"); + if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT) + { + std::unique_lock lck(participant_set_mutex); + std::cout << "Participant matched [" << info.participant_name.to_string() << "]" << std::endl; + graph->participant_set.emplace(info.participant_name.to_string(), false); + } + else if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::REMOVED_PARTICIPANT || + status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DROPPED_PARTICIPANT) + { + std::unique_lock lck(participant_set_mutex); + graph->participant_set.erase(info.participant_name.to_string()); + std::cout << "Participant unmatched [" << info.participant_name.to_string() << "]" << std::endl; + // Participant name is "Participant_ ( )" which doesn't + // match the DSR node name " ". Find the agent node by + // its agent_id attribute instead. + const std::string pname = info.participant_name.to_string(); + const std::string prefix = "Participant_"; + bool deleted = false; + if (pname.size() > prefix.size() && pname.substr(0, prefix.size()) == prefix) { + try { + uint32_t peer_id = static_cast(std::stoul(pname.substr(prefix.size()))); + for (auto& node : graph->get_nodes_by_type("agent")) { + auto attr = graph->get_attrib_by_name(node); + if (attr.has_value() && attr.value() == peer_id) { + graph->delete_node(node.id()); + deleted = true; + break; + } + } + } catch (...) {} + } + if (!deleted) + graph->delete_node(pname); + } + }), settings.domain_id); + }(); + auto[suc, participant_handle] = std::move(participant_init_result); // RTPS Initialize publisher with general topic - auto [res, pub, writer] = dsrpub_node.init(participant_handle, dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id()); - auto [res2, pub2, writer2] = dsrpub_node_attrs.init(participant_handle, dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id()); - - auto [res3, pub3, writer3] = dsrpub_edge.init(participant_handle, dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id()); - auto [res4, pub4, writer4] = dsrpub_edge_attrs.init(participant_handle, dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id()); - - auto [res5, pub5, writer5] = dsrpub_graph_request.init(participant_handle, dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id()); - auto [res6, pub6, writer6] = dsrpub_request_answer.init(participant_handle, dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id()); + auto [res, pub, writer, res2, pub2, writer2, res3, pub3, writer3, res4, pub4, writer4, res5, pub5, writer5, res6, pub6, writer6] = [&]() { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init publishers"); + auto [r1, p1, w1] = dsrpub_node.init(participant_handle, dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id()); + auto [r2, p2, w2] = dsrpub_node_attrs.init(participant_handle, dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id()); + auto [r3, p3, w3] = dsrpub_edge.init(participant_handle, dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id()); + auto [r4, p4, w4] = dsrpub_edge_attrs.init(participant_handle, dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id()); + auto [r5, p5, w5] = dsrpub_graph_request.init(participant_handle, dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id()); + auto [r6, p6, w6] = dsrpub_request_answer.init(participant_handle, dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id()); + return std::tuple{r1, p1, w1, r2, p2, w2, r3, p3, w3, r4, p4, w4, r5, p5, w5, r6, p6, w6}; + }(); - dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), {pub, writer}); - dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), {pub2, writer2}); - dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), {pub3, writer3}); - dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), {pub4, writer4}); - dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), {pub5, writer5}); - dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), {pub6, writer6}); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph register publishers"); + dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), {pub, writer}); + dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), {pub2, writer2}); + dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), {pub3, writer3}); + dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), {pub4, writer4}); + dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), {pub5, writer5}); + dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), {pub6, writer6}); + } // RTPS Initialize comms threads if (!settings.input_file.empty()) { try { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph load input graph"); read_from_json_file(settings.input_file); qDebug() << __FUNCTION__ << "Warning, graph read from file " << QString::fromStdString(settings.input_file); } @@ -147,7 +163,10 @@ DSRGraph::DSRGraph(GraphSettings settings) : } else { - start_subscription_threads(); // regular subscription to deltas + { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph bootstrap subscriptions"); + start_subscription_threads(); // regular subscription to deltas + } auto [response, repeated] = start_fullgraph_request_thread(); // for agents that want to request the graph for other agent if(!response) @@ -186,6 +205,7 @@ DSRGraph::~DSRGraph() std::optional DSRGraph::get_node(const std::string &name) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(name)"); std::shared_lock lock(_mutex); if (name.empty()) return {}; std::optional id = get_id_from_name(name); @@ -198,6 +218,7 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional DSRGraph::get_node(uint64_t id) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(id)"); std::shared_lock lock(_mutex); if (const auto* n = get_node_ptr_(id); n != nullptr) return Node(*n); return {}; @@ -205,6 +226,7 @@ std::optional DSRGraph::get_node(uint64_t id) std::tuple> DSRGraph::insert_node_(CRDTNode &&node) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_node_"); if (!deleted.contains(node.id())) { if (auto it = nodes.find(node.id()); it != nodes.end() and not it->second.empty() and it->second.read_reg() == node) @@ -213,9 +235,15 @@ std::tuple> DSRGraph::insert_node_(CRDTNo } uint64_t id = node.id(); - update_maps_node_insert(id, node); - mvreg delta = nodes[id].write(std::move(node)); - + { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_ update maps"); + update_maps_node_insert(id, node); + } + mvreg delta; + { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_ mvreg write"); + delta = nodes[id].write(std::move(node)); + } return {true, CRDTNode_to_Msg(agent_id, id, std::move(delta))}; } return {false, {}}; @@ -228,6 +256,7 @@ std::optional DSRGraph::insert_node(No &&node) std::optional delta; bool inserted = false; { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph merge phase"); std::unique_lock lock(_mutex); std::shared_lock lck_cache(_mutex_cache_maps); uint64_t new_node_id = generator.generate(); @@ -305,7 +334,7 @@ template std::optional DSRGraph::insert_node_with_id(DSR: std::tuple> DSRGraph::update_node_(CRDTNode &&node) { - + CORTEX_PROFILE_ZONE_N("DSRGraph::update_node_"); if (!deleted.contains(node.id())) { auto nit = nodes.find(node.id()); @@ -348,6 +377,7 @@ template bool DSRGraph::update_node(No &&node) requires (std::is_same_v, DSR::Node>) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node"); bool updated = false; std::optional vec_node_attr; @@ -397,6 +427,7 @@ template bool DSRGraph::update_node(DSR::Node&&); std::tuple, std::optional, std::vector> DSRGraph::delete_node_(uint64_t id, const CRDTNode &node) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node_"); std::vector deleted_edges; std::vector delta_vec; @@ -439,6 +470,7 @@ bool DSRGraph::delete_node(const DSR::Node &node) bool DSRGraph::delete_node(const std::string &name) { + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(name)"); bool result = false; std::vector deleted_edges; @@ -482,6 +514,7 @@ bool DSRGraph::delete_node(const std::string &name) bool DSRGraph::delete_node(uint64_t id) { + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(id)"); bool result = false; std::vector deleted_edges; @@ -643,7 +676,7 @@ std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::st std::tuple, std::optional> DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) { - + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_or_assign_edge_"); std::optional delta_edge; std::optional delta_attrs; @@ -693,6 +726,7 @@ template bool DSRGraph::insert_or_assign_edge(Ed &&attrs) requires (std::is_same_v, DSR::Edge>) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge"); bool result = false; std::optional delta_edge; std::optional delta_attrs; @@ -1054,6 +1088,7 @@ bool DSRGraph::empty(const uint64_t &id) void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_node"); std::optional maybe_deleted_node = {}; try { @@ -1157,6 +1192,7 @@ void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) std::string node_type_snapshot; std::vector> from_edges_snapshot; { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node crdt merge"); std::unique_lock lock(_mutex); if (!deleted.contains(id)) { joined = true; @@ -1187,6 +1223,7 @@ void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) uint32_t msg_agent_id = mvreg.agent_id; if (joined) { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node signal emit"); if (signal) { DSR_LOG_DEBUG("[JOIN_NODE] node inserted/updated:", id, node_type_snapshot); emitter.update_node_signal(id, node_type_snapshot, SignalInfo{ msg_agent_id }); @@ -1240,6 +1277,7 @@ void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) bool DSRGraph::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg && delta) { + CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_edge"); const bool d_empty = delta.empty(); auto &node = nodes.at(from).read_reg(); node.fano()[{to, type}].join(std::move(delta)); @@ -1256,6 +1294,7 @@ bool DSRGraph::process_delta_edge(uint64_t from, uint64_t to, const std::string& void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_edge"); try { if (!protocol_version_matches(log_level, "DSR_EDGE", mvreg.protocol_version)) { return; @@ -1304,6 +1343,7 @@ void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) uint32_t msg_agent_id = mvreg.agent_id; std::optional deleted_edge; { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge crdt merge"); auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); deleted_edge = get_edge_(from, to, type); @@ -1368,6 +1408,7 @@ void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) } if (joined) { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge signal emit"); if (signal) { DSR_LOG_DEBUG("[JOIN_EDGE] add edge:", from, to, type); emitter.update_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); @@ -1389,6 +1430,7 @@ void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) void DSRGraph::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg && attr) { + CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_node_attr"); const bool d_empty = attr.empty(); auto &n = nodes.at(id).read_reg(); n.attrs()[att_name].join(std::move(attr)); @@ -1400,7 +1442,7 @@ void DSRGraph::process_delta_node_attr(uint64_t id, const std::string& att_name, std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg) { - + CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_node_attr"); try { if (!protocol_version_matches(log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { return std::nullopt; @@ -1411,6 +1453,7 @@ std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg uint64_t timestamp = mvreg.timestamp; DSR_LOG_DEBUG("[JOIN_NODE_ATTR] node:", id, "attr:", att_name); { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node_attr crdt merge"); auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); //Check if the node where we are joining the edge exist. @@ -1455,6 +1498,7 @@ std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg void DSRGraph::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg && attr) { + CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_edge_attr"); const bool d_empty = attr.empty(); auto &n = nodes.at(from).read_reg().fano().at({to, type}).read_reg(); n.attrs()[att_name].join(std::move(attr)); @@ -1467,6 +1511,7 @@ void DSRGraph::process_delta_edge_attr(uint64_t from, uint64_t to, const std::st std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_edge_attr"); try { if (!protocol_version_matches(log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { return std::nullopt; @@ -1480,6 +1525,7 @@ std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg DSR_LOG_DEBUG("[JOIN_EDGE_ATTR] edge:", from, to, type, "attr:", att_name); { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge_attr crdt merge"); auto crdt_delta = std::move(mvreg.dk); std::unique_lock lock(_mutex); //Check if the node where we are joining the edge exist. @@ -1525,6 +1571,7 @@ std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph"); if (!protocol_version_matches(log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { return; } @@ -1641,7 +1688,9 @@ void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) } } - for (auto &[signal, id, type, nd, current_nd] : updates) + { + CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph emit phase"); + for (auto &[signal, id, type, nd, current_nd] : updates) if (signal) { //check what change is joined — use the snapshot captured inside the lock, //not nodes[id], which races with concurrent insert_node_/update_node calls. @@ -1670,22 +1719,26 @@ void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); } } + } } std::pair DSRGraph::start_fullgraph_request_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::start_fullgraph_request_thread"); return fullgraph_request_thread(); } void DSRGraph::start_fullgraph_server_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::start_fullgraph_server_thread"); auto fullgraph_thread = std::thread(&DSRGraph::fullgraph_server_thread, this); if (fullgraph_thread.joinable()) fullgraph_thread.join(); } void DSRGraph::start_subscription_threads() { + CORTEX_PROFILE_ZONE_N("DSRGraph::start_subscription_threads"); auto delta_node_thread = std::thread(&DSRGraph::node_subscription_thread, this); auto delta_edge_thread = std::thread(&DSRGraph::edge_subscription_thread, this); auto delta_node_attrs_thread = std::thread(&DSRGraph::node_attrs_subscription_thread, this); @@ -1699,6 +1752,7 @@ void DSRGraph::start_subscription_threads() std::map DSRGraph::Map() { + CORTEX_PROFILE_ZONE_N("DSRGraph::Map"); std::shared_lock lock(_mutex); std::map m; for (auto &kv : nodes) { @@ -1739,10 +1793,13 @@ void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::f void DSRGraph::node_subscription_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread setup"); auto name = __FUNCTION__; auto lambda_general_topic = [&, name = name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); try { while (true) { @@ -1782,10 +1839,13 @@ void DSRGraph::node_subscription_thread() void DSRGraph::edge_subscription_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread setup"); auto name = __FUNCTION__; auto lambda_general_topic = [&, name = name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); try { while (true) { @@ -1817,10 +1877,13 @@ void DSRGraph::edge_subscription_thread() void DSRGraph::edge_attrs_subscription_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread setup"); auto name = __FUNCTION__; auto lambda_general_topic = [&, name = name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); try { while (true) { @@ -1836,6 +1899,7 @@ void DSRGraph::edge_attrs_subscription_thread() if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); if (samples.vec.empty()) return; auto from = samples.vec.at(0).from_node; @@ -1844,26 +1908,33 @@ void DSRGraph::edge_attrs_subscription_thread() auto sample_agent_id = samples.vec.at(0).agent_id; std::vector>> futures; - - for (auto &&sample: samples.vec) { - if (!ignored_attributes.contains(sample.attr_name)) { - futures.emplace_back(tp.spawn_task_waitable([this, sample = std::move(sample)]() mutable { - return join_delta_edge_attr(std::move(sample)); - })); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread join batch"); + for (auto &&sample: samples.vec) { + if (!ignored_attributes.contains(sample.attr_name)) { + futures.emplace_back(tp.spawn_task_waitable([this, sample = std::move(sample)]() mutable { + return join_delta_edge_attr(std::move(sample)); + })); + } } } std::vector sig (futures.size()); - for (auto &f: futures) { - auto opt_str = f.get(); - if (opt_str.has_value()) - sig.emplace_back(std::move(opt_str.value())); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread wait futures"); + for (auto &f: futures) + { + auto opt_str = f.get(); + if (opt_str.has_value()) + sig.emplace_back(std::move(opt_str.value())); + } } - - emitter.update_edge_attr_signal(from, to, type, sig, SignalInfo{sample_agent_id}); - emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread signal emit"); + emitter.update_edge_attr_signal(from, to, type, sig, SignalInfo{sample_agent_id}); + emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); + } }); } @@ -1886,10 +1957,13 @@ void DSRGraph::edge_attrs_subscription_thread() void DSRGraph::node_attrs_subscription_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread setup"); auto name = __FUNCTION__; auto lambda_general_topic = [this, name = name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); try { while (true) { @@ -1904,6 +1978,7 @@ void DSRGraph::node_attrs_subscription_thread() } if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); if (samples.vec.empty()) return; @@ -1915,26 +1990,34 @@ void DSRGraph::node_attrs_subscription_thread() if (auto itn = nodes.find(id); itn != nodes.end()) type = itn->second.read_reg().type() ; } std::vector>> futures; - for (auto &&s: samples.vec) { - if (!ignored_attributes.contains(s.attr_name)) { - futures.emplace_back(tp.spawn_task_waitable([this, samp{std::move(s)}]() mutable { - auto f = join_delta_node_attr(std::move(samp)); - return f; - })); - + { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread join batch"); + for (auto &&s: samples.vec) { + if (!ignored_attributes.contains(s.attr_name)) { + futures.emplace_back(tp.spawn_task_waitable([this, samp{std::move(s)}]() mutable { + auto f = join_delta_node_attr(std::move(samp)); + return f; + })); + } } } std::vector sig (futures.size()); - for (auto &f: futures) { - auto opt_str = f.get(); - if (opt_str.has_value()) - sig.emplace_back(std::move(opt_str.value())); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread wait futures"); + for (auto &f: futures) + { + auto opt_str = f.get(); + if (opt_str.has_value()) + sig.emplace_back(std::move(opt_str.value())); + } } - emitter.update_node_attr_signal(id, sig, SignalInfo{sample_agent_id}); - emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread signal emit"); + emitter.update_node_attr_signal(id, sig, SignalInfo{sample_agent_id}); + emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); + } }); } } @@ -1955,8 +2038,11 @@ void DSRGraph::node_attrs_subscription_thread() void DSRGraph::fullgraph_server_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread setup"); auto lambda_graph_request = [&](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_server"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread callback"); while (true) { eprosima::fastdds::dds::SampleInfo m_info; @@ -1993,7 +2079,10 @@ void DSRGraph::fullgraph_server_thread() DSR::OrMap mp; mp.id = static_cast(graph->get_agent_id()); mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; - mp.m = graph->Map(); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread build full graph"); + mp.m = graph->Map(); + } dsrpub_request_answer.write(&mp); qDebug() << "Full graph written"; @@ -2014,10 +2103,13 @@ void DSRGraph::fullgraph_server_thread() std::pair DSRGraph::fullgraph_request_thread() { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread"); std::atomic sync{false}; std::atomic repeated{false}; auto lambda_request_answer = [&](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); while (true) { eprosima::fastdds::dds::SampleInfo m_info; @@ -2034,6 +2126,7 @@ std::pair DSRGraph::fullgraph_request_thread() << " whith " << sample.m.size() << " elements"; tp.spawn_task([this, s = std::move(sample)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); join_full_graph(std::move(s)); }); qDebug() << "Synchronized."; @@ -2057,7 +2150,10 @@ std::pair DSRGraph::fullgraph_request_thread() dsrpub_request_answer_call, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), {sub, reader}); - std::this_thread::sleep_for(300ms); // NEEDED ? + { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread initial wait"); + std::this_thread::sleep_for(300ms); // NEEDED ? + } qDebug() << " Requesting the complete graph "; @@ -2065,12 +2161,16 @@ std::pair DSRGraph::fullgraph_request_thread() gr.from = dsrparticipant.getParticipant()->get_qos().name().to_string(); gr.id = static_cast(agent_id); gr.protocol_version = DSR::DSR_PROTOCOL_VERSION; - dsrpub_graph_request.write(&gr); + { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread send request"); + dsrpub_graph_request.write(&gr); + } bool timeout = false; std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); while (!sync and !timeout and !repeated) { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread wait loop"); std::this_thread::sleep_for(1000ms); std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); timeout = std::chrono::duration_cast(end - begin).count() > TIMEOUT * 3; @@ -2091,7 +2191,7 @@ std::pair DSRGraph::fullgraph_request_thread() ///// PRIVATE COPY ///////////////////////////////////////////////// -DSRGraph::DSRGraph(const DSRGraph &G) : agent_id(G.agent_id), copy(true), tp(1), generator(G.agent_id) +DSRGraph::DSRGraph(const DSRGraph &G) : agent_id(G.agent_id), copy(true), tp(1, "join-copy"), generator(G.agent_id) { std::shared_lock lock(_mutex); std::shared_lock lock_cache(_mutex_cache_maps); diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index 2276a5f1..b4f43c8b 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -2,6 +2,7 @@ #include #include #include +#include using namespace DSR; @@ -144,6 +145,7 @@ std::optional RT_API::get_edge_RT(const Node &n, uint64_t to, const std::s std::optional RT_API::get_RT_pose_from_parent(const Node &n, const std::string &edge_type) { + CORTEX_PROFILE_ZONE_N("RT_API::get_RT_pose_from_parent"); if( not DSR::DSRGraph::is_valid_edge_type(edge_type)) return {}; auto p = G->get_parent_node(n); @@ -170,6 +172,7 @@ std::optional RT_API::get_RT_pose_from_parent(const Node &n, const s std::optional RT_API::get_edge_RT_as_rtmat(const Edge &edge, std::uint64_t timestamp, TimeQuery time_query) { + CORTEX_PROFILE_ZONE_N("RT_API::get_edge_RT_as_rtmat"); auto r_o = G->get_attrib_by_name(edge); auto t_o = G->get_attrib_by_name(edge); auto head_o = G->get_attrib_by_name(edge); @@ -281,6 +284,7 @@ std::optional> RT_API::get_edge_RT_covariance(const std::optional RT_API::get_translation(const Node &n, uint64_t to, std::uint64_t timestamp, TimeQuery time_query) { + CORTEX_PROFILE_ZONE_N("RT_API::get_translation(node,to)"); if( auto edge = get_edge_RT(n, to); edge.has_value()) { auto t_o = G->get_attrib_by_name(edge.value()); @@ -361,11 +365,13 @@ std::optional> RT_API::get_covariance_matrix(uint64_ void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, const std::vector &trans, const std::vector &rot_euler, std::optional timestamp) { + CORTEX_PROFILE_ZONE_N("RT_API::insert_or_assign_edge_RT(copy)"); insert_or_assign_edge_RT_impl(n, to, trans, rot_euler, std::nullopt, timestamp); } void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, std::vector &&trans, std::vector &&rot_euler, std::optional timestamp) { + CORTEX_PROFILE_ZONE_N("RT_API::insert_or_assign_edge_RT(move)"); insert_or_assign_edge_RT_impl(n, to, std::move(trans), std::move(rot_euler), std::nullopt, timestamp); } diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index a72bfd77..9a307a99 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -102,6 +102,7 @@ target_link_libraries(dsr_benchmarks PRIVATE nanobench dsr_api dsr_core + cortex_profiling Qt6::Core Eigen3::Eigen fastdds diff --git a/cmake/profiling.cmake b/cmake/profiling.cmake new file mode 100644 index 00000000..86d3f927 --- /dev/null +++ b/cmake/profiling.cmake @@ -0,0 +1,160 @@ +# Profiling backend selection for the cortex library. +# Defines and populates the cortex_profiling INTERFACE target, which consumers +# link against to get the right compile definitions and libraries. +# +# Usage: +# cmake -DCORTEX_PROFILING_BACKEND=TRACY -DCORTEX_ENABLE_TRACY=WSL_EXTRA .. +# cmake -DCORTEX_PROFILING_BACKEND=PERFETTO .. + +set(CORTEX_PROFILING_BACKEND "NONE" CACHE STRING + "Profiling backend. Accepted values: NONE, TRACY, PERFETTO") +set(CORTEX_CALLSTACK_DEPTH "16" CACHE STRING + "Number of stack frames captured by CORTEX_PROFILE_ZONE_CS") +set_property(CACHE CORTEX_PROFILING_BACKEND PROPERTY STRINGS NONE TRACY PERFETTO) +string(TOUPPER "${CORTEX_PROFILING_BACKEND}" CORTEX_PROFILING_BACKEND_MODE) + +add_library(cortex_profiling INTERFACE) + +# ── Tracy ───────────────────────────────────────────────────────────────────── + +set(CORTEX_ENABLE_TRACY "OFF" CACHE STRING + "Tracy preset. Accepted values: OFF, ON, DEFAULT, MEDIUM, EXTRA, WSL, WSL_EXTRA") +set_property(CACHE CORTEX_ENABLE_TRACY PROPERTY STRINGS OFF ON DEFAULT MEDIUM EXTRA WSL WSL_EXTRA) +option(CORTEX_TRACY_ON_DEMAND "Enable Tracy on-demand connection mode" ON) +option(CORTEX_TRACY_CALLSTACK "Enable Tracy callstack capture" OFF) +option(CORTEX_TRACY_ONLY_LOCALHOST "Restrict Tracy connections to localhost" ON) +option(CORTEX_TRACY_NO_BROADCAST "Disable Tracy client broadcast discovery" ON) +string(TOUPPER "${CORTEX_ENABLE_TRACY}" CORTEX_TRACY_MODE) +set(CORTEX_TRACY_ENABLED OFF) + +# Allow CORTEX_ENABLE_TRACY to implicitly select the Tracy backend. +if (CORTEX_PROFILING_BACKEND_MODE STREQUAL "NONE") + if (NOT CORTEX_TRACY_MODE STREQUAL "OFF" AND + NOT CORTEX_TRACY_MODE STREQUAL "FALSE" AND + NOT CORTEX_TRACY_MODE STREQUAL "NO" AND + NOT CORTEX_TRACY_MODE STREQUAL "0") + set(CORTEX_PROFILING_BACKEND_MODE "TRACY") + endif() +endif() + +# If TRACY backend is explicit but CORTEX_ENABLE_TRACY was left at OFF, use DEFAULT preset. +if (CORTEX_PROFILING_BACKEND_MODE STREQUAL "TRACY" AND + (CORTEX_TRACY_MODE STREQUAL "OFF" OR + CORTEX_TRACY_MODE STREQUAL "FALSE" OR + CORTEX_TRACY_MODE STREQUAL "NO" OR + CORTEX_TRACY_MODE STREQUAL "0")) + set(CORTEX_ENABLE_TRACY "DEFAULT") + set(CORTEX_TRACY_MODE "DEFAULT") +endif() + +# Preset table: each preset sets the four Tracy knobs. +if (CORTEX_TRACY_MODE STREQUAL "OFF" OR + CORTEX_TRACY_MODE STREQUAL "FALSE" OR + CORTEX_TRACY_MODE STREQUAL "NO" OR + CORTEX_TRACY_MODE STREQUAL "0") + set(CORTEX_TRACY_ENABLED OFF) +elseif (CORTEX_TRACY_MODE STREQUAL "ON" OR CORTEX_TRACY_MODE STREQUAL "DEFAULT") + set(CORTEX_TRACY_ENABLED ON) + set(CORTEX_TRACY_ON_DEMAND ON) + set(CORTEX_TRACY_CALLSTACK OFF) + set(CORTEX_TRACY_ONLY_LOCALHOST ON) + set(CORTEX_TRACY_NO_BROADCAST ON) +elseif (CORTEX_TRACY_MODE STREQUAL "MEDIUM") + set(CORTEX_TRACY_ENABLED ON) + set(CORTEX_TRACY_ON_DEMAND OFF) + set(CORTEX_TRACY_CALLSTACK OFF) + set(CORTEX_TRACY_ONLY_LOCALHOST ON) + set(CORTEX_TRACY_NO_BROADCAST ON) +elseif (CORTEX_TRACY_MODE STREQUAL "EXTRA") + set(CORTEX_TRACY_ENABLED ON) + set(CORTEX_TRACY_ON_DEMAND OFF) + set(CORTEX_TRACY_CALLSTACK ON) + set(CORTEX_TRACY_ONLY_LOCALHOST ON) + set(CORTEX_TRACY_NO_BROADCAST ON) +elseif (CORTEX_TRACY_MODE STREQUAL "WSL") + set(CORTEX_TRACY_ENABLED ON) + set(CORTEX_TRACY_ON_DEMAND OFF) + set(CORTEX_TRACY_CALLSTACK OFF) + set(CORTEX_TRACY_ONLY_LOCALHOST OFF) + set(CORTEX_TRACY_NO_BROADCAST OFF) +elseif (CORTEX_TRACY_MODE STREQUAL "WSL_EXTRA") + set(CORTEX_TRACY_ENABLED ON) + set(CORTEX_TRACY_ON_DEMAND OFF) + set(CORTEX_TRACY_CALLSTACK ON) + set(CORTEX_TRACY_ONLY_LOCALHOST OFF) + set(CORTEX_TRACY_NO_BROADCAST OFF) +else() + message(FATAL_ERROR + "Invalid value for CORTEX_ENABLE_TRACY='${CORTEX_ENABLE_TRACY}'. " + "Use one of: OFF, ON, DEFAULT, MEDIUM, EXTRA, WSL, WSL_EXTRA") +endif() + +if (CORTEX_PROFILING_BACKEND_MODE STREQUAL "TRACY" AND CORTEX_TRACY_ENABLED) + message(STATUS "Tracy support enabled with preset: ${CORTEX_TRACY_MODE}") + + set(CORTEX_TRACY_ON_DEMAND ${CORTEX_TRACY_ON_DEMAND} CACHE BOOL "" FORCE) + set(CORTEX_TRACY_CALLSTACK ${CORTEX_TRACY_CALLSTACK} CACHE BOOL "" FORCE) + set(CORTEX_TRACY_ONLY_LOCALHOST ${CORTEX_TRACY_ONLY_LOCALHOST} CACHE BOOL "" FORCE) + set(CORTEX_TRACY_NO_BROADCAST ${CORTEX_TRACY_NO_BROADCAST} CACHE BOOL "" FORCE) + + set(TRACY_ON_DEMAND ${CORTEX_TRACY_ON_DEMAND} CACHE BOOL "" FORCE) + set(TRACY_CALLSTACK ${CORTEX_TRACY_CALLSTACK} CACHE BOOL "" FORCE) + set(TRACY_ONLY_LOCALHOST ${CORTEX_TRACY_ONLY_LOCALHOST} CACHE BOOL "" FORCE) + set(TRACY_NO_BROADCAST ${CORTEX_TRACY_NO_BROADCAST} CACHE BOOL "" FORCE) + + FetchContent_Declare( + tracy + GIT_REPOSITORY https://github.com/wolfpld/tracy.git + GIT_TAG v0.11.1 + ) + FetchContent_MakeAvailable(tracy) + + if (TARGET Tracy::TracyClient) + if (TARGET TracyClient) + set_property(TARGET TracyClient PROPERTY POSITION_INDEPENDENT_CODE ON) + endif() + target_link_libraries(cortex_profiling INTERFACE Tracy::TracyClient) + elseif (TARGET TracyClient) + set_property(TARGET TracyClient PROPERTY POSITION_INDEPENDENT_CODE ON) + target_link_libraries(cortex_profiling INTERFACE TracyClient) + else() + message(FATAL_ERROR "Tracy target not found after FetchContent_MakeAvailable(tracy)") + endif() + + target_compile_definitions(cortex_profiling INTERFACE + TRACY_ENABLE CORTEX_PROFILING_BACKEND_TRACY + CORTEX_CALLSTACK_DEPTH=${CORTEX_CALLSTACK_DEPTH}) + + message(STATUS " on-demand: ${CORTEX_TRACY_ON_DEMAND}") + message(STATUS " callstack: ${CORTEX_TRACY_CALLSTACK}") + message(STATUS " localhost: ${CORTEX_TRACY_ONLY_LOCALHOST}") + message(STATUS " broadcast: ${CORTEX_TRACY_NO_BROADCAST}") + +# ── Perfetto ────────────────────────────────────────────────────────────────── + +elseif (CORTEX_PROFILING_BACKEND_MODE STREQUAL "PERFETTO") + message(STATUS "Perfetto support enabled") + + FetchContent_Declare( + perfetto_sdk_src + URL https://github.com/google/perfetto/releases/download/v54.0/perfetto-cpp-sdk-src.zip + ) + FetchContent_MakeAvailable(perfetto_sdk_src) + + add_library(perfetto_sdk STATIC + ${perfetto_sdk_src_SOURCE_DIR}/perfetto.cc + ) + set_property(TARGET perfetto_sdk PROPERTY POSITION_INDEPENDENT_CODE ON) + target_include_directories(perfetto_sdk PUBLIC ${perfetto_sdk_src_SOURCE_DIR}) + target_link_libraries(perfetto_sdk PUBLIC Threads::Threads) + + target_link_libraries(cortex_profiling INTERFACE perfetto_sdk dl) + target_compile_definitions(cortex_profiling INTERFACE + CORTEX_PROFILING_BACKEND_PERFETTO + CORTEX_CALLSTACK_DEPTH=${CORTEX_CALLSTACK_DEPTH}) + +elseif (NOT CORTEX_PROFILING_BACKEND_MODE STREQUAL "NONE") + message(FATAL_ERROR + "Invalid value for CORTEX_PROFILING_BACKEND='${CORTEX_PROFILING_BACKEND}'. " + "Use one of: NONE, TRACY, PERFETTO") +endif() diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 359128ea..8a3ae00a 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -42,12 +42,15 @@ target_sources(dsr_core include/dsr/core/traits.h include/dsr/core/utils.h + include/dsr/core/profiling.h + profiling.cpp ) target_link_libraries(dsr_core PRIVATE - Qt6::Core fastcdr fastdds Eigen3::Eigen) + Qt6::Core fastcdr fastdds osgDB OpenThreads Eigen3::Eigen + cortex_profiling) target_include_directories(dsr_core diff --git a/core/include/dsr/core/crdt/delta_crdt.h b/core/include/dsr/core/crdt/delta_crdt.h index 90efedd9..a839dd5b 100644 --- a/core/include/dsr/core/crdt/delta_crdt.h +++ b/core/include/dsr/core/crdt/delta_crdt.h @@ -12,6 +12,7 @@ Reimplementation from https://github.com/CBaquero/delta-enabled-crdts #include #include "dsr/core/serialization/serializable.h" +#include "dsr/core/profiling.h" using key_type = uint64_t; @@ -58,6 +59,7 @@ class dot_context : public ISerializable { //TODO: debug this void compact() { + CORTEX_PROFILE_ZONE_N("dot_context::compact"); // Compact DC to CC if possible //typename map::iterator mit; //typename set >::iterator sit; @@ -117,6 +119,7 @@ class dot_context : public ISerializable { } void join(const dot_context &o) { + CORTEX_PROFILE_ZONE_N("dot_context::join"); if (this == &o) return; // Join is idempotent, but just dont do it. // CC auto mit = cc.begin(); @@ -293,6 +296,7 @@ class dot_kernel : public ISerializable> { } void join_replace_conflict(dot_kernel &&o) { + CORTEX_PROFILE_ZONE_N("dot_kernel::join_replace_conflict"); if (this == &o) return; // Join is idempotent, but just dont do it. @@ -496,6 +500,7 @@ class mvreg : public ISerializable> // Multi-value register, Optimize } mvreg write(const V &val) { + CORTEX_PROFILE_ZONE_N("mvreg::write(copy)"); mvreg r, a; r.dk = dk.rmv(); a.dk = dk.add(id, val); @@ -505,6 +510,7 @@ class mvreg : public ISerializable> // Multi-value register, Optimize } mvreg write(V &&val) { + CORTEX_PROFILE_ZONE_N("mvreg::write(move)"); mvreg r, a; r.dk = dk.rmv(); a.dk = dk.add(id, std::move(val)); @@ -543,6 +549,7 @@ class mvreg : public ISerializable> // Multi-value register, Optimize } void join(mvreg &&o) { + CORTEX_PROFILE_ZONE_N("mvreg::join"); dk.join_replace_conflict(std::move(o.dk)); assert(dk.ds.size() <= 1); } diff --git a/core/include/dsr/core/profiling.h b/core/include/dsr/core/profiling.h new file mode 100644 index 00000000..335e9966 --- /dev/null +++ b/core/include/dsr/core/profiling.h @@ -0,0 +1,73 @@ +#ifndef DSR_CORE_PROFILING_H +#define DSR_CORE_PROFILING_H + +namespace DSR::profiling { +void ensure_started(); +void shutdown(); +} + +#if defined(CORTEX_PROFILING_BACKEND_TRACY) + +#include + +#define CORTEX_PROFILE_ZONE() ZoneScoped +#define CORTEX_PROFILE_ZONE_N(name_literal) ZoneScopedN(name_literal) +#define CORTEX_PROFILE_ZONE_CS(name_literal) ZoneScopedNS(name_literal, CORTEX_CALLSTACK_DEPTH) +#define CORTEX_PROFILE_FRAME() FrameMark +#define CORTEX_PROFILE_TEXT(text_ptr, text_size) ZoneText(text_ptr, text_size) +#define CORTEX_PROFILE_VALUE(value) ZoneValue(value) +#define CORTEX_PROFILE_THREAD_NAME(name) tracy::SetThreadName(name) + +#elif defined(CORTEX_PROFILING_BACKEND_PERFETTO) + +#include +#include +PERFETTO_DEFINE_CATEGORIES_IN_NAMESPACE( + DSR::profiling, + perfetto::Category("cortex").SetDescription("Cortex runtime events")); +PERFETTO_USE_CATEGORIES_FROM_NAMESPACE(DSR::profiling); + +namespace DSR::profiling { +struct CallstackFrames { + static constexpr int kMax = 64; + void* frames[kMax]; + int count; +}; +CallstackFrames capture_callstack(int depth) noexcept; +void emit_callstack(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept; +} // namespace DSR::profiling + +#define CORTEX_PROFILE_ZONE() \ + ::DSR::profiling::ensure_started(); \ + TRACE_EVENT("cortex", perfetto::StaticString{__func__}) + +#define CORTEX_PROFILE_ZONE_N(name_literal) \ + ::DSR::profiling::ensure_started(); \ + TRACE_EVENT("cortex", name_literal) + +#define CORTEX_PROFILE_ZONE_CS(name_literal) \ + ::DSR::profiling::ensure_started(); \ + auto _cortex_cs = ::DSR::profiling::capture_callstack(CORTEX_CALLSTACK_DEPTH); \ + TRACE_EVENT("cortex", name_literal, [&_cortex_cs](perfetto::EventContext ctx) { \ + ::DSR::profiling::emit_callstack(ctx, _cortex_cs); \ + }) + +#define CORTEX_PROFILE_FRAME() ((void)0) +#define CORTEX_PROFILE_TEXT(text_ptr, text_size) ((void)0) +#define CORTEX_PROFILE_VALUE(value) ((void)0) +#define CORTEX_PROFILE_THREAD_NAME(name) \ + do { char _tn[16]; strncpy(_tn, (name), 15); _tn[15] = '\0'; pthread_setname_np(pthread_self(), _tn); } while(0) + +#else + +#define CORTEX_PROFILE_ZONE() ((void)0) +#define CORTEX_PROFILE_ZONE_N(name_literal) ((void)0) +#define CORTEX_PROFILE_ZONE_CS(name_literal) ((void)0) +#define CORTEX_PROFILE_FRAME() ((void)0) +#define CORTEX_PROFILE_TEXT(text_ptr, text_size) ((void)0) +#define CORTEX_PROFILE_VALUE(value) ((void)0) +#define CORTEX_PROFILE_THREAD_NAME(name) ((void)0) + +#endif + +#endif diff --git a/core/include/threadpool/threadpool.h b/core/include/threadpool/threadpool.h new file mode 100644 index 00000000..5a6e381f --- /dev/null +++ b/core/include/threadpool/threadpool.h @@ -0,0 +1,182 @@ +// +// Created by juancarlos on 15/10/20. +// This class is a simple threadpool with a thread-safe interface. +// The interface offers methods to execute either asynchronous tasks from which +// no result is expected using the spawn_task method, or asynchronous tasks from +// which a result is expected, which return a future object (https://en.cppreference.com/w/cpp/thread/future) +// with the method spawn_task_waitable. +// It can be used as a set of worker threads for executing tasks sent by a thread that read periodically +// from the network (Used in dsr). +// It is also used to launch tasks that the user does not need to wait for to complete (Used in doublebuffer). +// Another use would be to spawn multiple tasks that can be executed in parallel and wait for all of them to +// be completed after that. + +#ifndef SIMPLE_THREADPOOL +#define SIMPLE_THREADPOOL + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +template +concept only_rvalues = (std::negation< std::bool_constant::value> >::value && ...); + + +//Base Virtual Object to store any kind of callable objects and its arguments. +class function_wrapper_base +{ +public: + virtual ~function_wrapper_base(){}; + virtual void operator()() {}; +}; + +//Specialization +template +class function_wrapper : public function_wrapper_base +{ +public: + function_wrapper(Function &&fn, std::tuple args) : f(std::forward(fn)), + args(std::move(args)){}; + + void operator()() override + { + std::apply(f, std::move(args)); + } + +private: + Function f; + std::tuple args; +}; + +class ThreadPool +{ +public: + + //The threadpool can't be copied. + ThreadPool(const ThreadPool &tp) = delete; + ThreadPool(ThreadPool &tp) = delete; + ThreadPool &operator=(const ThreadPool &tp) = delete; + + ThreadPool(uint32_t num_threads = 0, std::string name = "worker") : done(false), pool_name(std::move(name)) + { + uint32_t nt = (num_threads == 0) ? std::thread::hardware_concurrency() : num_threads; + for (std::size_t i = 0; i < nt; i++) + { + threads.emplace_back(std::thread(&ThreadPool::thread_loop, this, i)); + } + } + + ~ThreadPool() + { + + std::unique_lock lock(tp_mutex); + std::queue> tmp; + std::swap(tasks, tmp); + lock.unlock(); + + done = true; + cv.notify_all(); + + for (auto &th : threads) + { + if (th.joinable()) + th.join(); + } + } + + uint32_t remaining_tasks() { + return tasks.size(); + } + + template + void spawn_task(Function &&fn, Arguments &&... args) + requires (only_rvalues && std::is_invocable::value) + { + std::unique_lock task_queue_lock(tp_mutex, std::defer_lock); + task_queue_lock.lock(); + auto tmp_ptr = std::unique_ptr(new function_wrapper(std::forward(fn), std::forward_as_tuple(std::move(args)...))); + tasks.emplace(std::move(tmp_ptr)); + task_queue_lock.unlock(); + cv.notify_one(); + } + + template + auto spawn_task_waitable(Function &&fn, Arguments &&... args) + requires (only_rvalues && std::is_invocable::value) + { + std::unique_lock task_queue_lock(tp_mutex, std::defer_lock); + + auto task = std::packaged_task()>( + [fn_ = std::forward(fn), args_ = std::forward_as_tuple(args...)]() mutable -> auto { + return std::apply(std::move(fn_), std::move(args_)); + } + ); + + auto future = task.get_future(); + + task_queue_lock.lock(); + auto tmp_ptr = std::unique_ptr( + new function_wrapper()>>( + std::move(task), std::tuple<>{})); + tasks.emplace(std::move(tmp_ptr)); + task_queue_lock.unlock(); + cv.notify_one(); + + return future; + } + +private: + + void thread_loop(int i) + { + std::string tname = pool_name + "-" + std::to_string(i); + if (tname.size() > 15) tname.resize(15); + pthread_setname_np(pthread_self(), tname.c_str()); + + [[maybe_unused]] static thread_local uint32_t thread_index = i; + std::unique_lock task_queue_lock(tp_mutex, std::defer_lock); + while (!done) + { + task_queue_lock.lock(); + + cv.wait(task_queue_lock, + [&]() -> bool { return !tasks.empty() || done; }); + + if (done) { + task_queue_lock.unlock(); + cv.notify_all(); + break; + } + + std::unique_ptr t = std::move(tasks.front()); + tasks.pop(); + task_queue_lock.unlock(); + + if (t != nullptr) + { + (*t)(); + } + + } + } + + std::vector threads; + std::queue> tasks; + std::string pool_name; + static thread_local uint32_t thread_index; + std::condition_variable cv; + std::atomic_bool done = false; + mutable std::mutex tp_mutex; +}; + + +#endif diff --git a/core/profiling.cpp b/core/profiling.cpp new file mode 100644 index 00000000..2031b8a7 --- /dev/null +++ b/core/profiling.cpp @@ -0,0 +1,154 @@ +#include "dsr/core/profiling.h" + +#if defined(CORTEX_PROFILING_BACKEND_PERFETTO) + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +PERFETTO_TRACK_EVENT_STATIC_STORAGE_IN_NAMESPACE(DSR::profiling); + +namespace DSR::profiling { +namespace { + +std::once_flag g_init_once; +std::once_flag g_shutdown_once; +std::unique_ptr g_session; + +std::string default_trace_path() +{ + if (const char* env = std::getenv("CORTEX_PERFETTO_TRACE_FILE"); env != nullptr && env[0] != '\0') + return env; + + namespace fs = std::filesystem; + fs::path out_dir = fs::current_path() / ".artifacts" / "perfetto"; + std::error_code ec; + fs::create_directories(out_dir, ec); + + std::string exe_name = "cortex"; +#if defined(__linux__) + std::error_code symlink_ec; + const auto exe = fs::read_symlink("/proc/self/exe", symlink_ec); + if (!symlink_ec && exe.has_filename()) + exe_name = exe.filename().string(); +#endif + + const auto now = std::chrono::system_clock::now().time_since_epoch(); + const auto ts_ms = std::chrono::duration_cast(now).count(); + +#if defined(__linux__) + const auto pid = static_cast(::getpid()); +#else + const auto pid = 0LL; +#endif + + return (out_dir / (exe_name + "-" + std::to_string(pid) + "-" + std::to_string(ts_ms) + ".pftrace")).string(); +} + +void start_session() +{ + perfetto::TracingInitArgs args; + args.backends |= perfetto::kInProcessBackend; + perfetto::Tracing::Initialize(args); + DSR::profiling::TrackEvent::Register(); + + perfetto::TraceConfig cfg; + cfg.add_buffers()->set_size_kb(16 * 1024); + auto* ds_cfg = cfg.add_data_sources()->mutable_config(); + ds_cfg->set_name("track_event"); + + perfetto::protos::gen::TrackEventConfig te_cfg; + te_cfg.add_enabled_categories("*"); + ds_cfg->set_track_event_config_raw(te_cfg.SerializeAsString()); + + g_session = perfetto::Tracing::NewTrace(); + g_session->Setup(cfg); + g_session->StartBlocking(); + + std::atexit(&shutdown); +} + +} // namespace + +void ensure_started() +{ + std::call_once(g_init_once, &start_session); +} + +void shutdown() +{ + std::call_once(g_shutdown_once, [] { + if (!g_session) + return; + + g_session->StopBlocking(); + const auto trace_data = g_session->ReadTraceBlocking(); + + std::ofstream output(default_trace_path(), std::ios::out | std::ios::binary); + if (output.is_open()) { + output.write(trace_data.data(), static_cast(trace_data.size())); + output.close(); + } + + g_session.reset(); + }); +} + +CallstackFrames capture_callstack(int depth) noexcept +{ + CallstackFrames cs{}; + int capped = depth < CallstackFrames::kMax ? depth : CallstackFrames::kMax; + // +2 to skip backtrace() itself and capture_callstack() + cs.count = ::backtrace(cs.frames, capped + 2); + return cs; +} + +void emit_callstack(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept +{ + // skip frame 0 (backtrace) and frame 1 (capture_callstack) + constexpr int kSkip = 2; + std::string stack; + stack.reserve(cs.count * 64); + + for (int i = kSkip; i < cs.count; ++i) { + Dl_info info{}; + if (::dladdr(cs.frames[i], &info) && info.dli_sname) { + int status = -1; + char* dem = abi::__cxa_demangle(info.dli_sname, nullptr, nullptr, &status); + stack += (status == 0 && dem) ? dem : info.dli_sname; + ::free(dem); + } else { + char buf[20]; + ::snprintf(buf, sizeof(buf), "%p", cs.frames[i]); + stack += buf; + } + stack += '\n'; + } + + auto* ann = ctx.event()->add_debug_annotations(); + ann->set_name("callstack"); + ann->set_string_value(stack); +} + +} // namespace DSR::profiling + +#else + +namespace DSR::profiling { +void ensure_started() {} +void shutdown() {} +} + +#endif diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 131bbab7..3b2b4316 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -51,6 +51,7 @@ target_link_libraries(tests PRIVATE Catch2::Catch2WithMain Robocomp::dsr_api Robocomp::dsr_core + cortex_profiling Qt6::Core Eigen3::Eigen fastdds From da3bd8fd7cc114702d0f2a607d42bbae4386c19d Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Mon, 20 Apr 2026 14:07:32 +0200 Subject: [PATCH 08/38] fixup! tracing: add initial support for perfetto/tracy --- PROFILING.md | 74 +++++++++- benchmarks/CMakeLists.txt | 1 - cmake/profiling.cmake | 24 ++- core/include/dsr/core/profiling.h | 17 ++- core/profiling.cpp | 233 +++++++++++++++++++++++++----- tests/CMakeLists.txt | 24 ++- tests/profiling/perfetto_test.cpp | 101 +++++++++++++ 7 files changed, 427 insertions(+), 47 deletions(-) create mode 100644 tests/profiling/perfetto_test.cpp diff --git a/PROFILING.md b/PROFILING.md index 7a307710..ac249fda 100644 --- a/PROFILING.md +++ b/PROFILING.md @@ -57,17 +57,87 @@ What you need: - a generated `.pftrace` file - either the web UI at `https://ui.perfetto.dev/` or another Perfetto-compatible viewer -Typical usage: +#### Callstack mode (`CORTEX_PERFETTO_MODE`) + +Three modes are available, selected at configure time: + +| Mode | CMake flag | What you get | +|------|-----------|--------------| +| `DEFAULT` | _(omit)_ | Zone events only, no callstacks | +| `STACKFRAME` | `-DCORTEX_PERFETTO_MODE=STACKFRAME` | Callstacks attached to `CORTEX_PROFILE_ZONE_CS` zones via `callstack_iid` + `InternedData` (native flamechart in the UI) | +| `LINUX_PERF` | `-DCORTEX_PERFETTO_MODE=LINUX_PERF` | Kernel-driven CPU sampling correlated to zone events by timestamp | + +**STACKFRAME** captures a callstack at every `CORTEX_PROFILE_ZONE_CS` call site using `backtrace()`, resolves symbols with `dladdr` + demangling, and emits them as proper `Callstack` / `Frame` / `InternedString` proto entries. The Perfetto UI renders these as an expandable flamechart on the event. `-fno-omit-frame-pointer` is added automatically. + +**LINUX_PERF** adds a `linux.perf` data source alongside track events. The kernel interrupts the process at 1 kHz and records the CPU stack independently of instrumentation — useful for finding hotspots in uninstrumented code. `-fno-omit-frame-pointer` is added automatically. + +Requirements for `LINUX_PERF`: + +- `traced`, `traced_probes`, and `traced_perf` must be running (all three) +- `perf_event_paranoid <= 0`: + ```bash + sudo sysctl -w kernel.perf_event_paranoid=0 + ``` +- The `tracebox` binary (not its symlink) needs `CAP_SYS_PTRACE` for DWARF stack unwinding. `readlink -f` may not resolve the real path — locate it manually if needed: + ```bash + # find the actual binary (example path — yours may differ) + ls -la $(which tracebox) # shows where symlink points + sudo setcap cap_perfmon,cap_sys_ptrace+ep /home/jc/.local/share/perfetto/prebuilts/tracebox + ``` +- Run `traced_perf` as root if `setcap` is not an option (root can open `/proc//mem` and connect to user-owned sockets): + ```bash + tracebox traced --background # as your user + tracebox traced_probes --background # as your user + sudo tracebox traced_perf # as root + ``` + +**Important — LINUX_PERF vs DEFAULT/STACKFRAME modes:** + +LINUX_PERF mode registers the process as a system-backend producer only. It does **not** write a `.pftrace` file itself — the trace is owned by `traced` and read back at process exit via the consumer API. Zone events and CPU samples land in the same file and are visible as separate track groups in the UI ("Process callstacks cpu-clock" for samples, thread rows for zones). To correlate them, expand both groups and select an area that spans both. + +#### Typical usage + +DEFAULT (zone events only, no daemons needed): ```bash cmake -S . -B build-perfetto \ -DWITH_TESTS=ON \ -DCORTEX_PROFILING_BACKEND=PERFETTO cmake --build build-perfetto --target tests -export CORTEX_PERFETTO_TRACE_FILE=.artifacts/output.pftrace ./build-perfetto/tests/tests "[SYNCHRONIZATION][GRAPH]" ``` +STACKFRAME (callstacks on `_CS` zones, no daemons needed): + +```bash +cmake -S . -B build-perfetto \ + -DWITH_TESTS=ON \ + -DCORTEX_PROFILING_BACKEND=PERFETTO \ + -DCORTEX_PERFETTO_MODE=STACKFRAME +cmake --build build-perfetto --target tests +./build-perfetto/tests/tests "[SYNCHRONIZATION][GRAPH]" +``` + +LINUX_PERF (kernel CPU sampling correlated with zone events): + +```bash +# One-time setup: +sudo sysctl -w kernel.perf_event_paranoid=0 +sudo setcap cap_perfmon,cap_sys_ptrace+ep /path/to/real/tracebox + +# Start daemons (traced_perf as root OR with setcap applied): +tracebox traced --background +tracebox traced_probes --background +tracebox traced_perf --background # or: sudo tracebox traced_perf + +cmake -S . -B build-pf-lp \ + -DWITH_TESTS=ON \ + -DCORTEX_PROFILING_BACKEND=PERFETTO \ + -DCORTEX_PERFETTO_MODE=LINUX_PERF +cmake --build build-pf-lp -j$(nproc) +./build-pf-lp/bin/your_component +``` + The trace file path can be overridden with: ```bash diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index 9a307a99..a72bfd77 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -102,7 +102,6 @@ target_link_libraries(dsr_benchmarks PRIVATE nanobench dsr_api dsr_core - cortex_profiling Qt6::Core Eigen3::Eigen fastdds diff --git a/cmake/profiling.cmake b/cmake/profiling.cmake index 86d3f927..1479be13 100644 --- a/cmake/profiling.cmake +++ b/cmake/profiling.cmake @@ -133,7 +133,11 @@ if (CORTEX_PROFILING_BACKEND_MODE STREQUAL "TRACY" AND CORTEX_TRACY_ENABLED) # ── Perfetto ────────────────────────────────────────────────────────────────── elseif (CORTEX_PROFILING_BACKEND_MODE STREQUAL "PERFETTO") - message(STATUS "Perfetto support enabled") + + set(CORTEX_PERFETTO_MODE "DEFAULT" CACHE STRING + "Perfetto callstack mode. Accepted values: DEFAULT, STACKFRAME, LINUX_PERF") + set_property(CACHE CORTEX_PERFETTO_MODE PROPERTY STRINGS DEFAULT STACKFRAME LINUX_PERF) + string(TOUPPER "${CORTEX_PERFETTO_MODE}" _pf_mode) FetchContent_Declare( perfetto_sdk_src @@ -153,6 +157,24 @@ elseif (CORTEX_PROFILING_BACKEND_MODE STREQUAL "PERFETTO") CORTEX_PROFILING_BACKEND_PERFETTO CORTEX_CALLSTACK_DEPTH=${CORTEX_CALLSTACK_DEPTH}) + if (_pf_mode STREQUAL "STACKFRAME") + target_compile_definitions(cortex_profiling INTERFACE CORTEX_PERFETTO_CALLSTACK_STACKFRAME) + target_compile_options(cortex_profiling INTERFACE -fno-omit-frame-pointer) + target_link_options(cortex_profiling INTERFACE -rdynamic) + elseif (_pf_mode STREQUAL "LINUX_PERF") + target_compile_definitions(cortex_profiling INTERFACE CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + target_compile_options(cortex_profiling INTERFACE -fno-omit-frame-pointer) + elseif (NOT _pf_mode STREQUAL "DEFAULT") + message(FATAL_ERROR + "Invalid value for CORTEX_PERFETTO_MODE='${CORTEX_PERFETTO_MODE}'. " + "Use one of: DEFAULT, STACKFRAME, LINUX_PERF") + endif() + + message(STATUS "Perfetto support enabled (mode: ${_pf_mode})") + if (_pf_mode STREQUAL "LINUX_PERF") + message(STATUS " NOTE: LINUX_PERF requires traced + traced_probes and CAP_PERFMON (or perf_event_paranoid <= 1)") + endif() + elseif (NOT CORTEX_PROFILING_BACKEND_MODE STREQUAL "NONE") message(FATAL_ERROR "Invalid value for CORTEX_PROFILING_BACKEND='${CORTEX_PROFILING_BACKEND}'. " diff --git a/core/include/dsr/core/profiling.h b/core/include/dsr/core/profiling.h index 335e9966..a7273e28 100644 --- a/core/include/dsr/core/profiling.h +++ b/core/include/dsr/core/profiling.h @@ -22,19 +22,24 @@ void shutdown(); #include #include + PERFETTO_DEFINE_CATEGORIES_IN_NAMESPACE( DSR::profiling, perfetto::Category("cortex").SetDescription("Cortex runtime events")); PERFETTO_USE_CATEGORIES_FROM_NAMESPACE(DSR::profiling); namespace DSR::profiling { + +#if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) struct CallstackFrames { static constexpr int kMax = 64; void* frames[kMax]; int count; }; CallstackFrames capture_callstack(int depth) noexcept; -void emit_callstack(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept; +void emit_callstack_stackframe(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept; +#endif + } // namespace DSR::profiling #define CORTEX_PROFILE_ZONE() \ @@ -45,12 +50,20 @@ void emit_callstack(perfetto::EventContext& ctx, const CallstackFrames& cs) noex ::DSR::profiling::ensure_started(); \ TRACE_EVENT("cortex", name_literal) +#if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) #define CORTEX_PROFILE_ZONE_CS(name_literal) \ ::DSR::profiling::ensure_started(); \ auto _cortex_cs = ::DSR::profiling::capture_callstack(CORTEX_CALLSTACK_DEPTH); \ TRACE_EVENT("cortex", name_literal, [&_cortex_cs](perfetto::EventContext ctx) { \ - ::DSR::profiling::emit_callstack(ctx, _cortex_cs); \ + ::DSR::profiling::emit_callstack_stackframe(ctx, _cortex_cs); \ }) +#else +/* DEFAULT / LINUX_PERF: no per-zone callstack capture needed; + linux.perf samples the whole process at the configured frequency. */ +#define CORTEX_PROFILE_ZONE_CS(name_literal) \ + ::DSR::profiling::ensure_started(); \ + TRACE_EVENT("cortex", name_literal) +#endif #define CORTEX_PROFILE_FRAME() ((void)0) #define CORTEX_PROFILE_TEXT(text_ptr, text_size) ((void)0) diff --git a/core/profiling.cpp b/core/profiling.cpp index 2031b8a7..4b457fe5 100644 --- a/core/profiling.cpp +++ b/core/profiling.cpp @@ -5,6 +5,7 @@ #include #include +#include #include #include #include @@ -12,11 +13,15 @@ #include #include +#include + +// Included here (before any namespace) so that dladdr/backtrace are declared +// in the global namespace and accessible via :: inside DSR::profiling. +#if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) #include #include #include -#include - +#endif PERFETTO_TRACK_EVENT_STATIC_STORAGE_IN_NAMESPACE(DSR::profiling); @@ -47,12 +52,7 @@ std::string default_trace_path() const auto now = std::chrono::system_clock::now().time_since_epoch(); const auto ts_ms = std::chrono::duration_cast(now).count(); - -#if defined(__linux__) const auto pid = static_cast(::getpid()); -#else - const auto pid = 0LL; -#endif return (out_dir / (exe_name + "-" + std::to_string(pid) + "-" + std::to_string(ts_ms) + ".pftrace")).string(); } @@ -60,20 +60,50 @@ std::string default_trace_path() void start_session() { perfetto::TracingInitArgs args; +#if defined(CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + args.backends |= perfetto::kSystemBackend; +#else args.backends |= perfetto::kInProcessBackend; +#endif perfetto::Tracing::Initialize(args); DSR::profiling::TrackEvent::Register(); - perfetto::TraceConfig cfg; - cfg.add_buffers()->set_size_kb(16 * 1024); - auto* ds_cfg = cfg.add_data_sources()->mutable_config(); - ds_cfg->set_name("track_event"); +#if defined(CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + // Wait for traced_perf to connect to traced and register linux.perf. + // traced_perf is a separate producer from traced_probes — both must be + // running before this point. If linux.perf isn't registered when we send + // the config, traced silently skips that data source. + std::this_thread::sleep_for(std::chrono::milliseconds(500)); +#endif - perfetto::protos::gen::TrackEventConfig te_cfg; - te_cfg.add_enabled_categories("*"); - ds_cfg->set_track_event_config_raw(te_cfg.SerializeAsString()); + perfetto::TraceConfig cfg; + cfg.add_buffers()->set_size_kb(32 * 1024); + + { + auto* ds_cfg = cfg.add_data_sources()->mutable_config(); + ds_cfg->set_name("track_event"); + perfetto::protos::gen::TrackEventConfig te_cfg; + te_cfg.add_enabled_categories("*"); + ds_cfg->set_track_event_config_raw(te_cfg.SerializeAsString()); + } - g_session = perfetto::Tracing::NewTrace(); +#if defined(CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + { + auto* ds_cfg = cfg.add_data_sources()->mutable_config(); + ds_cfg->set_name("linux.perf"); + perfetto::protos::gen::PerfEventConfig perf_cfg; + perf_cfg.mutable_timebase()->set_frequency(1000); + // Per-process scope: works without root when perf_event_paranoid <= 1. + // Per-CPU scope (no target_pid) requires paranoid <= 0 or CAP_PERFMON. + auto* cs = perf_cfg.mutable_callstack_sampling(); + cs->mutable_scope()->add_target_pid(static_cast(::getpid())); + cs->set_kernel_frames(false); + ds_cfg->set_perf_event_config_raw(perf_cfg.SerializeAsString()); + } + g_session = perfetto::Tracing::NewTrace(perfetto::kSystemBackend); +#else + g_session = perfetto::Tracing::NewTrace(perfetto::kInProcessBackend); +#endif g_session->Setup(cfg); g_session->StartBlocking(); @@ -93,19 +123,133 @@ void shutdown() if (!g_session) return; + DSR::profiling::TrackEvent::Flush(); g_session->StopBlocking(); const auto trace_data = g_session->ReadTraceBlocking(); - std::ofstream output(default_trace_path(), std::ios::out | std::ios::binary); - if (output.is_open()) { - output.write(trace_data.data(), static_cast(trace_data.size())); - output.close(); + if (trace_data.empty()) { + // System backend not reachable (e.g. traced not running or socket + // permission mismatch). Avoid creating a misleading 0-byte file. + fprintf(stderr, "[cortex profiling] WARNING: trace data is empty — " + "check that traced/traced_probes are running as the same user\n"); + } else { + std::ofstream output(default_trace_path(), std::ios::out | std::ios::binary); + if (output.is_open()) + output.write(trace_data.data(), static_cast(trace_data.size())); } g_session.reset(); }); } +// ── StackFrame / InternedData callstack capture ─────────────────────────────── +#if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) + +#include + +// Three-level interning: FunctionName → Frame → Callstack. +// +// Perfetto's TrackEventInternedDataIndex::Add receives only (InternedData*, iid, +// key), not the EventContext, so we cannot call inner Get() from inside Add(). +// We work around this with two thread-local scratch maps that carry the +// already-computed inner IIDs across the interning boundary: +// +// tl_frame_fn_iid[pc] set before InternedFrame::Get() +// tl_callstack_frame_iids[key] set before InternedCallstack::Get() + +namespace { + +thread_local std::unordered_map tl_frame_fn_iid; +thread_local std::unordered_map> tl_cs_frame_iids; + +static std::string resolve_pc(void* pc) noexcept +{ + Dl_info info{}; + if (::dladdr(pc, &info)) { + if (info.dli_sname) { + int status = -1; + char* dem = abi::__cxa_demangle(info.dli_sname, nullptr, nullptr, &status); + std::string name = (status == 0 && dem) ? dem : info.dli_sname; + ::free(dem); + return name; + } + // No exported symbol (lambda, inline, template, etc.) — show library+offset + // so the frame can be resolved offline with: + // addr2line -e -f -C + if (info.dli_fname) { + const char* slash = ::strrchr(info.dli_fname, '/'); + const char* base = slash ? slash + 1 : info.dli_fname; + uintptr_t offset = reinterpret_cast(pc) + - reinterpret_cast(info.dli_fbase); + char buf[256]; + ::snprintf(buf, sizeof(buf), "%s+0x%lx", base, static_cast(offset)); + return buf; + } + } + char buf[20]; + ::snprintf(buf, sizeof(buf), "%p", pc); + return buf; +} + +// Intern a function-name string. +struct InternedFnName + : perfetto::TrackEventInternedDataIndex< + InternedFnName, + perfetto::protos::pbzero::InternedData::kFunctionNamesFieldNumber, + std::string> { + static void Add(perfetto::protos::pbzero::InternedData* data, + size_t iid, const std::string& name) { + auto* fn = data->add_function_names(); + fn->set_iid(iid); + fn->set_str(reinterpret_cast(name.data()), name.size()); + } +}; + +// Intern a frame keyed by PC address. +// tl_frame_fn_iid[pc] must be set before calling Get(). +struct InternedFrame + : perfetto::TrackEventInternedDataIndex< + InternedFrame, + perfetto::protos::pbzero::InternedData::kFramesFieldNumber, + uint64_t> { + static void Add(perfetto::protos::pbzero::InternedData* data, + size_t iid, uint64_t pc) { + auto* frame = data->add_frames(); + frame->set_iid(iid); + auto it = tl_frame_fn_iid.find(pc); + if (it != tl_frame_fn_iid.end()) + frame->set_function_name_id(it->second); + } +}; + +// Intern a callstack keyed by a binary encoding of its frame IIDs. +// tl_cs_frame_iids[key] must be set before calling Get(). +struct InternedCallstack + : perfetto::TrackEventInternedDataIndex< + InternedCallstack, + perfetto::protos::pbzero::InternedData::kCallstacksFieldNumber, + std::string> { + static void Add(perfetto::protos::pbzero::InternedData* data, + size_t iid, const std::string& key) { + auto* cs = data->add_callstacks(); + cs->set_iid(iid); + auto it = tl_cs_frame_iids.find(key); + if (it != tl_cs_frame_iids.end()) + for (uint64_t fid : it->second) + cs->add_frame_ids(fid); + } +}; + +// Encode a vector of uint64 frame IIDs as a raw byte string for use as a map key. +static std::string encode_frame_iids(const std::vector& ids) +{ + std::string key(ids.size() * sizeof(uint64_t), '\0'); + std::memcpy(key.data(), ids.data(), key.size()); + return key; +} + +} // namespace + CallstackFrames capture_callstack(int depth) noexcept { CallstackFrames cs{}; @@ -115,33 +259,42 @@ CallstackFrames capture_callstack(int depth) noexcept return cs; } -void emit_callstack(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept +void emit_callstack_stackframe(perfetto::EventContext& ctx, + const CallstackFrames& cs) noexcept { - // skip frame 0 (backtrace) and frame 1 (capture_callstack) - constexpr int kSkip = 2; - std::string stack; - stack.reserve(cs.count * 64); + constexpr int kSkip = 2; // skip backtrace() + capture_callstack() + // Phase 1: intern function names; populate tl_frame_fn_iid for phase 2. + std::vector pcs; + pcs.reserve(cs.count - kSkip); for (int i = kSkip; i < cs.count; ++i) { - Dl_info info{}; - if (::dladdr(cs.frames[i], &info) && info.dli_sname) { - int status = -1; - char* dem = abi::__cxa_demangle(info.dli_sname, nullptr, nullptr, &status); - stack += (status == 0 && dem) ? dem : info.dli_sname; - ::free(dem); - } else { - char buf[20]; - ::snprintf(buf, sizeof(buf), "%p", cs.frames[i]); - stack += buf; - } - stack += '\n'; + uint64_t pc = reinterpret_cast(cs.frames[i]); + pcs.push_back(pc); + std::string name = resolve_pc(cs.frames[i]); + uint64_t fn_iid = InternedFnName::Get(&ctx, name); + tl_frame_fn_iid[pc] = fn_iid; } - auto* ann = ctx.event()->add_debug_annotations(); - ann->set_name("callstack"); - ann->set_string_value(stack); + // Phase 2: intern frames; populate tl_cs_frame_iids for phase 3. + std::vector frame_iids; + frame_iids.reserve(pcs.size()); + for (uint64_t pc : pcs) + frame_iids.push_back(InternedFrame::Get(&ctx, pc)); + + // Phase 3: intern the callstack and attach it to the event. + std::string cs_key = encode_frame_iids(frame_iids); + tl_cs_frame_iids[cs_key] = frame_iids; + uint64_t cs_iid = InternedCallstack::Get(&ctx, cs_key); + ctx.event()->set_callstack_iid(cs_iid); + + // Cleanup scratch state. + for (uint64_t pc : pcs) + tl_frame_fn_iid.erase(pc); + tl_cs_frame_iids.erase(cs_key); } +#endif // CORTEX_PERFETTO_CALLSTACK_STACKFRAME + } // namespace DSR::profiling #else @@ -151,4 +304,4 @@ void ensure_started() {} void shutdown() {} } -#endif +#endif // CORTEX_PROFILING_BACKEND_PERFETTO diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 3b2b4316..f6584e02 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -47,7 +47,7 @@ CXX_EXTENSIONS ON) target_compile_options(tests PUBLIC -g -std=c++23) -target_link_libraries(tests PRIVATE +target_link_libraries(tests PRIVATE Catch2::Catch2WithMain Robocomp::dsr_api Robocomp::dsr_core @@ -57,3 +57,25 @@ target_link_libraries(tests PRIVATE fastdds fastcdr) +# ── Perfetto integration tests ──────────────────────────────────────────────── +# Built only when the Perfetto backend is active (any mode). +if (TARGET cortex_profiling) + get_target_property(_pf_defs cortex_profiling INTERFACE_COMPILE_DEFINITIONS) + if (_pf_defs AND _pf_defs MATCHES "CORTEX_PROFILING_BACKEND_PERFETTO") + add_executable(perfetto_tests + profiling/perfetto_test.cpp) + + set_target_properties(perfetto_tests PROPERTIES + CXX_STANDARD 23 + CXX_STANDARD_REQUIRED ON) + + target_compile_options(perfetto_tests PRIVATE -g -std=c++23) + + target_link_libraries(perfetto_tests PRIVATE + Catch2::Catch2 + Robocomp::dsr_api + Robocomp::dsr_core + cortex_profiling) + endif() +endif() + diff --git a/tests/profiling/perfetto_test.cpp b/tests/profiling/perfetto_test.cpp new file mode 100644 index 00000000..f82fc566 --- /dev/null +++ b/tests/profiling/perfetto_test.cpp @@ -0,0 +1,101 @@ +#include +#include + +#include "dsr/core/profiling.h" + +#include +#include +#include +#include +#include + +namespace fs = std::filesystem; + +// ── shared state set up in main() before any test runs ─────────────────────── + +static fs::path g_trace_path; +static std::string g_trace_bytes; + +// A noinline call chain so the callstack has at least two recognisable frames. +[[noinline]] static void profiling_leaf() +{ + CORTEX_PROFILE_ZONE_CS("perfetto_test_leaf"); + volatile int x = 0; + for (int i = 0; i < 10'000; ++i) x += i; +} + +[[noinline]] static void profiling_caller() +{ + CORTEX_PROFILE_ZONE_N("perfetto_test_caller"); + profiling_leaf(); +} + +// ── tests ───────────────────────────────────────────────────────────────────── + +TEST_CASE("trace file is written and non-empty", "[perfetto]") +{ + REQUIRE(fs::exists(g_trace_path)); + REQUIRE(fs::file_size(g_trace_path) > 256); // sanity: more than a header +} + +#if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) + +TEST_CASE("STACKFRAME: trace contains interned function name strings", "[perfetto][stackframe]") +{ + // The STACKFRAME path interns demangled symbol names as InternedStrings. + // They are stored as raw UTF-8 bytes inside the proto binary, so a plain + // substring search is sufficient. + CHECK(g_trace_bytes.find("perfetto_test_leaf") != std::string::npos); + CHECK(g_trace_bytes.find("perfetto_test_caller") != std::string::npos); +} + +TEST_CASE("STACKFRAME: trace contains callstack_iid field tag", "[perfetto][stackframe]") +{ + // TrackEvent.callstack_iid = field 36, wire type 0 (varint). + // Tag = (36 << 3) | 0 = 288 = 0x0120, encoded as two varint bytes: 0xa0 0x02. + const std::string tag("\xa0\x02", 2); + CHECK(g_trace_bytes.find(tag) != std::string::npos); +} + +#endif // CORTEX_PERFETTO_CALLSTACK_STACKFRAME + +#if defined(CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + +TEST_CASE("LINUX_PERF: trace is large enough to contain perf samples", "[perfetto][linux_perf]") +{ + // Perf samples are produced by traced_probes independently of track events. + // We can only confirm the file is non-trivially large; detailed content + // verification would require the Perfetto trace processor. + REQUIRE(fs::file_size(g_trace_path) > 1024); +} + +#endif // CORTEX_PERFETTO_CALLSTACK_LINUX_PERF + +// ── custom main: run workload, flush, then hand off to Catch2 ──────────────── + +int main(int argc, char* argv[]) +{ + g_trace_path = fs::temp_directory_path() / "cortex_perfetto_test.pftrace"; + fs::remove(g_trace_path); + ::setenv("CORTEX_PERFETTO_TRACE_FILE", g_trace_path.string().c_str(), /*overwrite=*/1); + + // Emit events from multiple threads so the flush path exercises all writers. + { + std::thread t1(profiling_caller); + std::thread t2(profiling_caller); + t1.join(); + t2.join(); + profiling_caller(); // main thread too + } + + // Flush thread-local buffers and write the file. + DSR::profiling::shutdown(); + + // Load trace bytes once; individual tests search within them. + if (fs::exists(g_trace_path)) { + std::ifstream f(g_trace_path, std::ios::binary); + g_trace_bytes.assign(std::istreambuf_iterator(f), {}); + } + + return Catch::Session().run(argc, argv); +} From f5868518d6595dc6470afb0135690766ab914785 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Tue, 21 Apr 2026 20:52:42 +0200 Subject: [PATCH 09/38] refactor: extract sync engine and add lww wire scaffolding --- api/CMakeLists.txt | 3 + api/dsr_api.cpp | 925 +++-------------- api/dsr_crdt_sync_engine.cpp | 993 +++++++++++++++++++ api/include/dsr/api/dsr_api.h | 37 +- api/include/dsr/api/dsr_crdt_sync_engine.h | 79 ++ api/include/dsr/api/dsr_graph_settings.h | 13 +- api/include/dsr/api/dsr_sync_engine.h | 97 ++ core/include/dsr/core/types/internal_types.h | 436 +++++++- tests/synchronization/type_translation.cpp | 122 +++ 9 files changed, 1898 insertions(+), 807 deletions(-) create mode 100644 api/dsr_crdt_sync_engine.cpp create mode 100644 api/include/dsr/api/dsr_crdt_sync_engine.h create mode 100644 api/include/dsr/api/dsr_sync_engine.h diff --git a/api/CMakeLists.txt b/api/CMakeLists.txt index 0ee45a4f..28da2717 100644 --- a/api/CMakeLists.txt +++ b/api/CMakeLists.txt @@ -23,6 +23,8 @@ set(headers_to_moc set(headers include/dsr/api/dsr_graph_settings.h + include/dsr/api/dsr_sync_engine.h + include/dsr/api/dsr_crdt_sync_engine.h ) add_library(dsr_api SHARED) @@ -32,6 +34,7 @@ add_library(Robocomp::dsr_api ALIAS dsr_api ) target_sources(dsr_api PRIVATE dsr_api.cpp + dsr_crdt_sync_engine.cpp dsr_camera_api.cpp dsr_agent_info_api.cpp dsr_inner_eigen_api.cpp diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index a7e1032a..b1bf4ac4 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -3,6 +3,7 @@ // #include "dsr/api/dsr_graph_settings.h" +#include "dsr/api/dsr_crdt_sync_engine.h" #include "dsr/core/types/internal_types.h" #include "dsr/core/types/translator.h" #include "dsr/core/profiling.h" @@ -46,6 +47,43 @@ bool protocol_version_matches( "local:", DSR::DSR_PROTOCOL_VERSION); return false; } + +const char* sync_mode_name(DSR::SyncMode mode) +{ + switch (mode) { + case DSR::SyncMode::CRDT: return "CRDT"; + case DSR::SyncMode::LWW: return "LWW"; + } + return "UNKNOWN"; +} + +bool network_compatibility_or_fatal( + const char* channel, + uint32_t remote_version, + uint8_t remote_sync_mode, + DSR::SyncMode local_sync_mode) +{ + if (remote_version != DSR::DSR_PROTOCOL_VERSION) { + const auto message = std::string("DSRGraph aborting: incompatible protocol on ") + channel + + " remote=" + std::to_string(remote_version) + + " local=" + std::to_string(DSR::DSR_PROTOCOL_VERSION); + qFatal("%s", message.c_str()); + return false; + } + + const auto local_wire = DSR::sync_mode_wire_value(local_sync_mode); + if (remote_sync_mode != local_wire) { + const auto message = std::string("DSRGraph aborting: incompatible sync mode on ") + channel + + " remote=" + std::to_string(remote_sync_mode) + + " (" + sync_mode_name(static_cast(remote_sync_mode)) + ")" + + " local=" + std::to_string(local_wire) + + " (" + sync_mode_name(local_sync_mode) + ")"; + qFatal("%s", message.c_str()); + return false; + } + + return true; +} } ///////////////////////////////////////////////// @@ -56,15 +94,20 @@ DSRGraph::DSRGraph(GraphSettings settings) : agent_id(settings.agent_id), agent_name(std::move(settings.graph_name)), copy(false), + sync_mode(settings.sync_mode), tp(settings.theradpool_threads, "join"), tp_delta_attr(settings.attribute_threadpool_threads, "attr"), same_host(settings.same_host), generator(settings.agent_id), - log_level(settings.log_level) + log_level(settings.log_level), + engine_(std::make_unique(*this)) { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph"); qDebug() << "Agent name: " << QString::fromStdString(agent_name); + if (sync_mode != SyncMode::CRDT) { + qFatal("DSRGraph aborting: SyncMode::LWW is not implemented yet"); + } { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph setup utils/signals"); utils = std::make_unique(this); @@ -186,7 +229,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : } DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_file, bool all_same_host, int8_t domain_id, SignalMode mode) - : DSR::DSRGraph(GraphSettings {id, 5, 1, name, dsr_input_file, "", all_same_host, GraphSettings::LOGLEVEL::INFOL, domain_id, mode}) + : DSR::DSRGraph(GraphSettings {id, 5, 1, name, dsr_input_file, "", all_same_host, GraphSettings::LOGLEVEL::INFOL, domain_id, mode, SyncMode::CRDT}) {} @@ -199,6 +242,29 @@ DSRGraph::~DSRGraph() } } +void DSRGraph::reset() +{ + dsrparticipant.remove_participant_and_entities(); + engine_ = std::make_unique(*this); + deleted.clear(); + name_map.clear(); + id_map.clear(); + edges.clear(); + edgeType.clear(); + nodeType.clear(); + to_edges.clear(); +} + +CRDTSyncEngine& DSRGraph::crdt_engine() +{ + return static_cast(*engine_); +} + +const CRDTSyncEngine& DSRGraph::crdt_engine() const +{ + return static_cast(*engine_); +} + ////////////////////////////////////// /// NODE METHODS ///////////////////////////////////// @@ -226,27 +292,7 @@ std::optional DSRGraph::get_node(uint64_t id) std::tuple> DSRGraph::insert_node_(CRDTNode &&node) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_node_"); - if (!deleted.contains(node.id())) - { - if (auto it = nodes.find(node.id()); it != nodes.end() and not it->second.empty() and it->second.read_reg() == node) - { - return {true, {}}; - } - - uint64_t id = node.id(); - { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_ update maps"); - update_maps_node_insert(id, node); - } - mvreg delta; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_ mvreg write"); - delta = nodes[id].write(std::move(node)); - } - return {true, CRDTNode_to_Msg(agent_id, id, std::move(delta))}; - } - return {false, {}}; + return crdt_engine().insert_node_raw(std::move(node)); } template @@ -300,7 +346,7 @@ std::optional DSRGraph::insert_node_with_id(No &&node) std::unique_lock lock(_mutex); std::shared_lock lck_cache(_mutex_cache_maps); //Check id - if (nodes.contains(node.id())) { + if (get_node_ptr_(node.id()) != nullptr) { DSR_LOG_WARNING("[INSERT_NODE_WITH_ID] Node id already exists", node.id(), node.type()); return {}; } @@ -334,44 +380,7 @@ template std::optional DSRGraph::insert_node_with_id(DSR: std::tuple> DSRGraph::update_node_(CRDTNode &&node) { - CORTEX_PROFILE_ZONE_N("DSRGraph::update_node_"); - if (!deleted.contains(node.id())) - { - auto nit = nodes.find(node.id()); - if (nit != nodes.end() && !nit->second.empty()) - { - DSR::MvregNodeAttrVec atts_deltas; - auto &iter = nit->second.read_reg().attrs(); - //New attributes and updates. - for (auto &[k, att]: node.attrs()) { - auto &attr_reg = iter.try_emplace(k, mvreg()).first->second; - if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { - auto delta = attr_reg.write(std::move(att.read_reg())); - atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(agent_id, node.id(), node.id(), k, std::move(delta))); - } - } - //Remove old attributes. - auto it_a = iter.begin(); - while (it_a != iter.end()) { - const std::string &k = it_a->first; - if (ignored_attributes.contains(k)) { - it_a = iter.erase(it_a); - } else if (!node.attrs().contains(k)) { - auto delta = it_a->second.reset(); - atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); - it_a = iter.erase(it_a); - } else { - ++it_a; - } - } - - return {true, std::move(atts_deltas)}; - } - } - - return {false, {}}; + return crdt_engine().update_node_raw(std::move(node)); } template bool DSRGraph::update_node(No &&node) @@ -394,7 +403,7 @@ requires (std::is_same_v, DSR::Node>) throw std::runtime_error( (std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (nodes.contains(node.id())) { + else if (get_node_ptr_(node.id()) != nullptr) { lck_cache.unlock(); std::tie(updated, vec_node_attr) = update_node_(user_node_to_crdt(std::forward(node))); } @@ -427,40 +436,7 @@ template bool DSRGraph::update_node(DSR::Node&&); std::tuple, std::optional, std::vector> DSRGraph::delete_node_(uint64_t id, const CRDTNode &node) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node_"); - - std::vector deleted_edges; - std::vector delta_vec; - - // Delete all edges from this node. - for (const auto &v : node.fano()) { - deleted_edges.emplace_back(v.second.read_reg()); - } - // Get remove delta. - auto delta = nodes[id].reset(); - DSR::MvregNodeMsg delta_remove = CRDTNode_to_Msg(agent_id, id, std::move(delta)); - // Search and remove incoming edges using to_edges cache: O(k) instead of O(n). - { - decltype(to_edges)::mapped_type incoming; - { - std::shared_lock lck_cache(_mutex_cache_maps); - if (to_edges.contains(id)) - incoming = to_edges.at(id); - } - for (const auto &[from, type] : incoming) - { - if (!nodes.contains(from)) continue; - auto &visited_node = nodes.at(from).read_reg(); - deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); - auto delta_fano = visited_node.fano().at({id, type}).reset(); - delta_vec.emplace_back(CRDTEdge_to_Msg(agent_id, from, id, type, std::move(delta_fano))); - visited_node.fano().erase({id, type}); - update_maps_edge_delete(from, id, type); - } - } - update_maps_node_delete(id, node); - - return make_tuple(true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)); + return crdt_engine().delete_node_raw(id, node); } bool DSRGraph::delete_node(const DSR::Node &node) @@ -574,16 +550,14 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) std::vector DSRGraph::get_nodes() { std::shared_lock lock(_mutex); - + auto snapshot = crdt_engine().snapshot(); std::vector nodes_; - nodes_.reserve(nodes.size()); - - for (auto &[id, N]: nodes) + nodes_.reserve(snapshot.size()); + for (auto& [id, node] : snapshot) { - nodes_.emplace_back(N.read_reg()); + nodes_.emplace_back(std::move(node)); } return nodes_; - } @@ -619,18 +593,7 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector DSRGraph::get_edge_(uint64_t from, uint64_t to, const std::string &key) { - auto from_it = nodes.find(from); - if (from_it == nodes.end() || from_it->second.empty() || !nodes.contains(to)) { - return {}; - } - - auto& fano = from_it->second.read_reg().fano(); - auto edge = fano.find({to, key}); - if (edge != fano.end() && !edge->second.empty()) { - return edge->second.read_reg(); - } - - return {}; + return crdt_engine().get_crdt_edge(from, to, key); } std::optional DSRGraph::get_edge(const std::string &from, const std::string &to, const std::string &key) @@ -676,50 +639,7 @@ std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::st std::tuple, std::optional> DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_or_assign_edge_"); - std::optional delta_edge; - std::optional delta_attrs; - - if (nodes.contains(from)) - { - auto &node = nodes.at(from).read_reg(); - //check if we are creating an edge or we are updating it. - auto fano_it = node.fano().find({to, attrs.type()}); - if (fano_it != node.fano().end()) - { - //Update - DSR::MvregEdgeAttrVec atts_deltas; - auto &iter_edge = fano_it->second.read_reg().attrs(); - for (auto &[k, att]: attrs.attrs()) { - auto &attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; - if (attr_reg.empty() or att.read_reg() != attr_reg.read_reg()) { - auto delta = attr_reg.write(std::move(att.read_reg())); - atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), k, std::move(delta))); - } - } - auto it = iter_edge.begin(); - while (it != iter_edge.end()) { - if (!attrs.attrs().contains(it->first)) { - std::string att = it->first; - auto delta = it->second.reset(); - it = iter_edge.erase(it); - atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); - } else { - ++it; - } - } - return {true, {}, std::move(atts_deltas)}; - } else - { // Insert - std::string att_type = attrs.type(); - auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); - update_maps_edge_insert(from, to, att_type); - return {true, CRDTEdge_to_Msg(agent_id, from, to, std::move(att_type), std::move(delta)), {}}; - } - } - return {false, {}, {}}; + return crdt_engine().insert_or_assign_edge_raw(std::move(attrs), from, to); } template @@ -735,7 +655,7 @@ requires (std::is_same_v, DSR::Edge>) std::unique_lock lock(_mutex); uint64_t from = attrs.from(); uint64_t to = attrs.to(); - if (nodes.contains(from) && nodes.contains(to)) { + if (get_node_ptr_(from) != nullptr && get_node_ptr_(to) != nullptr) { std::tie(result, delta_edge, delta_attrs) = insert_or_assign_edge_(user_edge_to_crdt(std::forward(attrs)), from, to); } else { std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << from << " or " << to @@ -776,16 +696,7 @@ template bool DSRGraph::insert_or_assign_edge(const DSR::Edge& std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) { - if (nodes.contains(from)) { - auto &node = nodes.at(from).read_reg(); - if (node.fano().contains({to, key})) { - auto delta = node.fano().at({to, key}).reset(); - node.fano().erase({to, key}); - update_maps_edge_delete(from, to, key); - return CRDTEdge_to_Msg(agent_id, from, to, key, std::move(delta)); - } - } - return {}; + return crdt_engine().delete_edge_raw(from, to, key); } bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) @@ -862,15 +773,9 @@ std::vector DSRGraph::get_edges_by_type(const std::string &type) if (edgeType.contains(type)) { edges_.reserve(edgeType.at(type).size()); for (auto &[from, to] : edgeType.at(type)) { - auto node_it = nodes.find(from); - if (node_it == nodes.end() || node_it->second.empty()) { - continue; - } - - auto &fano = node_it->second.read_reg().fano(); - auto edge_it = fano.find({to, type}); - if (edge_it != fano.end()) { - edges_.emplace_back(edge_it->second.read_reg()); + auto edge = get_edge_(from, to, type); + if (edge.has_value()) { + edges_.emplace_back(std::move(edge.value())); } } } @@ -896,13 +801,13 @@ std::vector DSRGraph::get_edges_to_id(uint64_t id) std::optional, DSR::Edge>> DSRGraph::get_edges(uint64_t id) { std::shared_lock lock(_mutex); - auto node_it = nodes.find(id); - if (node_it == nodes.end() || node_it->second.empty()) { + const auto* node = get_node_ptr_(id); + if (node == nullptr) { return std::nullopt; } std::map, DSR::Edge> edges_; - for (const auto &[key, edge_reg] : node_it->second.read_reg().fano()) { + for (const auto &[key, edge_reg] : node->fano()) { edges_.emplace(key, DSR::Edge(edge_reg.read_reg())); } return edges_; @@ -915,13 +820,8 @@ std::optional, DSR::Edge>> DSRGraph::g std::map DSRGraph::getCopy() const { - std::map mymap; std::shared_lock lock(_mutex); - - for (auto &[key, val] : nodes) - mymap.emplace(key, Node(val.read_reg())); - - return mymap; + return crdt_engine().snapshot(); } ////////////////////////////////////////////////////////////////////////////// @@ -930,17 +830,12 @@ std::map DSRGraph::getCopy() const std::optional DSRGraph::get_(uint64_t id) { - if (const auto* node = get_node_ptr_(id); node != nullptr) - return std::make_optional(*node); - return {}; + return crdt_engine().get_crdt_node(id); } const CRDTNode* DSRGraph::get_node_ptr_(uint64_t id) const { - auto it = nodes.find(id); - if (it != nodes.end() and !it->second.empty()) - return &it->second.read_reg(); - return nullptr; + return crdt_engine().get_node_ptr(id); } std::optional DSRGraph::get_node_level(const Node &n) @@ -972,10 +867,8 @@ std::string DSRGraph::get_node_type(Node &n) ////////////////////////////////////////////////////////////////////////////////////////////// -inline void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional &n) +void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional &n) { - nodes.erase(id); - std::unique_lock lck(_mutex_cache_maps); if (id_map.contains(id)) { @@ -1008,7 +901,7 @@ inline void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional lck(_mutex_cache_maps); @@ -1024,7 +917,7 @@ inline void DSRGraph::update_maps_node_insert(uint64_t id, const CRDTNode &n) } -inline void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key) +void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key) { std::unique_lock lck(_mutex_cache_maps); @@ -1044,7 +937,7 @@ inline void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const } } -inline void DSRGraph::update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key) +void DSRGraph::update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key) { std::unique_lock lck(_mutex_cache_maps); @@ -1073,504 +966,41 @@ std::optional DSRGraph::get_name_from_id(uint64_t id) size_t DSRGraph::size() const { std::shared_lock lock(_mutex); - return nodes.size(); + return crdt_engine().size(); } bool DSRGraph::empty(const uint64_t &id) { - auto it = nodes.find(id); - if (it != nodes.end()) { - return it->second.empty(); - } else - return false; + return get_node_ptr_(id) == nullptr; } void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_node"); - - std::optional maybe_deleted_node = {}; - try { - if (!protocol_version_matches(log_level, "DSR_NODE", mvreg.protocol_version)) { - return; - } - bool signal = false, joined = false; - auto id = mvreg.id; - uint64_t timestamp = mvreg.timestamp; - - DSR_LOG_DEBUG("[JOIN_NODE] id:", id, "timestamp:", timestamp, "agent:", mvreg.agent_id); - auto crdt_delta = std::move(mvreg.dk); - bool d_empty = crdt_delta.empty(); - - - auto delete_unprocessed_deltas = [&](){ - unprocessed_delta_node_att.erase(id); - decltype(unprocessed_delta_edge_from)::node_type node_handle = unprocessed_delta_edge_from.extract(id); - while (!node_handle.empty()) - { - node_handle = unprocessed_delta_edge_from.extract(id); - } - - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return std::get<0>(it.second) == id;}); - std::erase_if(unprocessed_delta_edge_att, - [&](auto &it){ return std::get<0>(it.first) == id or std::get<1>(it.first) == id;}); - }; - - - std::unordered_set,hash_tuple> map_new_to_edges = {}; - std::unordered_set,hash_tuple> map_new_from_edges = {}; - - auto consume_unprocessed_deltas = [&](){ - decltype(unprocessed_delta_node_att)::node_type node_handle_node_att = unprocessed_delta_node_att.extract(id); - while (!node_handle_node_att.empty()) - { - auto &[att_name, delta, timestamp_node_att] = node_handle_node_att.mapped(); - DSR_LOG_DEBUG("[JOIN_NODE] node_att", id, att_name, (timestamp < timestamp_node_att)); - if (timestamp < timestamp_node_att) { - process_delta_node_attr(id, att_name,std::move(delta)); - } - node_handle_node_att = unprocessed_delta_node_att.extract(id); - } - - decltype(unprocessed_delta_edge_from)::node_type node_handle_edge = unprocessed_delta_edge_from.extract(id); - while (!node_handle_edge.empty()) { - auto &[to, type, delta, timestamp_edge] = node_handle_edge.mapped(); - auto att_key = std::tuple{id, to, type}; - DSR_LOG_DEBUG("[JOIN_NODE] unprocessed_delta_edge_from", id, to, type, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge) { - if (process_delta_edge(id, to, type, std::move(delta))) map_new_to_edges.emplace(to, type); - } - if (nodes.contains(id) and nodes.at(id).read_reg().fano().contains({to, type})) { - decltype(unprocessed_delta_edge_att)::node_type node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - while (!node_handle_edge_att.empty()) { - auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); - DSR_LOG_DEBUG("[JOIN_NODE] edge_att", id, to, type, att_name, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge_att) { - process_delta_edge_attr(id, to, type, att_name, std::move(delta)); - } - node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - } - } - std::erase_if(unprocessed_delta_edge_to, - [to = to, id = id, type = type](auto& it) { return it.first == to && std::get<0>(it.second) == id && std::get<1>(it.second) == type;}); - node_handle_edge = unprocessed_delta_edge_from.extract(id); - } - - node_handle_edge = unprocessed_delta_edge_to.extract(id); - while (!node_handle_edge.empty()) { - auto &[from, type, delta, timestamp_edge] = node_handle_edge.mapped(); - auto att_key = std::tuple{from, id, type}; - DSR_LOG_DEBUG("[JOIN_NODE] unprocessed_delta_edge_to", from, id, type, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge) { - if (process_delta_edge(from, id, type, std::move(delta))) map_new_from_edges.emplace(from, id, type); - } - if (nodes.contains(from) and nodes.at(from).read_reg().fano().contains({id, type})) { - decltype(unprocessed_delta_edge_att)::node_type node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - while (!node_handle_edge_att.empty()) { - auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); - DSR_LOG_DEBUG("[JOIN_NODE] edge_att", from, id, type, att_name, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge_att) { - process_delta_edge_attr(from, id, type, att_name, std::move(delta)); - } - node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - } - } - - node_handle_edge = unprocessed_delta_edge_to.extract(id); - } - - }; - - std::optional,hash_tuple>> cache_map_to_edges = {}; - // Snapshot the data needed for signal emission while the lock is held. - // nodes.at(id) must NOT be accessed after the lock is released: a concurrent - // insert_node_/update_node call on the same id runs nodes[id].write() which - // calls dk.rmv() (clears dk.ds) followed by dk.add(), leaving a window where - // read_reg()'s assert(dk.ds.size() >= 1) would fire. - std::string node_type_snapshot; - std::vector> from_edges_snapshot; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node crdt merge"); - std::unique_lock lock(_mutex); - if (!deleted.contains(id)) { - joined = true; - if (auto it = nodes.find(id); it != nodes.end() && !it->second.empty()) { - maybe_deleted_node = it->second.read_reg(); - } - nodes[id].join(std::move(crdt_delta)); - if (nodes.at(id).empty() or d_empty) { - nodes.erase(id); - cache_map_to_edges = to_edges[id]; - update_maps_node_delete(id, maybe_deleted_node); - delete_unprocessed_deltas(); - } else { - signal = true; - const auto& reg = nodes.at(id).read_reg(); - update_maps_node_insert(id, reg); - consume_unprocessed_deltas(); - // Snapshot type and outgoing edges before the lock is released. - node_type_snapshot = reg.type(); - for (const auto &[k, v] : reg.fano()) { - from_edges_snapshot.emplace_back(k.first, k.second); - } - } - } else { - delete_unprocessed_deltas(); - } - } - - uint32_t msg_agent_id = mvreg.agent_id; - if (joined) { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node signal emit"); - if (signal) { - DSR_LOG_DEBUG("[JOIN_NODE] node inserted/updated:", id, node_type_snapshot); - emitter.update_node_signal(id, node_type_snapshot, SignalInfo{ msg_agent_id }); - for (const auto &[to_id, edge_type] : from_edges_snapshot) { - DSR_LOG_DEBUG("[JOIN_NODE] add edge FROM:", id, to_id, edge_type); - emitter.update_edge_signal(id, to_id, edge_type, SignalInfo{ msg_agent_id }); - } - - for (const auto &[k, v]: map_new_to_edges) - { - DSR_LOG_DEBUG("[JOIN_NODE] add edge TO:", k, id, v); - emitter.update_edge_signal(k, id, v, SignalInfo{ msg_agent_id }); - } - - for (const auto &[from, to, type]: map_new_from_edges) - { - DSR_LOG_DEBUG("[JOIN_NODE] add edge FROM (unprocessed_to):", from, to, type); - emitter.update_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); - } - } else { - DSR_LOG_DEBUG("[JOIN_NODE] node deleted:", id); - emitter.del_node_signal(id, SignalInfo{ msg_agent_id }); - if (maybe_deleted_node.has_value()) { - Node tmp_node(*maybe_deleted_node); - emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id }); - for (const auto &node: maybe_deleted_node->fano()) { - DSR_LOG_DEBUG("[JOIN_NODE] delete edge FROM:", node.second.read_reg().from(), node.second.read_reg().to(), node.second.read_reg().type()); - emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), - node.second.read_reg().type(), SignalInfo{ msg_agent_id }); - Edge tmp_edge(node.second.read_reg()); - emitter.deleted_edge_signal(tmp_edge, SignalInfo{ agent_id }); - } - } - - //TODO: deleted_edge_signal. update_maps_node_delete was called before so the maps are probably wrong... - for (const auto &[from, type] : cache_map_to_edges.value()) { - DSR_LOG_DEBUG("[JOIN_NODE] delete edge TO:", from, id, type); - emitter.del_edge_signal(from, id, type, SignalInfo{ msg_agent_id }); - //emitter.deleted_edge_signal(Edge(node.second.read_reg())); TODO: fix this - } - - } - } - - } - catch (const std::exception &e) { - std::cout << "EXCEPTION: " << __FILE__ << " " << __FUNCTION__ << ":" << __LINE__ << " " << e.what() - << std::endl; - } -} - -bool DSRGraph::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg && delta) -{ - CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_edge"); - const bool d_empty = delta.empty(); - auto &node = nodes.at(from).read_reg(); - node.fano()[{to, type}].join(std::move(delta)); - if (d_empty or !node.fano().contains({to, type})) { //Remove - node.fano().erase({to, type}); - update_maps_edge_delete(from, to, type); - return false; - } else { //Insert - update_maps_edge_insert(from, to, type); - return true; - } + crdt_engine().join_delta_node(std::move(mvreg)); } void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_edge"); - try { - if (!protocol_version_matches(log_level, "DSR_EDGE", mvreg.protocol_version)) { - return; - } - bool signal = false, joined = false; - auto from = mvreg.id; - auto to = mvreg.to; - std::string type = mvreg.type; - DSR_LOG_DEBUG("[JOIN_EDGE] from:", from, "to:", to, "type:", type, "agent:", mvreg.agent_id); - - uint64_t timestamp = mvreg.timestamp; - - //Clean remaining delta edges. - auto delete_unprocessed_deltas = [&](){ - //1. Delete all the delta attr for the edge. - //2. Delete all unprocessed delta edges with the same key (from and to) - //unprocessed_delta_edge_from.erase(from); // This should not be needed. - unprocessed_delta_edge_att.erase(std::tuple{from, to, type}); - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return it.first == to && std::get<0>(it.second) == from && type == std::get<1>(it.second);}); - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return it.first == from && std::get<0>(it.second) == to && type == std::get<1>(it.second);}); - }; - - //Consumes all delta attributes and deletes a possible previous delta from unprocessed map. - auto consume_unprocessed_deltas = [&](){ - //1. Consume all the delta attributes for the edge key - //2. Delete all unprocessed delta edges with the same key (from and to) - auto att_key = std::tuple{from, to, type}; - decltype(unprocessed_delta_edge_att)::node_type node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - while (!node_handle_edge_att.empty()) - { - auto &[att_name, delta, timestamp_delta_edge] = node_handle_edge_att.mapped(); - if (timestamp < timestamp_delta_edge) { - process_delta_edge_attr(from, to, type, att_name,std::move(delta)); - } - node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - } - - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return it.first == to && std::get<0>(it.second) == from && std::get<1>(it.second) == type; }); - std::erase_if(unprocessed_delta_edge_from, - [&](auto &it){ return it.first == from && std::get<0>(it.second) == to && std::get<1>(it.second) == type; }); - }; - - uint32_t msg_agent_id = mvreg.agent_id; - std::optional deleted_edge; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge crdt merge"); - auto crdt_delta = std::move(mvreg.dk); - std::unique_lock lock(_mutex); - deleted_edge = get_edge_(from, to, type); - //Check if the node where we are joining the edge exist. - bool cfrom{nodes.contains(from)}, cto{nodes.contains(to)}; - bool dfrom{deleted.contains(from)}, dto{deleted.contains(to)}; - if (cfrom and cto) { - joined = true; - signal = process_delta_edge(from, to, type, std::move(crdt_delta)); - if (signal) { - consume_unprocessed_deltas(); - } - else { - delete_unprocessed_deltas(); - } - - } else if (!dfrom and !dto) { - //We should receive the node later. To avoid storing more than one element on the unprocessed cache we use the mvreg join. - bool find = false; - for (auto [begin, end] = unprocessed_delta_edge_from.equal_range(from); begin != end; ++begin) { //There should not be many elements in this iteration - if (std::get<0>(begin->second) == to && std::get<1>(begin->second) == type){ - std::get<2>(begin->second).join(::mvreg(crdt_delta)); - DSR_LOG_DEBUG("[JOIN_EDGE] JOIN UNPROCESSED (from)", from, to, type); - find = true; break; - } - } - - for (auto [begin, end] = unprocessed_delta_edge_from.equal_range(to); begin != end; ++begin) { //There should not be many elements in this iteration - if (std::get<0>(begin->second) == from && std::get<1>(begin->second) == type){ - std::get<2>(begin->second).join(std::move(crdt_delta)); - DSR_LOG_DEBUG("[JOIN_EDGE] JOIN UNPROCESSED (to)", from, to, type); - find = true; break; - } - } - - if (!find) { - if (!cfrom) { - DSR_LOG_DEBUG("[JOIN_EDGE] INSERT UNPROCESSED, no from", from, "unprocessed_delta_edge_from"); - unprocessed_delta_edge_from.emplace(from, std::tuple{to, type, crdt_delta, timestamp}); - } - if (cfrom && !cto) - { - DSR_LOG_DEBUG("[JOIN_EDGE] INSERT UNPROCESSED, no to", to, "unprocessed_delta_edge_to"); - unprocessed_delta_edge_to.emplace(to, std::tuple{from, type, std::move(crdt_delta), timestamp}); - } - } else { - DSR_LOG_WARNING("Unhandled case, should sync deleted_nodes set"); - } - } else { - DSR_LOG_DEBUG("[JOIN_EDGE] edge is part of deleted node, cleaning unprocessed"); - auto node_deleted = [&](uint64_t id){ - unprocessed_delta_edge_from.erase(id); - unprocessed_delta_node_att.erase(id); - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return std::get<0>(it.second) == id;}); - std::erase_if(unprocessed_delta_edge_att, - [&](auto &it){ return std::get<0>(it.first) == id;}); - }; - if (dfrom) node_deleted(from); - if (dto) node_deleted(to); - } - } - - if (joined) { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge signal emit"); - if (signal) { - DSR_LOG_DEBUG("[JOIN_EDGE] add edge:", from, to, type); - emitter.update_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); - } else { - DSR_LOG_DEBUG("[JOIN_EDGE] delete edge:", from, to, type); - emitter.del_edge_signal(from, to, type, SignalInfo{ msg_agent_id }); - if (deleted_edge.has_value()) { - emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id }); - } - } - } - - } catch (const std::exception &e) { - std::cout << "EXCEPTION: " << __FILE__ << " " << __FUNCTION__ << ":" << __LINE__ << " " << e.what() - << std::endl; - } -} - - -void DSRGraph::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg && attr) -{ - CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_node_attr"); - const bool d_empty = attr.empty(); - auto &n = nodes.at(id).read_reg(); - n.attrs()[att_name].join(std::move(attr)); - //Check if we are inserting or deleting. - if (d_empty or not n.attrs().contains(att_name)) { //Remove - n.attrs().erase(att_name); - } + crdt_engine().join_delta_edge(std::move(mvreg)); } std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_node_attr"); - try { - if (!protocol_version_matches(log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { - return std::nullopt; - } - bool joined = false; - auto id = mvreg.id; - std::string att_name = mvreg.attr_name; - uint64_t timestamp = mvreg.timestamp; - DSR_LOG_DEBUG("[JOIN_NODE_ATTR] node:", id, "attr:", att_name); - { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_node_attr crdt merge"); - auto crdt_delta = std::move(mvreg.dk); - std::unique_lock lock(_mutex); - //Check if the node where we are joining the edge exist. - if (nodes.contains(id)) { - joined = true; - process_delta_node_attr(id, att_name, std::move(crdt_delta)); - std::erase_if(unprocessed_delta_node_att, - [&](auto &it){ return it.first == id && std::get<0>(it.second) == att_name;}); - } else if (!deleted.contains(id)) { - bool find = false; - for (auto [begin, end] = unprocessed_delta_node_att.equal_range(id); begin != end; ++begin) { //There should not be many elements in this iteration - if (std::get<0>(begin->second) == att_name ){ - std::get<1>(begin->second).join(std::move(crdt_delta)); - find = true; break; - } - } - if (!find) { - DSR_LOG_DEBUG("[JOIN_NODE_ATTR] storing to unprocessed cache, node", id, att_name); - unprocessed_delta_node_att.emplace(id, std::tuple{att_name, std::move(crdt_delta), timestamp}); - } - } else { - unprocessed_delta_edge_from.erase(id); - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return std::get<0>(it.second) == id;}); - unprocessed_delta_node_att.erase(id); - std::erase_if(unprocessed_delta_edge_att, - [&](auto &it){ return std::get<0>(it.first) == id;}); - } - } - - if (joined) { - return att_name; - } - - } catch (const std::exception &e) { - std::cout << "EXCEPTION: " << __FILE__ << " " << __FUNCTION__ << ":" << __LINE__ << " " << e.what() - << std::endl; - } - - return std::nullopt; -} - -void DSRGraph::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg && attr) -{ - CORTEX_PROFILE_ZONE_N("DSRGraph::process_delta_edge_attr"); - const bool d_empty = attr.empty(); - auto &n = nodes.at(from).read_reg().fano().at({to, type}).read_reg(); - n.attrs()[att_name].join(std::move(attr)); - //Check if we are inserting or deleting. - if (d_empty or !n.attrs().contains(att_name)) { //Remove - n.attrs().erase(att_name); - } + return crdt_engine().join_delta_node_attr(std::move(mvreg)); } std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::join_delta_edge_attr"); - try { - if (!protocol_version_matches(log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { - return std::nullopt; - } - bool joined = false; - auto from = mvreg.id; - auto to = mvreg.to_node; - std::string type = mvreg.type; - std::string att_name = mvreg.attr_name; - uint64_t timestamp = mvreg.timestamp; - DSR_LOG_DEBUG("[JOIN_EDGE_ATTR] edge:", from, to, type, "attr:", att_name); - - { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_delta_edge_attr crdt merge"); - auto crdt_delta = std::move(mvreg.dk); - std::unique_lock lock(_mutex); - //Check if the node where we are joining the edge exist. - if (nodes.contains(from) and nodes.at(from).read_reg().fano().contains({to, type})) - { - joined = true; - process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); - std::erase_if(unprocessed_delta_edge_att, - [&](auto &it){ return it.first == std::tuple{from, to, type} && std::get<0>(it.second) == att_name;}); - } else if (!deleted.contains(from)){ - bool find = false; - for (auto [begin, end] = unprocessed_delta_edge_att.equal_range(std::tuple{from, to, type}); begin != end; ++begin) { //There should not be many elements in this iteration - if (std::get<0>(begin->second) == att_name ){ - std::get<1>(begin->second).join(std::move(crdt_delta)); - find = true; break; - } - } - if (!find) { - DSR_LOG_DEBUG("[JOIN_EDGE_ATTR] storing to unprocessed cache, edge", from, to, type, att_name); - unprocessed_delta_edge_att.emplace(std::tuple{from, to, type}, std::tuple{att_name, std::move(crdt_delta), timestamp}); - } - } else { //If the node is deleted - unprocessed_delta_edge_from.erase(from); - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return std::get<0>(it.second) == from;}); - unprocessed_delta_node_att.erase(from); - std::erase_if(unprocessed_delta_edge_att, - [&](auto &it){ return std::get<0>(it.first) == from;}); - } - } - - if (joined) { - return att_name; - } - - } catch (const std::exception &e) { - std::cout << "EXCEPTION: " << __FILE__ << " " << __FUNCTION__ << ":" << __LINE__ << " " << e.what() - << std::endl; - } - - return std::nullopt; + return crdt_engine().join_delta_edge_attr(std::move(mvreg)); } void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) { + crdt_engine().join_full_graph(std::move(full_graph)); +#if 0 CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph"); if (!protocol_version_matches(log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { return; @@ -1720,7 +1150,7 @@ void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) } } } - +#endif } std::pair DSRGraph::start_fullgraph_request_thread() @@ -1752,19 +1182,8 @@ void DSRGraph::start_subscription_threads() std::map DSRGraph::Map() { - CORTEX_PROFILE_ZONE_N("DSRGraph::Map"); std::shared_lock lock(_mutex); - std::map m; - for (auto &kv : nodes) { - DSR::MvregNodeMsg msg; - msg.dk = kv.second; - msg.id = kv.first; - msg.agent_id = agent_id; - msg.timestamp = get_unix_timestamp(); - msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; - m.emplace(kv.first, std::move(msg)); - } - return m; + return crdt_engine().export_mvreg_map(); } void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info) { @@ -1809,7 +1228,7 @@ void DSRGraph::node_subscription_thread() if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { if (sample.agent_id != agent_id) { - if (!protocol_version_matches(log_level, "DSR_NODE", sample.protocol_version)) { + if (!network_compatibility_or_fatal("DSR_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { continue; } if (sample.id == CLEAR_DELETED_SIGNAL) { @@ -1822,7 +1241,9 @@ void DSRGraph::node_subscription_thread() qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " << m_info.sample_identity.writer_guid().entityId.value; } - tp.spawn_task(&DSRGraph::join_delta_node, this, std::move(sample)); + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); } } } else { @@ -1855,11 +1276,16 @@ void DSRGraph::edge_subscription_thread() if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); if (m_info.valid_data) { if (sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("DSR_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " << m_info.sample_identity.writer_guid().entityId.value; } - tp.spawn_task(&DSRGraph::join_delta_edge, this, std::move(sample)); + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); } } } else { @@ -1898,44 +1324,13 @@ void DSRGraph::edge_attrs_subscription_thread() } if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("DSR_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); - if (samples.vec.empty()) return; - - auto from = samples.vec.at(0).from_node; - auto to = samples.vec.at(0).to_node; - auto type = samples.vec.at(0).type; - auto sample_agent_id = samples.vec.at(0).agent_id; - - std::vector>> futures; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread join batch"); - for (auto &&sample: samples.vec) { - if (!ignored_attributes.contains(sample.attr_name)) { - futures.emplace_back(tp.spawn_task_waitable([this, sample = std::move(sample)]() mutable { - return join_delta_edge_attr(std::move(sample)); - })); - } - } - } - - std::vector sig (futures.size()); - { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread wait futures"); - for (auto &f: futures) - { - auto opt_str = f.get(); - if (opt_str.has_value()) - sig.emplace_back(std::move(opt_str.value())); - } - } - - { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread signal emit"); - emitter.update_edge_attr_signal(from, to, type, sig, SignalInfo{sample_agent_id}); - emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); - } - + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); }); } } @@ -1977,47 +1372,13 @@ void DSRGraph::node_attrs_subscription_thread() << m_info.sample_identity.writer_guid().entityId.value; } if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("DSR_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); - - if (samples.vec.empty()) return; - - auto id = samples.vec.at(0).id; - auto sample_agent_id = samples.vec.at(0).agent_id; - std::string type; - { - std::shared_lock lock(_mutex); - if (auto itn = nodes.find(id); itn != nodes.end()) type = itn->second.read_reg().type() ; - } - std::vector>> futures; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread join batch"); - for (auto &&s: samples.vec) { - if (!ignored_attributes.contains(s.attr_name)) { - futures.emplace_back(tp.spawn_task_waitable([this, samp{std::move(s)}]() mutable { - auto f = join_delta_node_attr(std::move(samp)); - return f; - })); - } - } - } - - std::vector sig (futures.size()); - { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread wait futures"); - for (auto &f: futures) - { - auto opt_str = f.get(); - if (opt_str.has_value()) - sig.emplace_back(std::move(opt_str.value())); - } - } - - { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread signal emit"); - emitter.update_node_attr_signal(id, sig, SignalInfo{sample_agent_id}); - emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); - } + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); }); } } @@ -2050,7 +1411,7 @@ void DSRGraph::fullgraph_server_thread() if (reader->take_next_sample(&sample, &m_info) == 0) { if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); if (m_info.valid_data) { - if (!protocol_version_matches(log_level, "GRAPH_REQUEST", sample.protocol_version)) { + if (!network_compatibility_or_fatal("GRAPH_REQUEST", sample.protocol_version, sample.sync_mode, sync_mode)) { continue; } { @@ -2064,6 +1425,7 @@ void DSRGraph::fullgraph_server_thread() mp.id = -1; mp.to_id = static_cast(sample.id); mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; + mp.sync_mode = sync_mode_wire_value(sync_mode); dsrpub_request_answer.write(&mp); continue; } else {} @@ -2076,13 +1438,9 @@ void DSRGraph::fullgraph_server_thread() qDebug() << " Received Full Graph request: from " << m_info.sample_identity.writer_guid().entityId.value; - DSR::OrMap mp; + auto full_graph_message = graph->engine_->export_full_graph(); + auto mp = std::get(std::move(full_graph_message)); mp.id = static_cast(graph->get_agent_id()); - mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; - { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread build full graph"); - mp.m = graph->Map(); - } dsrpub_request_answer.write(&mp); qDebug() << "Full graph written"; @@ -2117,7 +1475,7 @@ std::pair DSRGraph::fullgraph_request_thread() if (reader->take_next_sample(&sample, &m_info) == 0) { if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); if (m_info.valid_data) { - if (!protocol_version_matches(log_level, "GRAPH_ANSWER", sample.protocol_version)) { + if (!network_compatibility_or_fatal("GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { continue; } if (static_cast(sample.id) != graph->get_agent_id()) { @@ -2127,7 +1485,7 @@ std::pair DSRGraph::fullgraph_request_thread() << sample.m.size() << " elements"; tp.spawn_task([this, s = std::move(sample)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); - join_full_graph(std::move(s)); + engine_->import_full_graph(FullGraphMessage{std::move(s)}); }); qDebug() << "Synchronized."; sync = true; @@ -2161,6 +1519,7 @@ std::pair DSRGraph::fullgraph_request_thread() gr.from = dsrparticipant.getParticipant()->get_qos().name().to_string(); gr.id = static_cast(agent_id); gr.protocol_version = DSR::DSR_PROTOCOL_VERSION; + gr.sync_mode = sync_mode_wire_value(sync_mode); { CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread send request"); dsrpub_graph_request.write(&gr); @@ -2191,11 +1550,21 @@ std::pair DSRGraph::fullgraph_request_thread() ///// PRIVATE COPY ///////////////////////////////////////////////// -DSRGraph::DSRGraph(const DSRGraph &G) : agent_id(G.agent_id), copy(true), tp(1, "join-copy"), generator(G.agent_id) -{ - std::shared_lock lock(_mutex); - std::shared_lock lock_cache(_mutex_cache_maps); - nodes = G.nodes; +DSRGraph::DSRGraph(const DSRGraph &G) + : agent_id(G.agent_id), + agent_name(G.agent_name), + copy(true), + sync_mode(G.sync_mode), + ignored_attributes(G.ignored_attributes), + same_host(G.same_host), + generator(G.agent_id), + log_level(G.log_level), + engine_(std::make_unique(*this, G.crdt_engine())), + tp(1, "join-copy"), + tp_delta_attr(1, "attr-copy") +{ + std::shared_lock lock(G._mutex); + std::shared_lock lock_cache(G._mutex_cache_maps); utils = std::make_unique(this); id_map = G.id_map; deleted = G.deleted; @@ -2203,7 +1572,7 @@ DSRGraph::DSRGraph(const DSRGraph &G) : agent_id(G.agent_id), copy(true), tp(1, edges = G.edges; edgeType = G.edgeType; nodeType = G.nodeType; - same_host = G.same_host; + to_edges = G.to_edges; } std::unique_ptr DSRGraph::G_copy() diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp new file mode 100644 index 00000000..1e50016e --- /dev/null +++ b/api/dsr_crdt_sync_engine.cpp @@ -0,0 +1,993 @@ +#include "dsr/api/dsr_crdt_sync_engine.h" + +#include "dsr/api/dsr_api.h" +#include "dsr/api/dsr_logging.h" +#include "dsr/core/profiling.h" +#include "dsr/core/types/translator.h" + +#include +#include +#include + +using namespace DSR; + +namespace { +bool protocol_version_matches( + DSR::GraphSettings::LOGLEVEL log_level, + const char* channel, + uint32_t remote_version) +{ + if (remote_version == DSR::DSR_PROTOCOL_VERSION) { + return true; + } + + DSR_LOG_ERROR( + "[PROTOCOL] incompatible", channel, + "remote:", remote_version, + "local:", DSR::DSR_PROTOCOL_VERSION); + return false; +} +} + +CRDTSyncEngine::CRDTSyncEngine(DSRGraph& host) + : host_(host) +{ +} + +CRDTSyncEngine::CRDTSyncEngine(DSRGraph& host, const CRDTSyncEngine& other) + : host_(host), + nodes_(other.nodes_), + unprocessed_delta_node_att_(other.unprocessed_delta_node_att_), + unprocessed_delta_edge_from_(other.unprocessed_delta_edge_from_), + unprocessed_delta_edge_to_(other.unprocessed_delta_edge_to_), + unprocessed_delta_edge_att_(other.unprocessed_delta_edge_att_) +{ +} + +SyncBackendInfo CRDTSyncEngine::backend_info() const +{ + return {}; +} + +std::optional CRDTSyncEngine::get_node(uint64_t id) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + return Node(*node); + } + return {}; +} + +std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const +{ + if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + return Edge(std::move(edge.value())); + } + return {}; +} + +size_t CRDTSyncEngine::size() const +{ + return nodes_.size(); +} + +std::map CRDTSyncEngine::snapshot() const +{ + std::map out; + for (const auto& [id, reg] : nodes_) { + out.emplace(id, Node(reg.read_reg())); + } + return out; +} + +NodeMutationEffect CRDTSyncEngine::insert_node_local(Node&& node) +{ + NodeMutationEffect effect; + auto [applied, delta] = insert_node_raw(user_node_to_crdt(std::move(node))); + effect.applied = applied; + if (applied && delta.has_value()) { + effect.id = delta->id; + if (const auto* inserted = get_node_ptr(delta->id); inserted != nullptr) { + effect.type = inserted->type(); + } + } + return effect; +} + +NodeMutationEffect CRDTSyncEngine::update_node_local(Node&& node) +{ + NodeMutationEffect effect; + auto [applied, deltas] = update_node_raw(user_node_to_crdt(std::move(node))); + effect.applied = applied; + if (applied && deltas.has_value()) { + effect.changed_attributes.reserve(deltas->vec.size()); + for (const auto& item : deltas->vec) { + effect.changed_attributes.emplace_back(item.attr_name); + } + } + return effect; +} + +NodeMutationEffect CRDTSyncEngine::delete_node_local(uint64_t id) +{ + NodeMutationEffect effect; + if (auto node = get_crdt_node(id); node.has_value()) { + auto [applied, deleted_edges, _delta_node, _delta_edges] = delete_node_raw(id, *node); + effect.applied = applied; + effect.id = id; + effect.deleted_edges = std::move(deleted_edges); + if (node.has_value()) { + effect.deleted_node = Node(*node); + } + } + return effect; +} + +EdgeMutationEffect CRDTSyncEngine::insert_or_assign_edge_local(Edge&& edge) +{ + EdgeMutationEffect effect; + auto from = edge.from(); + auto to = edge.to(); + auto type = edge.type(); + auto [applied, _edge_delta, attr_deltas] = insert_or_assign_edge_raw(user_edge_to_crdt(std::move(edge)), from, to); + effect.applied = applied; + effect.from = from; + effect.to = to; + effect.type = std::move(type); + if (attr_deltas.has_value()) { + effect.changed_attributes.reserve(attr_deltas->vec.size()); + for (const auto& item : attr_deltas->vec) { + effect.changed_attributes.emplace_back(item.attr_name); + } + } + return effect; +} + +EdgeMutationEffect CRDTSyncEngine::delete_edge_local(uint64_t from, uint64_t to, const std::string& type) +{ + EdgeMutationEffect effect; + effect.deleted_edge = get_edge(from, to, type); + effect.applied = delete_edge_raw(from, to, type).has_value(); + effect.from = from; + effect.to = to; + effect.type = type; + return effect; +} + +void CRDTSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) +{ + if (auto* payload = std::get_if(&delta); payload != nullptr) { + join_delta_node(std::move(*payload)); + } +} + +void CRDTSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) +{ + if (auto* payload = std::get_if(&delta); payload != nullptr) { + join_delta_edge(std::move(*payload)); + } +} + +void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) +{ + auto* payload = std::get_if(&batch); + if (payload == nullptr || payload->vec.empty()) { + return; + } + + const auto id = payload->vec.front().id; + const auto sample_agent_id = payload->vec.front().agent_id; + std::vector changed_attributes; + for (auto&& item : payload->vec) { + if (host_.ignored_attributes.contains(item.attr_name)) { + continue; + } + if (auto changed = join_delta_node_attr(std::move(item)); changed.has_value()) { + changed_attributes.emplace_back(std::move(*changed)); + } + } + + if (!changed_attributes.empty()) { + std::string type; + { + std::shared_lock lock(host_._mutex); + if (const auto* node = get_node_ptr(id); node != nullptr) { + type = node->type(); + } + } + host_.emitter.update_node_attr_signal(id, changed_attributes, SignalInfo{sample_agent_id}); + host_.emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); + } +} + +void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) +{ + auto* payload = std::get_if(&batch); + if (payload == nullptr || payload->vec.empty()) { + return; + } + + const auto from = payload->vec.front().from_node; + const auto to = payload->vec.front().to_node; + const auto type = payload->vec.front().type; + const auto sample_agent_id = payload->vec.front().agent_id; + std::vector changed_attributes; + for (auto&& item : payload->vec) { + if (host_.ignored_attributes.contains(item.attr_name)) { + continue; + } + if (auto changed = join_delta_edge_attr(std::move(item)); changed.has_value()) { + changed_attributes.emplace_back(std::move(*changed)); + } + } + + if (!changed_attributes.empty()) { + host_.emitter.update_edge_attr_signal(from, to, type, changed_attributes, SignalInfo{sample_agent_id}); + host_.emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); + } +} + +void CRDTSyncEngine::import_full_graph(FullGraphMessage&& full_graph) +{ + if (auto* payload = std::get_if(&full_graph); payload != nullptr) { + join_full_graph(std::move(*payload)); + } +} + +FullGraphMessage CRDTSyncEngine::export_full_graph() const +{ + std::shared_lock lock(host_._mutex); + OrMap map; + map.id = static_cast(host_.agent_id); + map.protocol_version = DSR_PROTOCOL_VERSION; + map.sync_mode = sync_mode_wire_value(host_.sync_mode); + map.m = export_mvreg_map(); + return map; +} + +const CRDTNode* CRDTSyncEngine::get_node_ptr(uint64_t id) const +{ + auto it = nodes_.find(id); + if (it != nodes_.end() && !it->second.empty()) { + return &it->second.read_reg(); + } + return nullptr; +} + +std::optional CRDTSyncEngine::get_crdt_node(uint64_t id) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + return std::make_optional(*node); + } + return {}; +} + +std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const +{ + auto from_it = nodes_.find(from); + if (from_it == nodes_.end() || from_it->second.empty() || !nodes_.contains(to)) { + return {}; + } + + auto& fano = from_it->second.read_reg().fano(); + auto edge = fano.find({to, key}); + if (edge != fano.end() && !edge->second.empty()) { + return edge->second.read_reg(); + } + + return {}; +} + +std::tuple> CRDTSyncEngine::insert_node_raw(CRDTNode&& node) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_node_raw"); + if (!host_.deleted.contains(node.id())) + { + if (auto it = nodes_.find(node.id()); it != nodes_.end() and not it->second.empty() and it->second.read_reg() == node) + { + return {true, {}}; + } + + uint64_t id = node.id(); + host_.update_maps_node_insert(id, node); + auto delta = nodes_[id].write(std::move(node)); + return {true, CRDTNode_to_Msg(host_.agent_id, id, std::move(delta))}; + } + return {false, {}}; +} + +std::tuple> CRDTSyncEngine::update_node_raw(CRDTNode&& node) +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::update_node_raw"); + if (!host_.deleted.contains(node.id())) + { + auto nit = nodes_.find(node.id()); + if (nit != nodes_.end() && !nit->second.empty()) + { + MvregNodeAttrVec atts_deltas; + auto& iter = nit->second.read_reg().attrs(); + for (auto& [k, att] : node.attrs()) { + auto& attr_reg = iter.try_emplace(k, mvreg()).first->second; + if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { + auto delta = attr_reg.write(std::move(att.read_reg())); + atts_deltas.vec.emplace_back( + CRDTNodeAttr_to_Msg(host_.agent_id, node.id(), node.id(), k, std::move(delta))); + } + } + auto it_a = iter.begin(); + while (it_a != iter.end()) { + const std::string& k = it_a->first; + if (host_.ignored_attributes.contains(k)) { + it_a = iter.erase(it_a); + } else if (!node.attrs().contains(k)) { + auto delta = it_a->second.reset(); + atts_deltas.vec.emplace_back( + CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); + it_a = iter.erase(it_a); + } else { + ++it_a; + } + } + + return {true, std::move(atts_deltas)}; + } + } + + return {false, {}}; +} + +std::tuple, std::optional, std::vector> +CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::delete_node_raw"); + + std::vector deleted_edges; + std::vector delta_vec; + + for (const auto& v : node.fano()) { + deleted_edges.emplace_back(v.second.read_reg()); + } + auto delta = nodes_[id].reset(); + MvregNodeMsg delta_remove = CRDTNode_to_Msg(host_.agent_id, id, std::move(delta)); + { + decltype(host_.to_edges)::mapped_type incoming; + { + std::shared_lock lck_cache(host_._mutex_cache_maps); + if (host_.to_edges.contains(id)) + incoming = host_.to_edges.at(id); + } + for (const auto& [from, type] : incoming) + { + if (!nodes_.contains(from)) continue; + auto& visited_node = nodes_.at(from).read_reg(); + deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); + auto delta_fano = visited_node.fano().at({id, type}).reset(); + delta_vec.emplace_back(CRDTEdge_to_Msg(host_.agent_id, from, id, type, std::move(delta_fano))); + visited_node.fano().erase({id, type}); + host_.update_maps_edge_delete(from, id, type); + } + } + + host_.update_maps_node_delete(id, node); + + return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; +} + +std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint64_t to, const std::string& key) +{ + if (nodes_.contains(from)) { + auto& node = nodes_.at(from).read_reg(); + if (node.fano().contains({to, key})) { + auto delta = node.fano().at({to, key}).reset(); + node.fano().erase({to, key}); + host_.update_maps_edge_delete(from, to, key); + return CRDTEdge_to_Msg(host_.agent_id, from, to, key, std::move(delta)); + } + } + return {}; +} + +std::tuple, std::optional> +CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint64_t to) +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::insert_or_assign_edge_raw"); + std::optional delta_edge; + std::optional delta_attrs; + + if (nodes_.contains(from)) + { + auto& node = nodes_.at(from).read_reg(); + auto fano_it = node.fano().find({to, attrs.type()}); + if (fano_it != node.fano().end()) + { + MvregEdgeAttrVec atts_deltas; + auto& iter_edge = fano_it->second.read_reg().attrs(); + for (auto& [k, att] : attrs.attrs()) { + auto& attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; + if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { + auto delta = attr_reg.write(std::move(att.read_reg())); + atts_deltas.vec.emplace_back( + CRDTEdgeAttr_to_Msg(host_.agent_id, from, from, to, attrs.type(), k, std::move(delta))); + } + } + auto it = iter_edge.begin(); + while (it != iter_edge.end()) { + if (!attrs.attrs().contains(it->first)) { + std::string att = it->first; + auto delta = it->second.reset(); + it = iter_edge.erase(it); + atts_deltas.vec.emplace_back( + CRDTEdgeAttr_to_Msg(host_.agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); + } else { + ++it; + } + } + return {true, {}, std::move(atts_deltas)}; + } else + { + std::string att_type = attrs.type(); + auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); + host_.update_maps_edge_insert(from, to, att_type); + return {true, CRDTEdge_to_Msg(host_.agent_id, from, to, std::move(att_type), std::move(delta)), {}}; + } + } + return {false, {}, {}}; +} + +bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta) +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_edge"); + bool signal = false; + auto& node = nodes_.at(from).read_reg(); + auto& fanout = node.fano(); + std::optional prev = {}; + if (auto it = fanout.find({to, type}); it != fanout.end() && !it->second.empty()) { + prev = it->second.read_reg(); + } + auto& edge_reg = fanout[{to, type}]; + auto d_empty = delta.empty(); + edge_reg.join(std::move(delta)); + if (edge_reg.empty() || d_empty) { + fanout.erase({to, type}); + host_.update_maps_edge_delete(from, to, type); + signal = false; + } else { + host_.update_maps_edge_insert(from, to, type); + signal = !prev.has_value() || prev.value() != edge_reg.read_reg(); + } + return signal; +} + +void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr) +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_node_attr"); + auto& n = nodes_.at(id).read_reg(); + auto& attrs = n.attrs(); + auto& attr_reg = attrs[att_name]; + auto d_empty = attr.empty(); + attr_reg.join(std::move(attr)); + if (attr_reg.empty() || d_empty) { + attrs.erase(att_name); + } +} + +void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr) +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_edge_attr"); + auto& n = nodes_.at(from).read_reg().fano().at({to, type}).read_reg(); + auto& attrs = n.attrs(); + auto& attr_reg = attrs[att_name]; + auto d_empty = attr.empty(); + attr_reg.join(std::move(attr)); + if (attr_reg.empty() || d_empty) { + attrs.erase(att_name); + } +} + +void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node"); + const auto log_level = host_.log_level; + + std::optional maybe_deleted_node = {}; + try { + if (!protocol_version_matches(host_.log_level, "DSR_NODE", mvreg.protocol_version)) { + return; + } + bool signal = false, joined = false; + auto id = mvreg.id; + auto timestamp = mvreg.timestamp; + auto crdt_delta = std::move(mvreg.dk); + auto d_empty = crdt_delta.empty(); + std::unordered_set,hash_tuple> map_new_to_edges = {}; + std::unordered_set,hash_tuple> map_new_from_edges = {}; + std::optional,hash_tuple>> cache_map_to_edges = {}; + std::string current_type; + + auto delete_unprocessed_deltas = [&](){ + unprocessed_delta_node_att_.erase(id); + decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); + while (!node_handle.empty()) + { + unprocessed_delta_edge_att_.erase(std::tuple{id, std::get<0>(node_handle.mapped()), std::get<1>(node_handle.mapped())}); + node_handle = unprocessed_delta_edge_from_.extract(id); + } + std::erase_if(unprocessed_delta_edge_to_, + [&](auto &it){ return std::get<0>(it.second) == id;}); + std::erase_if(unprocessed_delta_edge_att_, + [&](auto &it){ return std::get<0>(it.first) == id || std::get<1>(it.first) == id;}); + }; + + auto consume_unprocessed_deltas = [&]() { + decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); + while (!node_handle_node_att.empty()) + { + auto &[att_name, delta, timestamp_node_att] = node_handle_node_att.mapped(); + if (timestamp < timestamp_node_att) { + process_delta_node_attr(id, att_name,std::move(delta)); + } + node_handle_node_att = unprocessed_delta_node_att_.extract(id); + } + + decltype(unprocessed_delta_edge_from_)::node_type node_handle_edge = unprocessed_delta_edge_from_.extract(id); + while (!node_handle_edge.empty()) { + auto &[to, type, delta, timestamp_edge] = node_handle_edge.mapped(); + auto att_key = std::tuple{id, to, type}; + DSR_LOG_DEBUG("[JOIN_NODE] unprocessed_delta_edge_from", id, to, type, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge) { + if (process_delta_edge(id, to, type, std::move(delta))) map_new_to_edges.emplace(to, type); + } + if (nodes_.contains(id) and nodes_.at(id).read_reg().fano().contains({to, type})) { + decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + while (!node_handle_edge_att.empty()) { + auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); + DSR_LOG_DEBUG("[JOIN_NODE] edge_att", id, to, type, att_name, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge_att) { + process_delta_edge_attr(id, to, type, att_name, std::move(delta)); + } + node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + } + } + std::erase_if(unprocessed_delta_edge_to_, + [to = to, id = id, type = type](auto& it) { return it.first == to && std::get<0>(it.second) == id && std::get<1>(it.second) == type;}); + node_handle_edge = unprocessed_delta_edge_from_.extract(id); + } + + node_handle_edge = unprocessed_delta_edge_to_.extract(id); + while (!node_handle_edge.empty()) { + auto &[from, type, delta, timestamp_edge] = node_handle_edge.mapped(); + auto att_key = std::tuple{from, id, type}; + DSR_LOG_DEBUG("[JOIN_NODE] unprocessed_delta_edge_to", from, id, type, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge) { + if (process_delta_edge(from, id, type, std::move(delta))) map_new_from_edges.emplace(from, id, type); + } + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({id, type})) { + decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + while (!node_handle_edge_att.empty()) { + auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); + DSR_LOG_DEBUG("[JOIN_NODE] edge_att", from, id, type, att_name, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge_att) { + process_delta_edge_attr(from, id, type, att_name, std::move(delta)); + } + node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + } + } + + node_handle_edge = unprocessed_delta_edge_to_.extract(id); + } + }; + + { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node crdt merge"); + std::unique_lock lock(host_._mutex); + if (!host_.deleted.contains(id)) { + if (auto it = nodes_.find(id); it != nodes_.end() && !it->second.empty()) { + maybe_deleted_node = it->second.read_reg(); + } + nodes_[id].join(std::move(crdt_delta)); + if (nodes_.at(id).empty() || d_empty) { + if (maybe_deleted_node.has_value()) { + cache_map_to_edges = host_.to_edges[id]; + } + host_.update_maps_node_delete(id, maybe_deleted_node); + delete_unprocessed_deltas(); + } else { + const auto& reg = nodes_.at(id).read_reg(); + current_type = reg.type(); + host_.update_maps_node_insert(id, reg); + consume_unprocessed_deltas(); + } + signal = !d_empty; + joined = true; + } + } + + if (joined) { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node signal emit"); + if (signal) { + host_.emitter.update_node_signal(id, current_type, SignalInfo{ mvreg.agent_id }); + if (const auto* current = get_node_ptr(id); current != nullptr) { + for (const auto &[k, v] : current->fano()) { + host_.emitter.update_edge_signal(id, k.first, k.second, SignalInfo{ mvreg.agent_id }); + } + } + + for (const auto &[k, v]: map_new_to_edges) + { + host_.emitter.update_edge_signal(k, id, v, SignalInfo{ mvreg.agent_id }); + } + } else { + host_.emitter.del_node_signal(id, SignalInfo{ mvreg.agent_id }); + if (maybe_deleted_node.has_value()) { + Node tmp_node(*maybe_deleted_node); + host_.emitter.deleted_node_signal(tmp_node, SignalInfo{ mvreg.agent_id }); + for (const auto &node: maybe_deleted_node->fano()) { + host_.emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), + node.second.read_reg().type(), SignalInfo{ mvreg.agent_id }); + Edge tmp_edge(node.second.read_reg()); + host_.emitter.deleted_edge_signal(tmp_edge, SignalInfo{ mvreg.agent_id }); + } + } + + if (cache_map_to_edges.has_value()) { + for (const auto &[from, type] : cache_map_to_edges.value()) { + host_.emitter.del_edge_signal(from, id, type, SignalInfo{ mvreg.agent_id }); + } + } + } + } + } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } +} + +void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge"); + const auto log_level = host_.log_level; + try { + if (!protocol_version_matches(host_.log_level, "DSR_EDGE", mvreg.protocol_version)) { + return; + } + bool signal = false, joined = false; + auto from = mvreg.from; + auto to = mvreg.to; + auto type = mvreg.type; + auto id = mvreg.id; + auto timestamp = mvreg.timestamp; + auto crdt_delta = std::move(mvreg.dk); + auto d_empty = crdt_delta.empty(); + std::optional deleted_edge; + + auto delete_unprocessed_deltas = [&](){ + unprocessed_delta_edge_att_.erase(std::tuple{from, to, type}); + std::erase_if(unprocessed_delta_edge_to_, + [&](auto &it){ return std::get<0>(it.second) == from || std::get<0>(it.second) == to;}); + std::erase_if(unprocessed_delta_edge_from_, + [&](auto &it){ return std::get<0>(it.second) == from || std::get<0>(it.second) == to;}); + }; + + auto consume_unprocessed_deltas = [&](){ + auto att_key = std::tuple{from, to, type}; + decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + while (!node_handle_edge_att.empty()) { + auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); + DSR_LOG_DEBUG("[JOIN_EDGE] edge_att", from, to, type, att_name, (timestamp < timestamp_edge_att)); + if (timestamp < timestamp_edge_att) { + process_delta_edge_attr(from, to, type, att_name,std::move(delta)); + } + node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + } + std::erase_if(unprocessed_delta_edge_to_, + [from = from, to = to, type = type](auto& it) { return it.first == to && std::get<0>(it.second) == from && std::get<1>(it.second) == type;}); + std::erase_if(unprocessed_delta_edge_from_, + [from = from, to = to, type = type](auto& it) { return it.first == from && std::get<0>(it.second) == to && std::get<1>(it.second) == type;}); + }; + + { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge crdt merge"); + std::unique_lock lock(host_._mutex); + deleted_edge = get_edge(from, to, type); + bool cfrom{nodes_.contains(from)}, cto{nodes_.contains(to)}; + bool dfrom{host_.deleted.contains(from)}, dto{host_.deleted.contains(to)}; + + if (cfrom && cto) { + signal = process_delta_edge(from, to, type, std::move(crdt_delta)); + consume_unprocessed_deltas(); + joined = true; + } else if (!dfrom && !dto) { + bool find = false; + for (auto [begin, end] = unprocessed_delta_edge_from_.equal_range(from); begin != end; ++begin) { + if (std::get<0>(begin->second) == to && std::get<1>(begin->second) == type){ + find = true; + break; + } + } + for (auto [begin, end] = unprocessed_delta_edge_to_.equal_range(to); begin != end; ++begin) { + if (std::get<0>(begin->second) == from && std::get<1>(begin->second) == type){ + find = true; + break; + } + } + + if (!find) { + if (!cfrom) { + DSR_LOG_DEBUG("[JOIN_EDGE] INSERT UNPROCESSED, no from", from, "unprocessed_delta_edge_from"); + unprocessed_delta_edge_from_.emplace(from, std::tuple{to, type, crdt_delta, timestamp}); + } + if (cfrom && !cto) { + DSR_LOG_DEBUG("[JOIN_EDGE] INSERT UNPROCESSED, no to", to, "unprocessed_delta_edge_to"); + unprocessed_delta_edge_to_.emplace(to, std::tuple{from, type, std::move(crdt_delta), timestamp}); + } + } + } else { + if (d_empty) { + delete_unprocessed_deltas(); + joined = true; + } + } + } + + if (joined) { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge signal emit"); + if (signal) { + host_.emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); + } else { + host_.emitter.del_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); + if (deleted_edge.has_value()) { + host_.emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ mvreg.agent_id }); + } + } + } + } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } +} + +std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg&& mvreg) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node_attr"); + try { + if (!protocol_version_matches(host_.log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { + return {}; + } + auto id = mvreg.node; + auto att_name = mvreg.attr_name; + auto timestamp = mvreg.timestamp; + auto crdt_delta = std::move(mvreg.dk); + auto d_empty = crdt_delta.empty(); + { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node_attr crdt merge"); + std::unique_lock lock(host_._mutex); + if (nodes_.contains(id)) { + process_delta_node_attr(id, att_name, std::move(crdt_delta)); + std::erase_if(unprocessed_delta_node_att_, + [id = id, att_name = att_name](auto &it){ return it.first == id && std::get<0>(it.second) == att_name;}); + return att_name; + } else if (!host_.deleted.contains(id)) { + bool find = false; + for (auto [begin, end] = unprocessed_delta_node_att_.equal_range(id); begin != end; ++begin) { + if (std::get<0>(begin->second) == att_name){ + find = true; + break; + } + } + if (!find) { + unprocessed_delta_node_att_.emplace(id, std::tuple{att_name, std::move(crdt_delta), timestamp}); + } + } else if (d_empty) { + unprocessed_delta_edge_from_.erase(id); + std::erase_if(unprocessed_delta_edge_to_, + [id = id](auto &it){ return std::get<0>(it.second) == id;}); + unprocessed_delta_node_att_.erase(id); + std::erase_if(unprocessed_delta_edge_att_, + [id = id](auto &it){ return std::get<0>(it.first) == id || std::get<1>(it.first) == id;}); + } + } + } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + return {}; +} + +std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg&& mvreg) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge_attr"); + try { + if (!protocol_version_matches(host_.log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { + return {}; + } + auto from = mvreg.from_node; + auto to = mvreg.to_node; + auto type = mvreg.type; + auto att_name = mvreg.attr_name; + auto timestamp = mvreg.timestamp; + auto crdt_delta = std::move(mvreg.dk); + auto d_empty = crdt_delta.empty(); + { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); + std::unique_lock lock(host_._mutex); + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({to, type})) + { + process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); + std::erase_if(unprocessed_delta_edge_att_, + [from = from, to = to, type = type, att_name = att_name](auto &it){ return it.first == std::tuple{from, to, type} && std::get<0>(it.second) == att_name;}); + return att_name; + } else if (!host_.deleted.contains(from) && !host_.deleted.contains(to)) { + bool find = false; + for (auto [begin, end] = unprocessed_delta_edge_att_.equal_range(std::tuple{from, to, type}); begin != end; ++begin) { + if (std::get<0>(begin->second) == att_name){ + find = true; + break; + } + } + if (!find) { + unprocessed_delta_edge_att_.emplace(std::tuple{from, to, type}, std::tuple{att_name, std::move(crdt_delta), timestamp}); + } + } else if (d_empty) { + unprocessed_delta_edge_from_.erase(from); + std::erase_if(unprocessed_delta_edge_to_, + [from = from](auto &it){ return std::get<0>(it.second) == from;}); + unprocessed_delta_node_att_.erase(from); + std::erase_if(unprocessed_delta_edge_att_, + [from = from](auto &it){ return std::get<0>(it.first) == from || std::get<1>(it.first) == from;}); + } + } + } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + return {}; +} + +void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) +{ + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_full_graph"); + const auto log_level = host_.log_level; + if (!protocol_version_matches(host_.log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { + return; + } + + std::vector, std::optional>> updates; + + uint64_t id{0}, timestamp{0}; + uint32_t agent_id_ch{0}; + auto delete_unprocessed_deltas = [&](){ + unprocessed_delta_node_att_.erase(id); + decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); + while (!node_handle.empty()) + { + unprocessed_delta_edge_att_.erase(std::tuple{id, std::get<0>(node_handle.mapped()), std::get<1>(node_handle.mapped())}); + node_handle = unprocessed_delta_edge_from_.extract(id); + } + std::erase_if(unprocessed_delta_edge_to_, + [&](auto &it){ return std::get<0>(it.second) == id;}); + }; + + auto consume_unprocessed_deltas = [&](){ + decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); + while (!node_handle_node_att.empty()) + { + auto &[att_name, delta, timestamp_node_att] = node_handle_node_att.mapped(); + if (timestamp < timestamp_node_att) { + process_delta_node_attr(id, att_name,std::move(delta)); + } + node_handle_node_att = unprocessed_delta_node_att_.extract(id); + } + + decltype(unprocessed_delta_edge_from_)::node_type node_handle_edge = unprocessed_delta_edge_from_.extract(id); + while (!node_handle_edge.empty()) { + auto &[to, type, delta, timestamp_edge] = node_handle_edge.mapped(); + auto att_key = std::tuple{id, to, type}; + DSR_LOG_DEBUG("[JOIN_FULL] unprocessed_delta_edge_from", id, to, type, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge) { + process_delta_edge(id, to, type, std::move(delta)); + } + if (nodes_.contains(id) and nodes_.at(id).read_reg().fano().contains({to, type})) { + decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + while (!node_handle_edge_att.empty()) { + auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); + DSR_LOG_DEBUG("[JOIN_FULL] edge_att", id, to, type, att_name, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge_att) { + process_delta_edge_attr(id, to, type, att_name, std::move(delta)); + } + node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + } + } + std::erase_if(unprocessed_delta_edge_to_, + [to = to, id = id, type = type](auto& it) { return it.first == to && std::get<0>(it.second) == id && std::get<1>(it.second) == type;}); + node_handle_edge = unprocessed_delta_edge_from_.extract(id); + } + + node_handle_edge = unprocessed_delta_edge_to_.extract(id); + while (!node_handle_edge.empty()) { + auto &[from, type, delta, timestamp_edge] = node_handle_edge.mapped(); + auto att_key = std::tuple{from, id, type}; + DSR_LOG_DEBUG("[JOIN_FULL] unprocessed_delta_edge_to", from, id, type, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge) { + process_delta_edge(from, id, type, std::move(delta)); + } + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({id, type})) { + decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + while (!node_handle_edge_att.empty()) { + auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); + DSR_LOG_DEBUG("[JOIN_FULL] edge_att", from, id, type, att_name, (timestamp < timestamp_edge)); + if (timestamp < timestamp_edge_att) { + process_delta_edge_attr(from, id, type, att_name, std::move(delta)); + } + node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); + } + } + + node_handle_edge = unprocessed_delta_edge_to_.extract(id); + } + }; + + { + std::unique_lock lock(host_._mutex); + + for (auto &[k, val] : full_graph.m) { + auto mv = std::move(val.dk); + bool mv_empty = mv.empty(); + agent_id_ch = val.agent_id; + auto it = nodes_.find(k); + std::optional nd = + (it != nodes_.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; + id = k; + if (!host_.deleted.contains(k)) { + if (it == nodes_.end()) { + it = nodes_.emplace(k, mvreg{}).first; + } + it->second.join(std::move(mv)); + if (mv_empty or it->second.empty()) { + host_.update_maps_node_delete(k, nd); + updates.emplace_back(false, k, "", std::nullopt, std::nullopt); + delete_unprocessed_deltas(); + } else { + const auto& reg = it->second.read_reg(); + host_.update_maps_node_insert(k, reg); + updates.emplace_back(true, k, reg.type(), nd, reg); + consume_unprocessed_deltas(); + } + } + } + } + { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph emit phase"); + for (auto &[signal, node_id, type, nd, current_nd] : updates) { + if (signal) { + if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { + host_.emitter.update_node_signal(node_id, type, SignalInfo{ agent_id_ch }); + } else if (nd.value() != *current_nd) { + const auto& iter = current_nd->fano(); + for (const auto &[k, v] : nd->fano()) { + if (!iter.contains(k)) { + host_.emitter.del_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); + if (v.dk.ds.size() > 0) { + Edge tmp_edge(v.read_reg()); + host_.emitter.deleted_edge_signal(tmp_edge, SignalInfo{ host_.agent_id }); + } + } + } + for (const auto &[k, v] : iter) { + if (auto it = nd->fano().find(k); it == nd->fano().end() or it->second != v) + host_.emitter.update_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); + } + } + } else { + host_.emitter.del_node_signal(node_id, SignalInfo{ agent_id_ch }); + if (nd.has_value()) { + Node tmp_node(*nd); + host_.emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); + } + } + } + } +} + +std::map CRDTSyncEngine::export_mvreg_map() const +{ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::export_mvreg_map"); + std::map m; + for (const auto& kv : nodes_) { + MvregNodeMsg msg; + msg.dk = kv.second; + msg.id = kv.first; + msg.agent_id = host_.agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(host_.sync_mode); + m.emplace(kv.first, std::move(msg)); + } + return m; +} diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index cf4412e8..ec65b2be 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -31,6 +31,7 @@ #include "dsr/api/dsr_rt_api.h" #include "dsr/api/dsr_utils.h" #include "dsr/api/dsr_signal_info.h" +#include "dsr/api/dsr_sync_engine.h" #include "dsr/api/dsr_graph_settings.h" #include "dsr/api/dsr_logging.h" #include "dsr/api/dsr_signal_emitter.h" @@ -48,10 +49,11 @@ namespace DSR { - using Nodes = std::unordered_map>; using IDType = uint64_t; static constexpr uint64_t CLEAR_DELETED_SIGNAL = std::numeric_limits::max(); + class CRDTSyncEngine; + ///////////////////////////////////////////////////////////////// /// CRDT API ///////////////////////////////////////////////////////////////// @@ -59,6 +61,7 @@ namespace DSR { friend RT_API; friend class DSRGraphTestAccess; + friend class CRDTSyncEngine; public: size_t size() const; @@ -464,20 +467,7 @@ namespace DSR inline uint64_t get_agent_id() const { return agent_id; }; inline std::string get_agent_name() const { return agent_name; }; - void reset() - { - dsrparticipant.remove_participant_and_entities(); - - nodes.clear(); - deleted.clear(); - name_map.clear(); - id_map.clear(); - edges.clear(); - edgeType.clear(); - nodeType.clear(); - to_edges.clear(); - - } + void reset(); void clear_deleted() { @@ -492,6 +482,7 @@ namespace DSR signal.id = CLEAR_DELETED_SIGNAL; signal.agent_id = agent_id; signal.protocol_version = DSR::DSR_PROTOCOL_VERSION; + signal.sync_mode = sync_mode_wire_value(sync_mode); dsrpub_node.write(&signal); } } @@ -585,7 +576,6 @@ namespace DSR DSRGraph(const DSRGraph& G); //Private constructor for DSRCopy - Nodes nodes; mutable std::shared_mutex _mutex; mutable std::shared_mutex _mutex_cache_maps; mutable std::mutex mtx_entity_creation; @@ -593,12 +583,14 @@ namespace DSR const uint32_t agent_id; const std::string agent_name; const bool copy; + const SyncMode sync_mode; std::unique_ptr utils; std::unordered_set ignored_attributes; bool same_host; id_generator generator; GraphSettings::LOGLEVEL log_level; signals_fns emitter; + SyncEnginePtr engine_; ////////////////////////////////////////////////////////////////////////// // Signal method @@ -651,6 +643,9 @@ namespace DSR void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key = ""); void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key); + CRDTSyncEngine& crdt_engine(); + const CRDTSyncEngine& crdt_engine() const; + ////////////////////////////////////////////////////////////////////////// // Non-blocking graph operations @@ -678,16 +673,6 @@ namespace DSR std::optional join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg); void join_full_graph(DSR::OrMap &&full_graph); - bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg && delta); - void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg && attr); - void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg && attr); - - //Maps for temporary deltas - std::unordered_multimap, uint64_t> > unprocessed_delta_node_att; - std::unordered_multimap, uint64_t>> unprocessed_delta_edge_from; - std::unordered_multimap, uint64_t>> unprocessed_delta_edge_to; - std::unordered_multimap, std::tuple, uint64_t>, hash_tuple> unprocessed_delta_edge_att; - // ThreadPools are declared after all data they access so that their // destructors (which join worker threads) run before the data members // are destroyed, preventing use-after-free data races on shutdown. diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h new file mode 100644 index 00000000..787450bd --- /dev/null +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -0,0 +1,79 @@ +#pragma once + +#include "dsr/api/dsr_sync_engine.h" +#include "dsr/core/crdt/delta_crdt.h" +#include "dsr/core/types/crdt_types.h" + +#include +#include +#include +#include + +namespace DSR { + +class DSRGraph; + +class CRDTSyncEngine final : public SyncEngine +{ +public: + using Nodes = std::unordered_map>; + + explicit CRDTSyncEngine(DSRGraph& host); + CRDTSyncEngine(DSRGraph& host, const CRDTSyncEngine& other); + ~CRDTSyncEngine() override = default; + + SyncBackendInfo backend_info() const override; + + std::optional get_node(uint64_t id) const override; + std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + size_t size() const override; + std::map snapshot() const override; + + NodeMutationEffect insert_node_local(Node&& node) override; + NodeMutationEffect update_node_local(Node&& node) override; + NodeMutationEffect delete_node_local(uint64_t id) override; + + EdgeMutationEffect insert_or_assign_edge_local(Edge&& edge) override; + EdgeMutationEffect delete_edge_local(uint64_t from, uint64_t to, const std::string& type) override; + + void apply_remote_node_delta(NodeDeltaMessage&& delta) override; + void apply_remote_edge_delta(EdgeDeltaMessage&& delta) override; + void apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) override; + void apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) override; + void import_full_graph(FullGraphMessage&& full_graph) override; + FullGraphMessage export_full_graph() const override; + + const CRDTNode* get_node_ptr(uint64_t id) const; + std::optional get_crdt_node(uint64_t id) const; + std::optional get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const; + + std::tuple> insert_node_raw(CRDTNode&& node); + std::tuple> update_node_raw(CRDTNode&& node); + std::tuple, std::optional, std::vector> + delete_node_raw(uint64_t id, const CRDTNode& node); + std::optional delete_edge_raw(uint64_t from, uint64_t to, const std::string& key); + std::tuple, std::optional> + insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint64_t to); + + void join_delta_node(MvregNodeMsg&& mvreg); + void join_delta_edge(MvregEdgeMsg&& mvreg); + std::optional join_delta_node_attr(MvregNodeAttrMsg&& mvreg); + std::optional join_delta_edge_attr(MvregEdgeAttrMsg&& mvreg); + void join_full_graph(OrMap&& full_graph); + + std::map export_mvreg_map() const; + +private: + bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta); + void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr); + void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr); + + DSRGraph& host_; + Nodes nodes_; + std::unordered_multimap, uint64_t>> unprocessed_delta_node_att_; + std::unordered_multimap, uint64_t>> unprocessed_delta_edge_from_; + std::unordered_multimap, uint64_t>> unprocessed_delta_edge_to_; + std::unordered_multimap, std::tuple, uint64_t>, hash_tuple> unprocessed_delta_edge_att_; +}; + +} // namespace DSR diff --git a/api/include/dsr/api/dsr_graph_settings.h b/api/include/dsr/api/dsr_graph_settings.h index e26874d9..474a70f2 100644 --- a/api/include/dsr/api/dsr_graph_settings.h +++ b/api/include/dsr/api/dsr_graph_settings.h @@ -6,6 +6,16 @@ namespace DSR { +enum struct SyncMode : uint8_t { + CRDT = 0, + LWW = 1, +}; + +constexpr uint8_t sync_mode_wire_value(SyncMode mode) noexcept +{ + return static_cast(mode); +} + struct GraphSettings { uint32_t agent_id {0}; int theradpool_threads {5}; @@ -19,6 +29,7 @@ struct GraphSettings { } log_level {LOGLEVEL::INFOL}; int8_t domain_id = 0; SignalMode signal_mode = QT; + SyncMode sync_mode = SyncMode::CRDT; }; -} \ No newline at end of file +} diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h new file mode 100644 index 00000000..9d2a46d9 --- /dev/null +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -0,0 +1,97 @@ +#pragma once + +#include "dsr/api/dsr_graph_settings.h" +#include "dsr/core/types/internal_types.h" +#include "dsr/core/types/user_types.h" + +#include +#include +#include +#include +#include +#include +#include + +namespace DSR { + +// Backend-agnostic message envelopes. Stage 4 extends these variants with LWW +// message types while keeping the engine interface typed and decoupled from DDS +// reader/writer plumbing. +using NodeDeltaMessage = std::variant; +using EdgeDeltaMessage = std::variant; +using NodeAttrDeltaBatchMessage = std::variant; +using EdgeAttrDeltaBatchMessage = std::variant; +using FullGraphMessage = std::variant; + +struct SyncBackendInfo +{ + SyncMode mode{SyncMode::CRDT}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; +}; + +struct NodeMutationEffect +{ + bool applied{false}; + uint64_t id{}; + std::string type; + std::vector changed_attributes; + std::vector> related_edge_keys; + std::vector deleted_edges; + std::optional deleted_node; +}; + +struct EdgeMutationEffect +{ + bool applied{false}; + uint64_t from{}; + uint64_t to{}; + std::string type; + std::vector changed_attributes; + std::optional deleted_edge; +}; + +class SyncEngineHost +{ +public: + virtual ~SyncEngineHost() = default; + + virtual uint32_t local_agent_id() const = 0; + virtual SyncMode local_sync_mode() const = 0; + virtual bool is_copy_graph() const = 0; + + virtual void update_maps_node_insert(const Node& node) = 0; + virtual void update_maps_node_delete(uint64_t id, const std::optional& node) = 0; + virtual void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string& type) = 0; + virtual void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string& type) = 0; +}; + +class SyncEngine +{ +public: + virtual ~SyncEngine() = default; + + virtual SyncBackendInfo backend_info() const = 0; + + virtual std::optional get_node(uint64_t id) const = 0; + virtual std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const = 0; + virtual size_t size() const = 0; + virtual std::map snapshot() const = 0; + + virtual NodeMutationEffect insert_node_local(Node&& node) = 0; + virtual NodeMutationEffect update_node_local(Node&& node) = 0; + virtual NodeMutationEffect delete_node_local(uint64_t id) = 0; + + virtual EdgeMutationEffect insert_or_assign_edge_local(Edge&& edge) = 0; + virtual EdgeMutationEffect delete_edge_local(uint64_t from, uint64_t to, const std::string& type) = 0; + + virtual void apply_remote_node_delta(NodeDeltaMessage&& delta) = 0; + virtual void apply_remote_edge_delta(EdgeDeltaMessage&& delta) = 0; + virtual void apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) = 0; + virtual void apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) = 0; + virtual void import_full_graph(FullGraphMessage&& full_graph) = 0; + virtual FullGraphMessage export_full_graph() const = 0; +}; + +using SyncEnginePtr = std::unique_ptr; + +} // namespace DSR diff --git a/core/include/dsr/core/types/internal_types.h b/core/include/dsr/core/types/internal_types.h index 24fcc909..00b4ab35 100644 --- a/core/include/dsr/core/types/internal_types.h +++ b/core/include/dsr/core/types/internal_types.h @@ -18,12 +18,14 @@ namespace DSR { std::string from; int32_t id{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { cdr << from; cdr << id; cdr << protocol_version; + cdr << sync_mode; } void deserialize_impl(eprosima::fastcdr::Cdr& cdr) @@ -31,6 +33,7 @@ namespace DSR { cdr >> from; cdr >> id; cdr >> protocol_version; + cdr >> sync_mode; } size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const @@ -39,6 +42,7 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), from, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), sync_mode, ca); return size; } }; @@ -53,6 +57,7 @@ namespace DSR { uint32_t agent_id{}; uint64_t timestamp{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { @@ -61,6 +66,7 @@ namespace DSR { cdr << agent_id; cdr << timestamp; cdr << protocol_version; + cdr << sync_mode; } void deserialize_impl(eprosima::fastcdr::Cdr& cdr) @@ -70,6 +76,7 @@ namespace DSR { cdr >> agent_id; cdr >> timestamp; cdr >> protocol_version; + cdr >> sync_mode; } size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const @@ -79,6 +86,7 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), agent_id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), timestamp, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), sync_mode, ca); return size; } }; @@ -95,6 +103,7 @@ namespace DSR { uint32_t agent_id{}; uint64_t timestamp{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { @@ -106,6 +115,7 @@ namespace DSR { cdr << agent_id; cdr << timestamp; cdr << protocol_version; + cdr << sync_mode; } void deserialize_impl(eprosima::fastcdr::Cdr& cdr) @@ -118,6 +128,7 @@ namespace DSR { cdr >> agent_id; cdr >> timestamp; cdr >> protocol_version; + cdr >> sync_mode; } size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const @@ -130,6 +141,7 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), agent_id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), timestamp, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), sync_mode, ca); return size; } }; @@ -145,6 +157,7 @@ namespace DSR { uint32_t agent_id{}; uint64_t timestamp{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { @@ -155,6 +168,7 @@ namespace DSR { cdr << agent_id; cdr << timestamp; cdr << protocol_version; + cdr << sync_mode; } void deserialize_impl(eprosima::fastcdr::Cdr& cdr) @@ -166,6 +180,7 @@ namespace DSR { cdr >> agent_id; cdr >> timestamp; cdr >> protocol_version; + cdr >> sync_mode; } size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const @@ -177,6 +192,7 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), agent_id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), timestamp, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), sync_mode, ca); return size; } }; @@ -194,6 +210,7 @@ namespace DSR { uint32_t agent_id{}; uint64_t timestamp{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; void serialize_impl(eprosima::fastcdr::Cdr& cdr) const { @@ -206,6 +223,7 @@ namespace DSR { cdr << agent_id; cdr << timestamp; cdr << protocol_version; + cdr << sync_mode; } void deserialize_impl(eprosima::fastcdr::Cdr& cdr) @@ -219,6 +237,7 @@ namespace DSR { cdr >> agent_id; cdr >> timestamp; cdr >> protocol_version; + cdr >> sync_mode; } size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const @@ -232,6 +251,7 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), agent_id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), timestamp, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), sync_mode, ca); return size; } }; @@ -311,6 +331,7 @@ namespace DSR { uint32_t to_id{}; int32_t id{}; uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; std::map m; dot_context cbase; @@ -319,6 +340,7 @@ namespace DSR { cdr << to_id; cdr << id; cdr << protocol_version; + cdr << sync_mode; auto count = static_cast(m.size()); cdr << count; for (const auto& [k, v] : m) { @@ -333,6 +355,7 @@ namespace DSR { cdr >> to_id; cdr >> id; cdr >> protocol_version; + cdr >> sync_mode; uint32_t count = 0; cdr >> count; m.clear(); @@ -352,10 +375,11 @@ namespace DSR { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), to_id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), id, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), sync_mode, ca); auto count = static_cast(m.size()); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), count, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), count, ca); for (const auto& [k, v] : m) { - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), k, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), k, ca); size += v.serialized_size(calc, ca); } size += cbase.serialized_size(calc, ca); @@ -363,4 +387,412 @@ namespace DSR { } }; + // ---- LWWNodeMsg ---------------------------------------------------------- + + struct LWWNodeMsg : public ISerializable + { + uint64_t id{}; + std::string type; + std::string name; + std::map attrs; + uint32_t agent_id{}; + uint64_t timestamp{}; + bool deleted{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << id; + cdr << type; + cdr << name; + auto count = static_cast(attrs.size()); + cdr << count; + for (const auto& [key, value] : attrs) { + cdr << key; + value.serialize(cdr); + } + cdr << agent_id; + cdr << timestamp; + cdr << deleted; + cdr << protocol_version; + cdr << sync_mode; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> id; + cdr >> type; + cdr >> name; + uint32_t count = 0; + cdr >> count; + attrs.clear(); + for (uint32_t i = 0; i < count; ++i) { + std::string key; + Attribute value; + cdr >> key; + value.deserialize(cdr); + attrs.emplace(std::move(key), std::move(value)); + } + cdr >> agent_id; + cdr >> timestamp; + cdr >> deleted; + cdr >> protocol_version; + cdr >> sync_mode; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), name, ca); + auto count = static_cast(attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), count, ca); + for (const auto& [key, value] : attrs) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), key, ca); + size += value.serialized_size(calc, ca); + } + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), deleted, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), sync_mode, ca); + return size; + } + }; + + // ---- LWWEdgeMsg ---------------------------------------------------------- + + struct LWWEdgeMsg : public ISerializable + { + uint64_t from{}; + uint64_t to{}; + std::string type; + std::map attrs; + uint32_t agent_id{}; + uint64_t timestamp{}; + bool deleted{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << from; + cdr << to; + cdr << type; + auto count = static_cast(attrs.size()); + cdr << count; + for (const auto& [key, value] : attrs) { + cdr << key; + value.serialize(cdr); + } + cdr << agent_id; + cdr << timestamp; + cdr << deleted; + cdr << protocol_version; + cdr << sync_mode; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> from; + cdr >> to; + cdr >> type; + uint32_t count = 0; + cdr >> count; + attrs.clear(); + for (uint32_t i = 0; i < count; ++i) { + std::string key; + Attribute value; + cdr >> key; + value.deserialize(cdr); + attrs.emplace(std::move(key), std::move(value)); + } + cdr >> agent_id; + cdr >> timestamp; + cdr >> deleted; + cdr >> protocol_version; + cdr >> sync_mode; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), to, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), type, ca); + auto count = static_cast(attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), count, ca); + for (const auto& [key, value] : attrs) { + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), key, ca); + size += value.serialized_size(calc, ca); + } + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), deleted, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), sync_mode, ca); + return size; + } + }; + + // ---- LWWNodeAttrMsg ------------------------------------------------------ + + struct LWWNodeAttrMsg : public ISerializable + { + uint64_t node_id{}; + std::string attr_name; + Attribute value; + uint32_t agent_id{}; + uint64_t timestamp{}; + bool deleted{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << node_id; + cdr << attr_name; + value.serialize(cdr); + cdr << agent_id; + cdr << timestamp; + cdr << deleted; + cdr << protocol_version; + cdr << sync_mode; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> node_id; + cdr >> attr_name; + value.deserialize(cdr); + cdr >> agent_id; + cdr >> timestamp; + cdr >> deleted; + cdr >> protocol_version; + cdr >> sync_mode; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), node_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), attr_name, ca); + size += value.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), deleted, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), sync_mode, ca); + return size; + } + }; + + // ---- LWWEdgeAttrMsg ------------------------------------------------------ + + struct LWWEdgeAttrMsg : public ISerializable + { + uint64_t from{}; + uint64_t to{}; + std::string type; + std::string attr_name; + Attribute value; + uint32_t agent_id{}; + uint64_t timestamp{}; + bool deleted{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << from; + cdr << to; + cdr << type; + cdr << attr_name; + value.serialize(cdr); + cdr << agent_id; + cdr << timestamp; + cdr << deleted; + cdr << protocol_version; + cdr << sync_mode; + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> from; + cdr >> to; + cdr >> type; + cdr >> attr_name; + value.deserialize(cdr); + cdr >> agent_id; + cdr >> timestamp; + cdr >> deleted; + cdr >> protocol_version; + cdr >> sync_mode; + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), to, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), attr_name, ca); + size += value.serialized_size(calc, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), agent_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), timestamp, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), deleted, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), sync_mode, ca); + return size; + } + }; + + // ---- LWWNodeAttrVec ------------------------------------------------------ + + struct LWWNodeAttrVec : public ISerializable + { + std::vector vec; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + auto count = static_cast(vec.size()); + cdr << count; + for (const auto& item : vec) { + item.serialize(cdr); + } + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + uint32_t count = 0; + cdr >> count; + vec.resize(count); + for (auto& item : vec) { + item.deserialize(cdr); + } + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + auto count = static_cast(vec.size()); + size_t size = calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), count, ca); + for (const auto& item : vec) { + size += item.serialized_size(calc, ca); + } + return size; + } + }; + + // ---- LWWEdgeAttrVec ------------------------------------------------------ + + struct LWWEdgeAttrVec : public ISerializable + { + std::vector vec; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + auto count = static_cast(vec.size()); + cdr << count; + for (const auto& item : vec) { + item.serialize(cdr); + } + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + uint32_t count = 0; + cdr >> count; + vec.resize(count); + for (auto& item : vec) { + item.deserialize(cdr); + } + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + auto count = static_cast(vec.size()); + size_t size = calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), count, ca); + for (const auto& item : vec) { + size += item.serialized_size(calc, ca); + } + return size; + } + }; + + // ---- LWWGraphSnapshot ---------------------------------------------------- + + struct LWWGraphSnapshot : public ISerializable + { + uint32_t to_id{}; + int32_t id{}; + uint64_t tombstone_window_ms{}; + uint32_t protocol_version{DSR_PROTOCOL_VERSION}; + uint8_t sync_mode{0}; + std::vector nodes; + std::vector edges; + + void serialize_impl(eprosima::fastcdr::Cdr& cdr) const + { + cdr << to_id; + cdr << id; + cdr << tombstone_window_ms; + cdr << protocol_version; + cdr << sync_mode; + auto node_count = static_cast(nodes.size()); + cdr << node_count; + for (const auto& node : nodes) { + node.serialize(cdr); + } + auto edge_count = static_cast(edges.size()); + cdr << edge_count; + for (const auto& edge : edges) { + edge.serialize(cdr); + } + } + + void deserialize_impl(eprosima::fastcdr::Cdr& cdr) + { + cdr >> to_id; + cdr >> id; + cdr >> tombstone_window_ms; + cdr >> protocol_version; + cdr >> sync_mode; + uint32_t node_count = 0; + cdr >> node_count; + nodes.resize(node_count); + for (auto& node : nodes) { + node.deserialize(cdr); + } + uint32_t edge_count = 0; + cdr >> edge_count; + edges.resize(edge_count); + for (auto& edge : edges) { + edge.deserialize(cdr); + } + } + + size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + { + size_t size = 0; + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), to_id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), tombstone_window_ms, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), protocol_version, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), sync_mode, ca); + auto node_count = static_cast(nodes.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), node_count, ca); + for (const auto& node : nodes) { + size += node.serialized_size(calc, ca); + } + auto edge_count = static_cast(edges.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), edge_count, ca); + for (const auto& edge : edges) { + size += edge.serialized_size(calc, ca); + } + return size; + } + }; + } // namespace DSR diff --git a/tests/synchronization/type_translation.cpp b/tests/synchronization/type_translation.cpp index ecb1867e..05a03018 100644 --- a/tests/synchronization/type_translation.cpp +++ b/tests/synchronization/type_translation.cpp @@ -16,6 +16,7 @@ #include "dsr/core/types/type_checking/dsr_node_type.h" #include "dsr/core/types/user_types.h" #include "dsr/core/rtps/CRDTPubSubTypes.h" +#include "dsr/api/dsr_sync_engine.h" #include #include @@ -160,6 +161,127 @@ TEST_CASE("NODE: from DSR representation to CRDT and back via serialization", "[ } +TEST_CASE("Wire metadata round-trip preserves sync mode", "[TRANSLATION][SYNC_MODE]") +{ + SECTION("GraphRequest preserves non-default sync mode") + { + GraphRequest request; + request.from = "agent"; + request.id = 42; + request.protocol_version = DSR_PROTOCOL_VERSION; + request.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto rt = roundtrip(request); + REQUIRE(rt.from == request.from); + REQUIRE(rt.id == request.id); + REQUIRE(rt.protocol_version == request.protocol_version); + REQUIRE(rt.sync_mode == request.sync_mode); + } + + SECTION("Node delta preserves sync mode") + { + auto node = Node::create("sync_mode_node"); + node.id(7); + node.agent_id(3); + + mvreg reg; + auto delta = reg.write(user_node_to_crdt(node)); + auto msg = CRDTNode_to_Msg(node.agent_id(), node.id(), std::move(delta)); + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto rt = roundtrip(msg); + REQUIRE(rt.id == msg.id); + REQUIRE(rt.agent_id == msg.agent_id); + REQUIRE(rt.protocol_version == msg.protocol_version); + REQUIRE(rt.sync_mode == msg.sync_mode); + } + + SECTION("Full graph snapshot preserves sync mode") + { + OrMap graph; + graph.id = 1; + graph.to_id = 2; + graph.protocol_version = DSR_PROTOCOL_VERSION; + graph.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto rt = roundtrip(graph); + REQUIRE(rt.id == graph.id); + REQUIRE(rt.to_id == graph.to_id); + REQUIRE(rt.protocol_version == graph.protocol_version); + REQUIRE(rt.sync_mode == graph.sync_mode); + } + + SECTION("LWW node delta preserves delete metadata") + { + LWWNodeMsg msg; + msg.id = 42; + msg.type = "robot"; + msg.name = "lww_node"; + msg.deleted = true; + msg.agent_id = 9; + msg.timestamp = 123456; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + msg.attrs.emplace("level", Attribute(7, msg.timestamp, msg.agent_id)); + + auto rt = roundtrip(msg); + REQUIRE(rt.id == msg.id); + REQUIRE(rt.type == msg.type); + REQUIRE(rt.name == msg.name); + REQUIRE(rt.deleted == msg.deleted); + REQUIRE(rt.timestamp == msg.timestamp); + REQUIRE(rt.sync_mode == msg.sync_mode); + REQUIRE(rt.attrs.contains("level")); + } + + SECTION("LWW full graph snapshot preserves tombstone window") + { + LWWGraphSnapshot graph; + graph.id = 5; + graph.to_id = 6; + graph.tombstone_window_ms = 300000; + graph.protocol_version = DSR_PROTOCOL_VERSION; + graph.sync_mode = sync_mode_wire_value(SyncMode::LWW); + graph.nodes.push_back(LWWNodeMsg{.id = 1, .type = "root", .name = "root", .attrs = {}, .agent_id = 2, .timestamp = 77, .deleted = false, .protocol_version = DSR_PROTOCOL_VERSION, .sync_mode = sync_mode_wire_value(SyncMode::LWW)}); + + auto rt = roundtrip(graph); + REQUIRE(rt.id == graph.id); + REQUIRE(rt.to_id == graph.to_id); + REQUIRE(rt.tombstone_window_ms == graph.tombstone_window_ms); + REQUIRE(rt.sync_mode == graph.sync_mode); + REQUIRE(rt.nodes.size() == graph.nodes.size()); + } +} + +TEST_CASE("Sync engine interface message aliases compile", "[SYNC_ENGINE][COMPILE]") +{ + NodeDeltaMessage node_delta = MvregNodeMsg{}; + EdgeDeltaMessage edge_delta = MvregEdgeMsg{}; + NodeAttrDeltaBatchMessage node_attr_batch = MvregNodeAttrVec{}; + EdgeAttrDeltaBatchMessage edge_attr_batch = MvregEdgeAttrVec{}; + FullGraphMessage full_graph = OrMap{}; + NodeDeltaMessage lww_node_delta = LWWNodeMsg{}; + EdgeDeltaMessage lww_edge_delta = LWWEdgeMsg{}; + NodeAttrDeltaBatchMessage lww_node_attr_batch = LWWNodeAttrVec{}; + EdgeAttrDeltaBatchMessage lww_edge_attr_batch = LWWEdgeAttrVec{}; + FullGraphMessage lww_full_graph = LWWGraphSnapshot{}; + + REQUIRE(std::holds_alternative(node_delta)); + REQUIRE(std::holds_alternative(edge_delta)); + REQUIRE(std::holds_alternative(node_attr_batch)); + REQUIRE(std::holds_alternative(edge_attr_batch)); + REQUIRE(std::holds_alternative(full_graph)); + REQUIRE(std::holds_alternative(lww_node_delta)); + REQUIRE(std::holds_alternative(lww_edge_delta)); + REQUIRE(std::holds_alternative(lww_node_attr_batch)); + REQUIRE(std::holds_alternative(lww_edge_attr_batch)); + REQUIRE(std::holds_alternative(lww_full_graph)); + + SyncBackendInfo info; + REQUIRE(info.mode == SyncMode::CRDT); + REQUIRE(info.protocol_version == DSR_PROTOCOL_VERSION); +} + TEST_CASE("EDGE: from DSR representation to CRDT and back via serialization", "[TRANSLATION][EDGE]"){ From b629248beb5e2484d8235ba228c83f749a0c4d82 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Tue, 21 Apr 2026 21:54:23 +0200 Subject: [PATCH 10/38] feat: add local lww sync engine backend --- api/CMakeLists.txt | 2 + api/dsr_api.cpp | 336 +++++++++++++- api/dsr_lww_sync_engine.cpp | 538 ++++++++++++++++++++++ api/include/dsr/api/dsr_api.h | 32 +- api/include/dsr/api/dsr_lww_sync_engine.h | 116 +++++ tests/CMakeLists.txt | 2 +- tests/synchronization/lww_sync_engine.cpp | 209 +++++++++ 7 files changed, 1197 insertions(+), 38 deletions(-) create mode 100644 api/dsr_lww_sync_engine.cpp create mode 100644 api/include/dsr/api/dsr_lww_sync_engine.h create mode 100644 tests/synchronization/lww_sync_engine.cpp diff --git a/api/CMakeLists.txt b/api/CMakeLists.txt index 28da2717..ef68b441 100644 --- a/api/CMakeLists.txt +++ b/api/CMakeLists.txt @@ -25,6 +25,7 @@ set(headers include/dsr/api/dsr_graph_settings.h include/dsr/api/dsr_sync_engine.h include/dsr/api/dsr_crdt_sync_engine.h + include/dsr/api/dsr_lww_sync_engine.h ) add_library(dsr_api SHARED) @@ -35,6 +36,7 @@ target_sources(dsr_api PRIVATE dsr_api.cpp dsr_crdt_sync_engine.cpp + dsr_lww_sync_engine.cpp dsr_camera_api.cpp dsr_agent_info_api.cpp dsr_inner_eigen_api.cpp diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index b1bf4ac4..b5b54b91 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -4,6 +4,7 @@ #include "dsr/api/dsr_graph_settings.h" #include "dsr/api/dsr_crdt_sync_engine.h" +#include "dsr/api/dsr_lww_sync_engine.h" #include "dsr/core/types/internal_types.h" #include "dsr/core/types/translator.h" #include "dsr/core/profiling.h" @@ -32,6 +33,14 @@ using namespace DSR; using namespace std::literals; namespace { +DSR::SyncEnginePtr make_sync_engine(DSR::DSRGraph& graph, DSR::SyncMode mode) +{ + if (mode == DSR::SyncMode::LWW) { + return std::make_unique(graph); + } + return std::make_unique(graph); +} + bool protocol_version_matches( DSR::GraphSettings::LOGLEVEL log_level, const char* channel, @@ -100,14 +109,11 @@ DSRGraph::DSRGraph(GraphSettings settings) : same_host(settings.same_host), generator(settings.agent_id), log_level(settings.log_level), - engine_(std::make_unique(*this)) + engine_(make_sync_engine(*this, settings.sync_mode)) { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph"); qDebug() << "Agent name: " << QString::fromStdString(agent_name); - if (sync_mode != SyncMode::CRDT) { - qFatal("DSRGraph aborting: SyncMode::LWW is not implemented yet"); - } { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph setup utils/signals"); utils = std::make_unique(this); @@ -117,6 +123,25 @@ DSRGraph::DSRGraph(GraphSettings settings) : set_queued_signals(); } } + if (sync_mode == SyncMode::LWW) + { + if (!settings.input_file.empty()) + { + try + { + CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph load local LWW graph"); + read_from_json_file(settings.input_file); + qDebug() << __FUNCTION__ << "Warning, graph read from file " << QString::fromStdString(settings.input_file); + } + catch(const DSR::DSRException& e) + { + std::cout << e.what() << '\n'; + qFatal("Aborting program. Cannot continue without intial file"); + } + } + qDebug() << __FUNCTION__ << "Constructor finished OK"; + return; + } // RTPS Create participant auto participant_init_result = [&]() { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init participant"); @@ -236,16 +261,20 @@ DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_f DSRGraph::~DSRGraph() { qDebug() << "Removing DSRGraph"; - dsrparticipant.remove_participant_and_entities(); - if (!copy) { + if (sync_mode == SyncMode::CRDT) { + dsrparticipant.remove_participant_and_entities(); + } + if (!copy && sync_mode == SyncMode::CRDT) { qDebug() << "Removing rtps participant"; } } void DSRGraph::reset() { - dsrparticipant.remove_participant_and_entities(); - engine_ = std::make_unique(*this); + if (sync_mode == SyncMode::CRDT) { + dsrparticipant.remove_participant_and_entities(); + } + engine_ = make_sync_engine(*this, sync_mode); deleted.clear(); name_map.clear(); id_map.clear(); @@ -277,6 +306,9 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional id = get_id_from_name(name); if (id.has_value()) { + if (sync_mode == SyncMode::LWW) { + return engine_->get_node(id.value()); + } if (const auto* n = get_node_ptr_(id.value()); n != nullptr) return Node(*n); } return {}; @@ -286,6 +318,9 @@ std::optional DSRGraph::get_node(uint64_t id) { CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(id)"); std::shared_lock lock(_mutex); + if (sync_mode == SyncMode::LWW) { + return engine_->get_node(id); + } if (const auto* n = get_node_ptr_(id); n != nullptr) return Node(*n); return {}; } @@ -299,6 +334,35 @@ template std::optional DSRGraph::insert_node(No &&node) requires (std::is_same_v, DSR::Node>) { + if (sync_mode == SyncMode::LWW) + { + { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node LWW"); + std::unique_lock lock(_mutex); + std::shared_lock lck_cache(_mutex_cache_maps); + uint64_t new_node_id = generator.generate(); + node.id(new_node_id); + if (node.name().empty() or name_map.contains(node.name())) + node.name(node.type() + "_" + id_generator::hex_string(new_node_id)); + lck_cache.unlock(); + auto node_copy = Node(node); + auto effect = engine_->insert_node_local(std::move(node_copy)); + if (!effect.applied) { + return {}; + } + } + if (!copy) + { + DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) + { + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + } + } + return node.id(); + } + std::optional delta; bool inserted = false; { @@ -340,6 +404,36 @@ template std::optional DSRGraph::insert_node_with_id(No &&node) requires (std::is_same_v, DSR::Node>) { + if (sync_mode == SyncMode::LWW) + { + { + std::unique_lock lock(_mutex); + std::shared_lock lck_cache(_mutex_cache_maps); + if (id_map.contains(node.id())) { + DSR_LOG_WARNING("[INSERT_NODE_WITH_ID] Node id already exists", node.id(), node.type()); + return {}; + } + if (node.name().empty() or name_map.contains(node.name())) + node.name(node.type() + "_" + id_generator::hex_string(node.id())); + lck_cache.unlock(); + auto node_copy = Node(node); + auto effect = engine_->insert_node_local(std::move(node_copy)); + if (!effect.applied) { + return {}; + } + } + if (!copy) + { + DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) + { + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + } + } + return node.id(); + } + std::optional delta; bool inserted = false; { @@ -388,6 +482,43 @@ requires (std::is_same_v, DSR::Node>) { CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node"); + if (sync_mode == SyncMode::LWW) + { + std::vector changed_attributes; + { + std::unique_lock lock(_mutex); + std::shared_lock lck_cache(_mutex_cache_maps); + if (deleted.contains(node.id())) + throw std::runtime_error( + (std::string("Cannot update node in G, " + std::to_string(node.id()) + " is deleted") + __FILE__ + + " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); + else if (( id_map.contains(node.id()) and id_map.at(node.id()) != node.name()) or + ( name_map.contains(node.name()) and name_map.at(node.name()) != node.id())) + throw std::runtime_error( + (std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " + + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); + else if (id_map.contains(node.id())) { + lck_cache.unlock(); + auto node_copy = Node(node); + auto effect = engine_->update_node_local(std::move(node_copy)); + if (!effect.applied) { + return false; + } + changed_attributes = std::move(effect.changed_attributes); + } else { + return false; + } + } + if (!copy) { + DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + if (!changed_attributes.empty()) { + emitter.update_node_attr_signal(node.id(), changed_attributes, SignalInfo{agent_id}); + } + } + return true; + } + bool updated = false; std::optional vec_node_attr; @@ -448,6 +579,15 @@ bool DSRGraph::delete_node(const std::string &name) { CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(name)"); + if (sync_mode == SyncMode::LWW) + { + auto id = get_id_from_name(name); + if (!id.has_value()) { + return false; + } + return delete_node(*id); + } + bool result = false; std::vector deleted_edges; std::optional deleted_node; @@ -492,6 +632,32 @@ bool DSRGraph::delete_node(uint64_t id) { CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(id)"); + if (sync_mode == SyncMode::LWW) + { + NodeMutationEffect effect; + { + std::unique_lock lock(_mutex); + effect = engine_->delete_node_local(id); + } + + if (!effect.applied) { + return false; + } + + if (!copy) { + DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); + emitter.del_node_signal(id, SignalInfo{ agent_id }); + if (effect.deleted_node) { + emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); + } + for (auto &edge : effect.deleted_edges) { + emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); + emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); + } + } + return true; + } + bool result = false; std::vector deleted_edges; std::optional deleted_node; @@ -539,9 +705,15 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) nodes_.reserve(nodeType.at(type).size()); for (auto &id: nodeType.at(type)) { - std::optional n = get_(id); - if (n.has_value()) - nodes_.emplace_back(std::move(*n)); + if (sync_mode == SyncMode::LWW) { + if (auto node = engine_->get_node(id); node.has_value()) { + nodes_.emplace_back(std::move(*node)); + } + } else { + std::optional n = get_(id); + if (n.has_value()) + nodes_.emplace_back(std::move(*n)); + } } } return nodes_; @@ -550,7 +722,7 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) std::vector DSRGraph::get_nodes() { std::shared_lock lock(_mutex); - auto snapshot = crdt_engine().snapshot(); + auto snapshot = engine_->snapshot(); std::vector nodes_; nodes_.reserve(snapshot.size()); for (auto& [id, node] : snapshot) @@ -579,9 +751,15 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector n = get_(id); - if (n.has_value()) - nodes_.emplace_back(std::move(*n)); + if (sync_mode == SyncMode::LWW) { + if (auto node = engine_->get_node(id); node.has_value()) { + nodes_.emplace_back(std::move(*node)); + } + } else { + std::optional n = get_(id); + if (n.has_value()) + nodes_.emplace_back(std::move(*n)); + } } } } @@ -603,6 +781,9 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional id_to = get_id_from_name(to); if (id_from.has_value() and id_to.has_value()) { + if (sync_mode == SyncMode::LWW) { + return engine_->get_edge(id_from.value(), id_to.value(), key); + } auto edge_opt = get_edge_(id_from.value(), id_to.value(), key); if (edge_opt.has_value()) return Edge(edge_opt.value()); } @@ -612,6 +793,9 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional DSRGraph::get_edge(uint64_t from, uint64_t to, const std::string &key) { std::shared_lock lock(_mutex); + if (sync_mode == SyncMode::LWW) { + return engine_->get_edge(from, to, key); + } auto edge_opt = get_edge_(from, to, key); if (edge_opt.has_value()) return Edge(std::move(edge_opt.value())); return {}; @@ -647,6 +831,31 @@ bool DSRGraph::insert_or_assign_edge(Ed &&attrs) requires (std::is_same_v, DSR::Edge>) { CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge"); + + if (sync_mode == SyncMode::LWW) + { + std::vector changed_attributes; + { + std::unique_lock lock(_mutex); + auto edge_copy = Edge(attrs); + auto effect = engine_->insert_or_assign_edge_local(std::move(edge_copy)); + if (!effect.applied) { + std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << attrs.from() << " or " << attrs.to() + << " not found. Cant update. " << std::endl; + return false; + } + changed_attributes = std::move(effect.changed_attributes); + } + if (!copy) { + DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); + emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); + if (!changed_attributes.empty()) { + emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), changed_attributes, SignalInfo{ agent_id }); + } + } + return true; + } + bool result = false; std::optional delta_edge; std::optional delta_attrs; @@ -701,6 +910,26 @@ std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) { + if (sync_mode == SyncMode::LWW) + { + EdgeMutationEffect effect; + { + std::unique_lock lock(_mutex); + effect = engine_->delete_edge_local(from, to, key); + } + if (!effect.applied) + { + return false; + } + if (!copy) { + DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key); + emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id }); + if (effect.deleted_edge.has_value()) { + emitter.deleted_edge_signal(*effect.deleted_edge, SignalInfo{ agent_id }); + } + } + return true; + } std::optional delta; std::optional deleted_edge; @@ -726,6 +955,15 @@ bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::string &key) { + if (sync_mode == SyncMode::LWW) + { + auto id_from = get_id_from_name(from); + auto id_to = get_id_from_name(to); + if (!id_from.has_value() || !id_to.has_value()) { + return false; + } + return delete_edge(*id_from, *id_to, key); + } std::optional id_from = {}; std::optional id_to = {}; @@ -821,7 +1059,7 @@ std::optional, DSR::Edge>> DSRGraph::g std::map DSRGraph::getCopy() const { std::shared_lock lock(_mutex); - return crdt_engine().snapshot(); + return engine_->snapshot(); } ////////////////////////////////////////////////////////////////////////////// @@ -916,6 +1154,56 @@ void DSRGraph::update_maps_node_insert(uint64_t id, const CRDTNode &n) } } +void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional& n) +{ + std::unique_lock lck(_mutex_cache_maps); + if (id_map.contains(id)) + { + name_map.erase(id_map.at(id)); + id_map.erase(id); + } + deleted.insert(id); + to_edges.erase(id); + + if (n.has_value()) + { + if (nodeType.contains(n->type())) { + nodeType.at(n->type()).erase(id); + if (nodeType.at(n->type()).empty()) nodeType.erase(n->type()); + } + for (const auto &[k, v] : n->fano()) { + if (const auto tuple = std::pair{id, v.to()}; edges.contains(tuple)) { + edges.at(tuple).erase(k.second); + if (edges.at(tuple).empty()) edges.erase(tuple); + } + if (edgeType.contains(k.second)) { + edgeType.at(k.second).erase({id, k.first}); + if (edgeType.at(k.second).empty()) edgeType.erase(k.second); + } + if (to_edges.contains(k.first)) { + to_edges.at(k.first).erase({id, k.second}); + if (to_edges.at(k.first).empty()) to_edges.erase(k.first); + } + } + } +} + +void DSRGraph::update_maps_node_insert(const Node& n) +{ + std::unique_lock lck(_mutex_cache_maps); + + deleted.erase(n.id()); + name_map[n.name()] = n.id(); + id_map[n.id()] = n.name(); + nodeType[n.type()].emplace(n.id()); + for (const auto& [k, v] : n.fano()) + { + edges[{n.id(), k.first}].insert(k.second); + edgeType[k.second].insert({n.id(), k.first}); + to_edges[k.first].insert({n.id(), k.second}); + } +} + void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key) { @@ -966,7 +1254,7 @@ std::optional DSRGraph::get_name_from_id(uint64_t id) size_t DSRGraph::size() const { std::shared_lock lock(_mutex); - return crdt_engine().size(); + return engine_->size(); } @@ -1559,7 +1847,7 @@ DSRGraph::DSRGraph(const DSRGraph &G) same_host(G.same_host), generator(G.agent_id), log_level(G.log_level), - engine_(std::make_unique(*this, G.crdt_engine())), + engine_(make_sync_engine(*this, G.sync_mode)), tp(1, "join-copy"), tp_delta_attr(1, "attr-copy") { @@ -1573,6 +1861,18 @@ DSRGraph::DSRGraph(const DSRGraph &G) edgeType = G.edgeType; nodeType = G.nodeType; to_edges = G.to_edges; + if (sync_mode == SyncMode::CRDT) { + engine_ = std::make_unique(*this, G.crdt_engine()); + } else { + for (auto& [id, node] : G.engine_->snapshot()) { + engine_->insert_node_local(Node(node)); + } + for (auto& [id, node] : G.engine_->snapshot()) { + for (const auto& [key, edge] : node.fano()) { + engine_->insert_or_assign_edge_local(Edge(edge)); + } + } + } } std::unique_ptr DSRGraph::G_copy() diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp new file mode 100644 index 00000000..b42d128a --- /dev/null +++ b/api/dsr_lww_sync_engine.cpp @@ -0,0 +1,538 @@ +#include "dsr/api/dsr_lww_sync_engine.h" + +#include + +using namespace DSR; + +namespace { +template +void erase_if_compat(Map& map, Predicate&& predicate) +{ + for (auto it = map.begin(); it != map.end(); ) { + if (predicate(*it)) { + it = map.erase(it); + } else { + ++it; + } + } +} +} + +LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, uint64_t tombstone_window_ms) + : host_(host), + tombstone_window_ms_(tombstone_window_ms) +{ +} + +SyncBackendInfo LWWSyncEngine::backend_info() const +{ + return SyncBackendInfo{SyncMode::LWW, DSR_PROTOCOL_VERSION}; +} + +bool LWWSyncEngine::is_newer(const Version& lhs, const Version& rhs) +{ + return lhs.tie() > rhs.tie(); +} + +LWWSyncEngine::Version LWWSyncEngine::version_of(uint64_t timestamp, uint32_t agent_id) +{ + return Version{timestamp, agent_id}; +} + +LWWSyncEngine::EdgeKey LWWSyncEngine::edge_key(uint64_t from, uint64_t to, const std::string& type) +{ + return EdgeKey{from, to, type}; +} + +uint64_t LWWSyncEngine::current_time_ms() const +{ + return static_cast( + std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count()); +} + +uint64_t LWWSyncEngine::next_timestamp() +{ + logical_clock_ms_ = std::max(logical_clock_ms_ + 1, current_time_ms()); + return logical_clock_ms_; +} + +void LWWSyncEngine::prune_tombstones(uint64_t now) +{ + erase_if_compat(node_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); + erase_if_compat(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); +} + +Node LWWSyncEngine::to_node(const NodeState& state) const +{ + Node out(state.agent_id, state.type); + out.id(state.id); + out.name(state.name); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : state.attrs) { + attrs.emplace(name, attr.value); + } + auto& fano = out.fano(); + for (const auto& [key, edge] : edges_) { + if (edge.from != state.id) { + continue; + } + fano.emplace(std::pair{edge.to, edge.type}, to_edge(edge)); + } + return out; +} + +Edge LWWSyncEngine::to_edge(const EdgeState& state) const +{ + Edge out(state.to, state.from, state.type, {}, state.agent_id); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : state.attrs) { + attrs.emplace(name, attr.value); + } + return out; +} + +void LWWSyncEngine::store_node_tombstone(uint64_t id, Version version, uint64_t now) +{ + node_tombstones_[id] = Tombstone{version, now + tombstone_window_ms_}; +} + +void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now) +{ + edge_tombstones_[edge_key(from, to, type)] = Tombstone{version, now + tombstone_window_ms_}; +} + +void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) +{ + for (auto it = edges_.begin(); it != edges_.end(); ) { + if (it->second.from == node_id || it->second.to == node_id) { + host_.update_maps_edge_delete(it->second.from, it->second.to, it->second.type); + store_edge_tombstone(it->second.from, it->second.to, it->second.type, version, now); + if (removed_edges != nullptr) { + removed_edges->emplace_back(to_edge(it->second)); + } + it = edges_.erase(it); + } else { + ++it; + } + } +} + +bool LWWSyncEngine::node_delta_is_stale(uint64_t id, const Version& version) const +{ + if (auto it = node_tombstones_.find(id); it != node_tombstones_.end() && !is_newer(version, it->second.version)) { + return true; + } + if (auto it = nodes_.find(id); it != nodes_.end() && !is_newer(version, it->second.version)) { + return true; + } + return false; +} + +bool LWWSyncEngine::edge_delta_is_stale(uint64_t from, uint64_t to, const std::string& type, const Version& version) const +{ + if (auto it = edge_tombstones_.find(edge_key(from, to, type)); it != edge_tombstones_.end() && !is_newer(version, it->second.version)) { + return true; + } + if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end() && !is_newer(version, it->second.version)) { + return true; + } + return false; +} + +std::optional LWWSyncEngine::get_node(uint64_t id) const +{ + if (auto it = nodes_.find(id); it != nodes_.end()) { + return to_node(it->second); + } + return {}; +} + +std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const +{ + if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end()) { + return to_edge(it->second); + } + return {}; +} + +size_t LWWSyncEngine::size() const +{ + return nodes_.size(); +} + +std::map LWWSyncEngine::snapshot() const +{ + std::map out; + for (const auto& [id, node] : nodes_) { + out.emplace(id, to_node(node)); + } + return out; +} + +NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) +{ + auto now = next_timestamp(); + prune_tombstones(now); + + NodeMutationEffect effect; + effect.id = node.id(); + effect.type = node.type(); + + auto version = version_of(now, host_.local_agent_id()); + if (node_delta_is_stale(node.id(), version)) { + return effect; + } + + NodeState state; + state.id = node.id(); + state.type = node.type(); + state.name = node.name(); + state.agent_id = host_.local_agent_id(); + state.version = version; + for (const auto& [name, attr] : node.attrs()) { + state.attrs.emplace(name, AttrState{attr, version}); + effect.changed_attributes.emplace_back(name); + } + + nodes_[node.id()] = std::move(state); + node_tombstones_.erase(node.id()); + host_.update_maps_node_insert(node); + effect.applied = true; + return effect; +} + +NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) +{ + auto now = next_timestamp(); + prune_tombstones(now); + + NodeMutationEffect effect; + effect.id = node.id(); + effect.type = node.type(); + + auto it = nodes_.find(node.id()); + if (it == nodes_.end()) { + return effect; + } + + auto old_node = to_node(it->second); + auto version = version_of(now, host_.local_agent_id()); + it->second.type = node.type(); + it->second.name = node.name(); + it->second.version = version; + it->second.agent_id = host_.local_agent_id(); + + std::map next_attrs; + for (const auto& [name, attr] : node.attrs()) { + next_attrs.emplace(name, AttrState{attr, version}); + effect.changed_attributes.emplace_back(name); + } + for (const auto& [name, _] : it->second.attrs) { + if (!next_attrs.contains(name)) { + effect.changed_attributes.emplace_back(name); + } + } + it->second.attrs = std::move(next_attrs); + + host_.update_maps_node_delete(node.id(), old_node); + host_.update_maps_node_insert(node); + effect.applied = true; + return effect; +} + +NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) +{ + auto now = next_timestamp(); + prune_tombstones(now); + + NodeMutationEffect effect; + effect.id = id; + auto it = nodes_.find(id); + if (it == nodes_.end()) { + return effect; + } + + auto version = version_of(now, host_.local_agent_id()); + auto deleted_node = to_node(it->second); + effect.deleted_node = deleted_node; + effect.deleted_edges.clear(); + erase_related_edges(id, version, now, &effect.deleted_edges); + host_.update_maps_node_delete(id, deleted_node); + store_node_tombstone(id, version, now); + nodes_.erase(it); + effect.applied = true; + return effect; +} + +EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) +{ + auto now = next_timestamp(); + prune_tombstones(now); + + EdgeMutationEffect effect; + effect.from = edge.from(); + effect.to = edge.to(); + effect.type = edge.type(); + + auto version = version_of(now, host_.local_agent_id()); + if (!nodes_.contains(edge.from()) || !nodes_.contains(edge.to()) || + edge_delta_is_stale(edge.from(), edge.to(), edge.type(), version)) { + return effect; + } + + auto key = edge_key(edge.from(), edge.to(), edge.type()); + auto& state = edges_[key]; + state.from = edge.from(); + state.to = edge.to(); + state.type = edge.type(); + state.version = version; + state.agent_id = host_.local_agent_id(); + state.attrs.clear(); + for (const auto& [name, attr] : edge.attrs()) { + state.attrs.emplace(name, AttrState{attr, version}); + effect.changed_attributes.emplace_back(name); + } + edge_tombstones_.erase(key); + host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); + effect.applied = true; + return effect; +} + +EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, const std::string& type) +{ + auto now = next_timestamp(); + prune_tombstones(now); + + EdgeMutationEffect effect; + effect.from = from; + effect.to = to; + effect.type = type; + + auto key = edge_key(from, to, type); + auto it = edges_.find(key); + if (it == edges_.end()) { + return effect; + } + + auto version = version_of(now, host_.local_agent_id()); + effect.deleted_edge = to_edge(it->second); + host_.update_maps_edge_delete(from, to, type); + store_edge_tombstone(from, to, type, version, now); + edges_.erase(it); + effect.applied = true; + return effect; +} + +void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) +{ + auto* payload = std::get_if(&delta); + if (payload == nullptr) { + return; + } + + auto now = std::max(current_time_ms(), payload->timestamp); + logical_clock_ms_ = std::max(logical_clock_ms_, now); + prune_tombstones(now); + + auto version = version_of(payload->timestamp, payload->agent_id); + if (node_delta_is_stale(payload->id, version)) { + return; + } + + if (payload->deleted) { + if (auto it = nodes_.find(payload->id); it != nodes_.end()) { + auto deleted_node = to_node(it->second); + erase_related_edges(payload->id, version, now); + host_.update_maps_node_delete(payload->id, deleted_node); + nodes_.erase(it); + } + store_node_tombstone(payload->id, version, now); + return; + } + + NodeState state; + state.id = payload->id; + state.type = payload->type; + state.name = payload->name; + state.agent_id = payload->agent_id; + state.version = version; + for (const auto& [name, attr] : payload->attrs) { + state.attrs.emplace(name, AttrState{attr, version}); + } + + auto maybe_old = get_node(payload->id); + if (maybe_old.has_value()) { + host_.update_maps_node_delete(payload->id, maybe_old); + } + nodes_[payload->id] = std::move(state); + node_tombstones_.erase(payload->id); + host_.update_maps_node_insert(*get_node(payload->id)); +} + +void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) +{ + auto* payload = std::get_if(&delta); + if (payload == nullptr) { + return; + } + + auto now = std::max(current_time_ms(), payload->timestamp); + logical_clock_ms_ = std::max(logical_clock_ms_, now); + prune_tombstones(now); + + auto version = version_of(payload->timestamp, payload->agent_id); + if (edge_delta_is_stale(payload->from, payload->to, payload->type, version)) { + return; + } + if (!nodes_.contains(payload->from) || !nodes_.contains(payload->to)) { + return; + } + + auto key = edge_key(payload->from, payload->to, payload->type); + if (payload->deleted) { + if (edges_.contains(key)) { + host_.update_maps_edge_delete(payload->from, payload->to, payload->type); + edges_.erase(key); + } + store_edge_tombstone(payload->from, payload->to, payload->type, version, now); + return; + } + + EdgeState state; + state.from = payload->from; + state.to = payload->to; + state.type = payload->type; + state.agent_id = payload->agent_id; + state.version = version; + for (const auto& [name, attr] : payload->attrs) { + state.attrs.emplace(name, AttrState{attr, version}); + } + + edges_[key] = std::move(state); + edge_tombstones_.erase(key); + host_.update_maps_edge_insert(payload->from, payload->to, payload->type); +} + +void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) +{ + auto* payload = std::get_if(&batch); + if (payload == nullptr) { + return; + } + + for (const auto& item : payload->vec) { + auto it = nodes_.find(item.node_id); + if (it == nodes_.end()) { + continue; + } + auto version = version_of(item.timestamp, item.agent_id); + auto attr_it = it->second.attrs.find(item.attr_name); + if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { + continue; + } + if (item.deleted) { + it->second.attrs.erase(item.attr_name); + } else { + it->second.attrs[item.attr_name] = AttrState{item.value, version}; + } + } +} + +void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) +{ + auto* payload = std::get_if(&batch); + if (payload == nullptr) { + return; + } + + for (const auto& item : payload->vec) { + auto it = edges_.find(edge_key(item.from, item.to, item.type)); + if (it == edges_.end()) { + continue; + } + auto version = version_of(item.timestamp, item.agent_id); + auto attr_it = it->second.attrs.find(item.attr_name); + if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { + continue; + } + if (item.deleted) { + it->second.attrs.erase(item.attr_name); + } else { + it->second.attrs[item.attr_name] = AttrState{item.value, version}; + } + } +} + +void LWWSyncEngine::import_full_graph(FullGraphMessage&& full_graph) +{ + auto* payload = std::get_if(&full_graph); + if (payload == nullptr) { + return; + } + + tombstone_window_ms_ = payload->tombstone_window_ms == 0 ? tombstone_window_ms_ : payload->tombstone_window_ms; + for (const auto& node : payload->nodes) { + apply_remote_node_delta(NodeDeltaMessage{node}); + } + for (const auto& edge : payload->edges) { + apply_remote_edge_delta(EdgeDeltaMessage{edge}); + } +} + +FullGraphMessage LWWSyncEngine::export_full_graph() const +{ + LWWGraphSnapshot snapshot; + snapshot.id = static_cast(host_.local_agent_id()); + snapshot.protocol_version = DSR_PROTOCOL_VERSION; + snapshot.sync_mode = sync_mode_wire_value(SyncMode::LWW); + snapshot.tombstone_window_ms = tombstone_window_ms_; + + for (const auto& [id, node] : nodes_) { + LWWNodeMsg item; + item.id = id; + item.type = node.type; + item.name = node.name; + item.agent_id = node.agent_id; + item.timestamp = node.version.timestamp; + item.protocol_version = DSR_PROTOCOL_VERSION; + item.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : node.attrs) { + item.attrs.emplace(name, attr.value); + } + snapshot.nodes.emplace_back(std::move(item)); + } + + for (const auto& [key, edge] : edges_) { + LWWEdgeMsg item; + item.from = edge.from; + item.to = edge.to; + item.type = edge.type; + item.agent_id = edge.agent_id; + item.timestamp = edge.version.timestamp; + item.protocol_version = DSR_PROTOCOL_VERSION; + item.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : edge.attrs) { + item.attrs.emplace(name, attr.value); + } + snapshot.edges.emplace_back(std::move(item)); + } + + return snapshot; +} + +std::optional LWWSyncEngine::node_tombstone(uint64_t id) const +{ + if (auto it = node_tombstones_.find(id); it != node_tombstones_.end()) { + return it->second; + } + return {}; +} + +std::optional LWWSyncEngine::edge_tombstone(uint64_t from, uint64_t to, const std::string& type) const +{ + if (auto it = edge_tombstones_.find(edge_key(from, to, type)); it != edge_tombstones_.end()) { + return it->second; + } + return {}; +} diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index ec65b2be..6658dbe4 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -53,15 +53,17 @@ namespace DSR static constexpr uint64_t CLEAR_DELETED_SIGNAL = std::numeric_limits::max(); class CRDTSyncEngine; + class LWWSyncEngine; ///////////////////////////////////////////////////////////////// /// CRDT API ///////////////////////////////////////////////////////////////// - class DSRGraph : public QObject + class DSRGraph : public QObject, public SyncEngineHost { friend RT_API; friend class DSRGraphTestAccess; friend class CRDTSyncEngine; + friend class LWWSyncEngine; public: size_t size() const; @@ -515,22 +517,8 @@ namespace DSR { utils->read_from_json_file(file, [&] (const Node& node) -> std::optional { - bool r = false; - { - std::unique_lock lock(_mutex); - if (auto t1 = !id_map.contains(node.id()), t2 = !name_map.contains(node.name()); t1 and t2) { - std::tie(r, std::ignore) = insert_node_(user_node_to_crdt(node)); - } else { - if (!t1 and t2) throw std::runtime_error((std::string("Cannot insert node in G, a node with the same id (" + std::to_string(node.id()) +") already exists ") + __FILE__ + " " + " " + std::to_string(__LINE__)).data()); - if (t1) throw std::runtime_error((std::string("Cannot insert node in G, a node with the same name (" + node.name() +") already exists ") + __FILE__ + " " + " " + std::to_string(__LINE__)).data()); - throw std::runtime_error((std::string("Cannot insert node in G, a node with the same name (" + node.name() +") and same id (" + std::to_string(node.id()) +") already exists ") + __FILE__ + " " + " " + std::to_string(__LINE__)).data()); - } - - } - if (r) { - return node.id(); - } - return {}; + auto copy = node; + return insert_node_with_id(copy); }); }; @@ -640,8 +628,14 @@ namespace DSR void update_maps_node_delete(uint64_t id, const std::optional& n); void update_maps_node_insert(uint64_t id, const CRDTNode &n); - void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key = ""); - void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key); + void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key = "") override; + void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key) override; + + uint32_t local_agent_id() const override { return agent_id; } + SyncMode local_sync_mode() const override { return sync_mode; } + bool is_copy_graph() const override { return copy; } + void update_maps_node_insert(const Node& node) override; + void update_maps_node_delete(uint64_t id, const std::optional& node) override; CRDTSyncEngine& crdt_engine(); const CRDTSyncEngine& crdt_engine() const; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h new file mode 100644 index 00000000..3d8dfb31 --- /dev/null +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -0,0 +1,116 @@ +#pragma once + +#include "dsr/api/dsr_sync_engine.h" + +#include +#include +#include +#include +#include +#include + +namespace DSR { + +class LWWSyncEngine final : public SyncEngine +{ +public: + struct Version + { + uint64_t timestamp{}; + uint32_t agent_id{}; + + auto tie() const { return std::tie(timestamp, agent_id); } + }; + + struct Tombstone + { + Version version; + uint64_t expires_at_ms{}; + }; + + explicit LWWSyncEngine( + SyncEngineHost& host, + uint64_t tombstone_window_ms = std::chrono::duration_cast(std::chrono::minutes(5)).count()); + ~LWWSyncEngine() override = default; + + SyncBackendInfo backend_info() const override; + + std::optional get_node(uint64_t id) const override; + std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + size_t size() const override; + std::map snapshot() const override; + + NodeMutationEffect insert_node_local(Node&& node) override; + NodeMutationEffect update_node_local(Node&& node) override; + NodeMutationEffect delete_node_local(uint64_t id) override; + + EdgeMutationEffect insert_or_assign_edge_local(Edge&& edge) override; + EdgeMutationEffect delete_edge_local(uint64_t from, uint64_t to, const std::string& type) override; + + void apply_remote_node_delta(NodeDeltaMessage&& delta) override; + void apply_remote_edge_delta(EdgeDeltaMessage&& delta) override; + void apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) override; + void apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) override; + void import_full_graph(FullGraphMessage&& full_graph) override; + FullGraphMessage export_full_graph() const override; + + std::optional node_tombstone(uint64_t id) const; + std::optional edge_tombstone(uint64_t from, uint64_t to, const std::string& type) const; + +private: + struct AttrState + { + Attribute value; + Version version; + }; + + struct NodeState + { + uint64_t id{}; + std::string type; + std::string name; + uint32_t agent_id{}; + Version version; + std::map attrs; + }; + + struct EdgeState + { + uint64_t from{}; + uint64_t to{}; + std::string type; + uint32_t agent_id{}; + Version version; + std::map attrs; + }; + + using EdgeKey = std::tuple; + + static bool is_newer(const Version& lhs, const Version& rhs); + static Version version_of(uint64_t timestamp, uint32_t agent_id); + static EdgeKey edge_key(uint64_t from, uint64_t to, const std::string& type); + + uint64_t current_time_ms() const; + uint64_t next_timestamp(); + void prune_tombstones(uint64_t now); + + Node to_node(const NodeState& state) const; + Edge to_edge(const EdgeState& state) const; + + void store_node_tombstone(uint64_t id, Version version, uint64_t now); + void store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now); + void erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges = nullptr); + + bool node_delta_is_stale(uint64_t id, const Version& version) const; + bool edge_delta_is_stale(uint64_t from, uint64_t to, const std::string& type, const Version& version) const; + + SyncEngineHost& host_; + uint64_t tombstone_window_ms_; + uint64_t logical_clock_ms_{0}; + std::unordered_map nodes_; + std::unordered_map edges_; + std::unordered_map node_tombstones_; + std::unordered_map edge_tombstones_; +}; + +} // namespace DSR diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index f6584e02..20579ab8 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -35,6 +35,7 @@ add_executable(tests test.cpp crdt/crdt_operations.cpp synchronization/graph_synchronization.cpp synchronization/type_translation.cpp + synchronization/lww_sync_engine.cpp synchronization/graph_signals.cpp utils.h) @@ -78,4 +79,3 @@ if (TARGET cortex_profiling) cortex_profiling) endif() endif() - diff --git a/tests/synchronization/lww_sync_engine.cpp b/tests/synchronization/lww_sync_engine.cpp new file mode 100644 index 00000000..7143a591 --- /dev/null +++ b/tests/synchronization/lww_sync_engine.cpp @@ -0,0 +1,209 @@ +#include + +#include "dsr/api/dsr_api.h" +#include "dsr/api/dsr_lww_sync_engine.h" +#include "dsr/core/types/type_checking/dsr_attr_name.h" +#include "dsr/core/types/type_checking/dsr_edge_type.h" +#include "dsr/core/types/type_checking/dsr_node_type.h" + +using namespace DSR; + +namespace { + +struct FakeSyncHost final : SyncEngineHost +{ + uint32_t agent{17}; + SyncMode mode{SyncMode::LWW}; + bool copy{false}; + std::unordered_map nodes; + std::unordered_map, Edge, hash_tuple> edges; + + uint32_t local_agent_id() const override { return agent; } + SyncMode local_sync_mode() const override { return mode; } + bool is_copy_graph() const override { return copy; } + + void update_maps_node_insert(const Node& node) override { nodes[node.id()] = node; } + + void update_maps_node_delete(uint64_t id, const std::optional&) override + { + nodes.erase(id); + for (auto it = edges.begin(); it != edges.end(); ) { + if (std::get<0>(it->first) == id || std::get<1>(it->first) == id) { + it = edges.erase(it); + } else { + ++it; + } + } + } + + void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string& type) override + { + edges[std::tuple{from, to, type}] = Edge(to, from, type, {}, agent); + } + + void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string& type) override + { + edges.erase(std::tuple{from, to, type}); + } +}; + +Node make_robot(uint64_t id, std::string name, int level) +{ + auto node = Node::create(name); + node.id(id); + node.agent_id(17); + node.attrs()["level"] = Attribute(level, 1, 17); + return node; +} + +} // namespace + +TEST_CASE("LWW tombstones suppress older remote node recreation", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + REQUIRE(engine.insert_node_local(make_robot(1, "robot_1", 1)).applied); + auto deleted = engine.delete_node_local(1); + REQUIRE(deleted.applied); + REQUIRE_FALSE(engine.get_node(1).has_value()); + REQUIRE(engine.node_tombstone(1).has_value()); + + LWWNodeMsg older_recreate; + older_recreate.id = 1; + older_recreate.type = robot_node_type::attr_name; + older_recreate.name = "robot_1"; + older_recreate.agent_id = 3; + older_recreate.timestamp = deleted.deleted_node->attrs().at("level").timestamp(); + older_recreate.protocol_version = DSR_PROTOCOL_VERSION; + older_recreate.sync_mode = sync_mode_wire_value(SyncMode::LWW); + older_recreate.attrs.emplace("level", Attribute(2, older_recreate.timestamp, older_recreate.agent_id)); + engine.apply_remote_node_delta(NodeDeltaMessage{older_recreate}); + + REQUIRE_FALSE(engine.get_node(1).has_value()); +} + +TEST_CASE("LWW newer remote node recreation beats tombstone", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + REQUIRE(engine.insert_node_local(make_robot(2, "robot_2", 1)).applied); + REQUIRE(engine.delete_node_local(2).applied); + auto tombstone = engine.node_tombstone(2); + REQUIRE(tombstone.has_value()); + + LWWNodeMsg newer_recreate; + newer_recreate.id = 2; + newer_recreate.type = robot_node_type::attr_name; + newer_recreate.name = "robot_2b"; + newer_recreate.agent_id = 8; + newer_recreate.timestamp = tombstone->version.timestamp + 1; + newer_recreate.deleted = false; + newer_recreate.protocol_version = DSR_PROTOCOL_VERSION; + newer_recreate.sync_mode = sync_mode_wire_value(SyncMode::LWW); + newer_recreate.attrs.emplace("level", Attribute(9, newer_recreate.timestamp, newer_recreate.agent_id)); + engine.apply_remote_node_delta(NodeDeltaMessage{newer_recreate}); + + auto node = engine.get_node(2); + REQUIRE(node.has_value()); + REQUIRE(node->name() == "robot_2b"); + REQUIRE(node->attrs().at("level").dec() == 9); +} + +TEST_CASE("LWW update_node keeps full replacement API semantics", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + auto node = make_robot(3, "robot_3", 1); + node.attrs()["parent"] = Attribute(7, 1, 17); + REQUIRE(engine.insert_node_local(std::move(node)).applied); + + auto replacement = make_robot(3, "robot_3", 5); + auto effect = engine.update_node_local(std::move(replacement)); + REQUIRE(effect.applied); + + auto stored = engine.get_node(3); + REQUIRE(stored.has_value()); + REQUIRE(stored->attrs().contains("level")); + REQUIRE_FALSE(stored->attrs().contains("parent")); +} + +TEST_CASE("LWW edge tombstones allow newer recreation", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + REQUIRE(engine.insert_node_local(make_robot(10, "robot_a", 1)).applied); + REQUIRE(engine.insert_node_local(make_robot(11, "robot_b", 1)).applied); + + auto edge = Edge::create(10, 11); + edge.attrs()["weight"] = Attribute(1, 1, 17); + REQUIRE(engine.insert_or_assign_edge_local(std::move(edge)).applied); + REQUIRE(engine.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + REQUIRE(engine.delete_edge_local(10, 11, std::string(RT_edge_type::attr_name)).applied); + REQUIRE_FALSE(engine.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + auto tombstone = engine.edge_tombstone(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(tombstone.has_value()); + + LWWEdgeMsg newer_edge; + newer_edge.from = 10; + newer_edge.to = 11; + newer_edge.type = RT_edge_type::attr_name; + newer_edge.agent_id = 22; + newer_edge.timestamp = tombstone->version.timestamp + 1; + newer_edge.deleted = false; + newer_edge.protocol_version = DSR_PROTOCOL_VERSION; + newer_edge.sync_mode = sync_mode_wire_value(SyncMode::LWW); + newer_edge.attrs.emplace("weight", Attribute(4, newer_edge.timestamp, newer_edge.agent_id)); + engine.apply_remote_edge_delta(EdgeDeltaMessage{newer_edge}); + + auto stored = engine.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(stored.has_value()); + REQUIRE(stored->attrs().at("weight").dec() == 4); +} + +TEST_CASE("DSRGraph LWW mode supports local core mutations without DDS", "[LWW][GRAPH]") +{ + GraphSettings settings; + settings.agent_id = 31; + settings.graph_name = "lww_local_graph"; + settings.sync_mode = SyncMode::LWW; + settings.same_host = true; + + DSRGraph graph(settings); + + auto parent = make_robot(100, "parent", 1); + auto child = make_robot(101, "child", 2); + + REQUIRE(graph.insert_node_with_id(parent).has_value()); + REQUIRE(graph.insert_node_with_id(child).has_value()); + REQUIRE(graph.size() == 2); + + auto edge = Edge::create(100, 101); + edge.attrs()["weight"] = Attribute(3, 1, settings.agent_id); + REQUIRE(graph.insert_or_assign_edge(edge)); + + auto stored_parent = graph.get_node(100); + REQUIRE(stored_parent.has_value()); + REQUIRE(stored_parent->name() == "parent"); + + auto stored_edge = graph.get_edge(100, 101, std::string(RT_edge_type::attr_name)); + REQUIRE(stored_edge.has_value()); + REQUIRE(stored_edge->attrs().at("weight").dec() == 3); + + auto replacement = make_robot(100, "parent", 7); + REQUIRE(graph.update_node(replacement)); + stored_parent = graph.get_node(100); + REQUIRE(stored_parent.has_value()); + REQUIRE(stored_parent->attrs().at("level").dec() == 7); + + REQUIRE(graph.delete_edge(100, 101, std::string(RT_edge_type::attr_name))); + REQUIRE_FALSE(graph.get_edge(100, 101, std::string(RT_edge_type::attr_name)).has_value()); + + REQUIRE(graph.delete_node(100)); + REQUIRE_FALSE(graph.get_node(100).has_value()); + REQUIRE(graph.size() == 1); +} From cac46620af6e583f2800ed9fbd8cbb27384aeda8 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Tue, 21 Apr 2026 23:06:07 +0200 Subject: [PATCH 11/38] refactor: route sync queries through backend interface --- api/dsr_api.cpp | 283 +++++++++++++------- api/dsr_crdt_sync_engine.cpp | 40 +++ api/dsr_lww_sync_engine.cpp | 100 +++++++ api/include/dsr/api/dsr_api.h | 2 + api/include/dsr/api/dsr_crdt_sync_engine.h | 3 + api/include/dsr/api/dsr_lww_sync_engine.h | 5 + api/include/dsr/api/dsr_sync_engine.h | 8 + core/include/dsr/core/rtps/dsrparticipant.h | 3 +- core/include/dsr/core/rtps/dsrpublisher.h | 5 + core/rtps/dsrparticipant.cpp | 29 +- core/rtps/dsrpublisher.cpp | 60 +++++ tests/synchronization/lww_sync_engine.cpp | 79 +++--- 12 files changed, 480 insertions(+), 137 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index b5b54b91..482c3667 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -123,24 +123,9 @@ DSRGraph::DSRGraph(GraphSettings settings) : set_queued_signals(); } } - if (sync_mode == SyncMode::LWW) + if (sync_mode == SyncMode::LWW && !same_host) { - if (!settings.input_file.empty()) - { - try - { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph load local LWW graph"); - read_from_json_file(settings.input_file); - qDebug() << __FUNCTION__ << "Warning, graph read from file " << QString::fromStdString(settings.input_file); - } - catch(const DSR::DSRException& e) - { - std::cout << e.what() << '\n'; - qFatal("Aborting program. Cannot continue without intial file"); - } - } - qDebug() << __FUNCTION__ << "Constructor finished OK"; - return; + qFatal("DSRGraph aborting: SyncMode::LWW currently supports same_host only"); } // RTPS Create participant auto participant_init_result = [&]() { @@ -185,7 +170,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : if (!deleted) graph->delete_node(pname); } - }), settings.domain_id); + }), settings.domain_id, sync_mode == SyncMode::LWW); }(); auto[suc, participant_handle] = std::move(participant_init_result); @@ -294,6 +279,16 @@ const CRDTSyncEngine& DSRGraph::crdt_engine() const return static_cast(*engine_); } +LWWSyncEngine& DSRGraph::lww_engine() +{ + return static_cast(*engine_); +} + +const LWWSyncEngine& DSRGraph::lww_engine() const +{ + return static_cast(*engine_); +} + ////////////////////////////////////// /// NODE METHODS ///////////////////////////////////// @@ -353,11 +348,14 @@ std::optional DSRGraph::insert_node(No &&node) } if (!copy) { - DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { + dsrpub_node.write(&delta.value()); + DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) + { + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + } } } return node.id(); @@ -424,11 +422,14 @@ std::optional DSRGraph::insert_node_with_id(No &&node) } if (!copy) { - DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { + dsrpub_node.write(&delta.value()); + DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) + { + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); + } } } return node.id(); @@ -510,10 +511,13 @@ requires (std::is_same_v, DSR::Node>) } } if (!copy) { - DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - if (!changed_attributes.empty()) { - emitter.update_node_attr_signal(node.id(), changed_attributes, SignalInfo{agent_id}); + if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { + dsrpub_node.write(&delta.value()); + DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + if (!changed_attributes.empty()) { + emitter.update_node_attr_signal(node.id(), changed_attributes, SignalInfo{agent_id}); + } } } return true; @@ -650,6 +654,14 @@ bool DSRGraph::delete_node(uint64_t id) if (effect.deleted_node) { emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); } + if (auto delta = lww_engine().export_node_delta(id); delta.has_value()) { + dsrpub_node.write(&delta.value()); + } + for (auto &edge : effect.deleted_edges) { + if (auto delta = lww_engine().export_edge_delta(edge.from(), edge.to(), edge.type()); delta.has_value()) { + dsrpub_edge.write(&delta.value()); + } + } for (auto &edge : effect.deleted_edges) { emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); @@ -705,14 +717,8 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) nodes_.reserve(nodeType.at(type).size()); for (auto &id: nodeType.at(type)) { - if (sync_mode == SyncMode::LWW) { - if (auto node = engine_->get_node(id); node.has_value()) { - nodes_.emplace_back(std::move(*node)); - } - } else { - std::optional n = get_(id); - if (n.has_value()) - nodes_.emplace_back(std::move(*n)); + if (auto node = engine_->get_node(id); node.has_value()) { + nodes_.emplace_back(std::move(*node)); } } } @@ -751,14 +757,8 @@ std::vector DSRGraph::get_nodes_by_types(const std::vectorget_node(id); node.has_value()) { - nodes_.emplace_back(std::move(*node)); - } - } else { - std::optional n = get_(id); - if (n.has_value()) - nodes_.emplace_back(std::move(*n)); + if (auto node = engine_->get_node(id); node.has_value()) { + nodes_.emplace_back(std::move(*node)); } } } @@ -781,11 +781,7 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional id_to = get_id_from_name(to); if (id_from.has_value() and id_to.has_value()) { - if (sync_mode == SyncMode::LWW) { - return engine_->get_edge(id_from.value(), id_to.value(), key); - } - auto edge_opt = get_edge_(id_from.value(), id_to.value(), key); - if (edge_opt.has_value()) return Edge(edge_opt.value()); + return engine_->get_edge(id_from.value(), id_to.value(), key); } return {}; } @@ -793,12 +789,7 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional DSRGraph::get_edge(uint64_t from, uint64_t to, const std::string &key) { std::shared_lock lock(_mutex); - if (sync_mode == SyncMode::LWW) { - return engine_->get_edge(from, to, key); - } - auto edge_opt = get_edge_(from, to, key); - if (edge_opt.has_value()) return Edge(std::move(edge_opt.value())); - return {}; + return engine_->get_edge(from, to, key); } std::optional DSRGraph::get_edge(const Node &n, const std::string &to, const std::string &key) @@ -847,10 +838,13 @@ requires (std::is_same_v, DSR::Edge>) changed_attributes = std::move(effect.changed_attributes); } if (!copy) { - DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); - emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); - if (!changed_attributes.empty()) { - emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), changed_attributes, SignalInfo{ agent_id }); + if (auto delta = lww_engine().export_edge_delta(attrs.from(), attrs.to(), attrs.type()); delta.has_value()) { + dsrpub_edge.write(&delta.value()); + DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); + emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); + if (!changed_attributes.empty()) { + emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), changed_attributes, SignalInfo{ agent_id }); + } } } return true; @@ -927,6 +921,9 @@ bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) if (effect.deleted_edge.has_value()) { emitter.deleted_edge_signal(*effect.deleted_edge, SignalInfo{ agent_id }); } + if (auto delta = lww_engine().export_edge_delta(from, to, key); delta.has_value()) { + dsrpub_edge.write(&delta.value()); + } } return true; } @@ -1010,11 +1007,15 @@ std::vector DSRGraph::get_edges_by_type(const std::string &type) std::vector edges_; if (edgeType.contains(type)) { edges_.reserve(edgeType.at(type).size()); - for (auto &[from, to] : edgeType.at(type)) { - auto edge = get_edge_(from, to, type); - if (edge.has_value()) { - edges_.emplace_back(std::move(edge.value())); - } + engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { + edges_.emplace_back(edge); + }); + } else { + engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { + edges_.emplace_back(edge); + }); + if (!edges_.empty()) { + edges_.shrink_to_fit(); } } return edges_; @@ -1027,28 +1028,23 @@ std::vector DSRGraph::get_edges_to_id(uint64_t id) std::vector edges_; if (to_edges.contains(id)) { edges_.reserve(to_edges.at(id).size()); - for (const auto &[k, v] : to_edges.at(id)) { - auto n = get_edge_(k, id, v); - if (n.has_value()) - edges_.emplace_back(std::move(n.value())); - } } + engine_->for_each_edge_to(id, [&](uint64_t, const std::string&, const Edge& edge) { + edges_.emplace_back(edge); + }); return edges_; } std::optional, DSR::Edge>> DSRGraph::get_edges(uint64_t id) { std::shared_lock lock(_mutex); - const auto* node = get_node_ptr_(id); - if (node == nullptr) { - return std::nullopt; - } - std::map, DSR::Edge> edges_; - for (const auto &[key, edge_reg] : node->fano()) { - edges_.emplace(key, DSR::Edge(edge_reg.read_reg())); + if (engine_->for_each_edge_from(id, [&](uint64_t to, const std::string& type, const Edge& edge) { + edges_.emplace(std::pair{to, type}, edge); + })) { + return edges_; } - return edges_; + return std::nullopt; } @@ -1092,7 +1088,7 @@ std::optional DSRGraph::get_parent_node(const Node &n) if (p.has_value()) { std::shared_lock lock(_mutex); - if (const auto* tmp = get_node_ptr_(p.value()); tmp != nullptr) return Node(*tmp); + return engine_->get_node(p.value()); } return {}; } @@ -1511,6 +1507,22 @@ void DSRGraph::node_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; + if (sync_mode == SyncMode::LWW) { + DSR::LWWNodeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("LWW_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); + } + continue; + } DSR::MvregNodeMsg sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); @@ -1559,6 +1571,22 @@ void DSRGraph::edge_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; + if (sync_mode == SyncMode::LWW) { + DSR::LWWEdgeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("LWW_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); + } + continue; + } DSR::MvregEdgeMsg sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); @@ -1602,6 +1630,22 @@ void DSRGraph::edge_attrs_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; + if (sync_mode == SyncMode::LWW) { + DSR::LWWEdgeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("LWW_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + continue; + } DSR::MvregEdgeAttrVec samples; if (reader->take_next_sample(&samples, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); @@ -1651,6 +1695,22 @@ void DSRGraph::node_attrs_subscription_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; + if (sync_mode == SyncMode::LWW) { + DSR::LWWNodeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("LWW_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + continue; + } DSR::MvregNodeAttrVec samples; if (reader->take_next_sample(&samples, &m_info) == 0) { if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); @@ -1709,12 +1769,21 @@ void DSRGraph::fullgraph_server_thread() { if (it->second) { lck.unlock(); - DSR::OrMap mp; - mp.id = -1; - mp.to_id = static_cast(sample.id); - mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; - mp.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_request_answer.write(&mp); + if (sync_mode == SyncMode::LWW) { + DSR::LWWGraphSnapshot mp; + mp.id = -1; + mp.to_id = static_cast(sample.id); + mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; + mp.sync_mode = sync_mode_wire_value(sync_mode); + dsrpub_request_answer.write(&mp); + } else { + DSR::OrMap mp; + mp.id = -1; + mp.to_id = static_cast(sample.id); + mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; + mp.sync_mode = sync_mode_wire_value(sync_mode); + dsrpub_request_answer.write(&mp); + } continue; } else {} } else { @@ -1727,9 +1796,15 @@ void DSRGraph::fullgraph_server_thread() qDebug() << " Received Full Graph request: from " << m_info.sample_identity.writer_guid().entityId.value; auto full_graph_message = graph->engine_->export_full_graph(); - auto mp = std::get(std::move(full_graph_message)); - mp.id = static_cast(graph->get_agent_id()); - dsrpub_request_answer.write(&mp); + if (sync_mode == SyncMode::LWW) { + auto mp = std::get(std::move(full_graph_message)); + mp.id = static_cast(graph->get_agent_id()); + dsrpub_request_answer.write(&mp); + } else { + auto mp = std::get(std::move(full_graph_message)); + mp.id = static_cast(graph->get_agent_id()); + dsrpub_request_answer.write(&mp); + } qDebug() << "Full graph written"; @@ -1759,6 +1834,32 @@ std::pair DSRGraph::fullgraph_request_thread() while (true) { eprosima::fastdds::dds::SampleInfo m_info; + if (sync_mode == SyncMode::LWW) { + DSR::LWWGraphSnapshot sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); + if (m_info.valid_data) { + if (!network_compatibility_or_fatal("LWW_GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (static_cast(sample.id) != graph->get_agent_id()) { + if (sample.id != -1) { + tp.spawn_task([this, s = std::move(sample)]() mutable { + engine_->import_full_graph(FullGraphMessage{std::move(s)}); + }); + sync = true; + break; + } + else if (!sync && sample.to_id == agent_id) + { + repeated = true; + } + } + } + continue; + } DSR::OrMap sample; if (reader->take_next_sample(&sample, &m_info) == 0) { if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 1e50016e..c4cf0e78 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -65,6 +65,46 @@ std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const s return {}; } +bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const +{ + if (const auto* node = get_node_ptr(from); node != nullptr) { + for (const auto& [key, edge_reg] : node->fano()) { + if (!edge_reg.empty()) { + Edge edge(edge_reg.read_reg()); + visitor(key.first, key.second, edge); + } + } + return true; + } + return false; +} + +bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const +{ + if (auto it = host_.to_edges.find(to); it != host_.to_edges.end()) { + for (const auto& [from, type] : it->second) { + if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + Edge out(std::move(*edge)); + visitor(from, type, out); + } + } + return true; + } + return false; +} + +void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const +{ + if (auto it = host_.edgeType.find(type); it != host_.edgeType.end()) { + for (const auto& [from, to] : it->second) { + if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + Edge out(std::move(*edge)); + visitor(from, to, out); + } + } + } +} + size_t CRDTSyncEngine::size() const { return nodes_.size(); diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index b42d128a..ac14d063 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -156,6 +156,43 @@ std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const st return {}; } +bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const +{ + if (!nodes_.contains(from)) { + return false; + } + for (const auto& [key, edge] : edges_) { + if (edge.from == from) { + Edge out = to_edge(edge); + visitor(edge.to, edge.type, out); + } + } + return true; +} + +bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const +{ + bool found = false; + for (const auto& [key, edge] : edges_) { + if (edge.to == to) { + Edge out = to_edge(edge); + visitor(edge.from, edge.type, out); + found = true; + } + } + return found; +} + +void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const +{ + for (const auto& [key, edge] : edges_) { + if (edge.type == type) { + Edge out = to_edge(edge); + visitor(edge.from, edge.to, out); + } + } +} + size_t LWWSyncEngine::size() const { return nodes_.size(); @@ -536,3 +573,66 @@ std::optional LWWSyncEngine::edge_tombstone(uint64_t f } return {}; } + +std::optional LWWSyncEngine::export_node_delta(uint64_t id) const +{ + if (auto it = nodes_.find(id); it != nodes_.end()) { + LWWNodeMsg msg; + msg.id = it->second.id; + msg.type = it->second.type; + msg.name = it->second.name; + msg.agent_id = it->second.agent_id; + msg.timestamp = it->second.version.timestamp; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : it->second.attrs) { + msg.attrs.emplace(name, attr.value); + } + return msg; + } + if (auto it = node_tombstones_.find(id); it != node_tombstones_.end()) { + LWWNodeMsg msg; + msg.id = id; + msg.agent_id = it->second.version.agent_id; + msg.timestamp = it->second.version.timestamp; + msg.deleted = true; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; + } + return {}; +} + +std::optional LWWSyncEngine::export_edge_delta(uint64_t from, uint64_t to, const std::string& type) const +{ + auto key = edge_key(from, to, type); + if (auto it = edges_.find(key); it != edges_.end()) { + LWWEdgeMsg msg; + msg.from = it->second.from; + msg.to = it->second.to; + msg.type = it->second.type; + msg.agent_id = it->second.agent_id; + msg.timestamp = it->second.version.timestamp; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : it->second.attrs) { + msg.attrs.emplace(name, attr.value); + } + return msg; + } + if (auto it = edge_tombstones_.find(key); it != edge_tombstones_.end()) { + LWWEdgeMsg msg; + msg.from = from; + msg.to = to; + msg.type = type; + msg.agent_id = it->second.version.agent_id; + msg.timestamp = it->second.version.timestamp; + msg.deleted = true; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; + } + return {}; +} diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 6658dbe4..a0beb287 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -639,6 +639,8 @@ namespace DSR CRDTSyncEngine& crdt_engine(); const CRDTSyncEngine& crdt_engine() const; + LWWSyncEngine& lww_engine(); + const LWWSyncEngine& lww_engine() const; ////////////////////////////////////////////////////////////////////////// diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 787450bd..59265065 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -26,6 +26,9 @@ class CRDTSyncEngine final : public SyncEngine std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const override; + bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const override; + void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const override; size_t size() const override; std::map snapshot() const override; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index 3d8dfb31..cd25a0ca 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -37,6 +37,9 @@ class LWWSyncEngine final : public SyncEngine std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const override; + bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const override; + void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const override; size_t size() const override; std::map snapshot() const override; @@ -56,6 +59,8 @@ class LWWSyncEngine final : public SyncEngine std::optional node_tombstone(uint64_t id) const; std::optional edge_tombstone(uint64_t from, uint64_t to, const std::string& type) const; + std::optional export_node_delta(uint64_t id) const; + std::optional export_edge_delta(uint64_t from, uint64_t to, const std::string& type) const; private: struct AttrState diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h index 9d2a46d9..ec83c6dd 100644 --- a/api/include/dsr/api/dsr_sync_engine.h +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -5,6 +5,7 @@ #include "dsr/core/types/user_types.h" #include +#include #include #include #include @@ -68,12 +69,19 @@ class SyncEngineHost class SyncEngine { public: + using OutgoingEdgeVisitor = std::function; + using IncomingEdgeVisitor = std::function; + using TypedEdgeVisitor = std::function; + virtual ~SyncEngine() = default; virtual SyncBackendInfo backend_info() const = 0; virtual std::optional get_node(uint64_t id) const = 0; virtual std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const = 0; + virtual bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const = 0; + virtual bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const = 0; + virtual void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const = 0; virtual size_t size() const = 0; virtual std::map snapshot() const = 0; diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index ee773895..1df9c60b 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -17,7 +17,7 @@ class DSRParticipant public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0); + [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, bool lww_mode = false); [[nodiscard]] int8_t get_domain_id() const { return domain_id_; } [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; [[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->get_name().data();} @@ -44,6 +44,7 @@ class DSRParticipant private: int8_t domain_id_ {0}; + bool cleanup_enabled_ {true}; eprosima::fastdds::dds::DomainParticipant* mp_participant{}; eprosima::fastdds::dds::Topic* topic_node{}; diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index 1a28bde9..66cd3012 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -28,6 +28,11 @@ class DSRPublisher bool write(DSR::MvregEdgeMsg *object); bool write(DSR::MvregEdgeAttrVec *object); bool write(DSR::MvregNodeAttrVec *object); + bool write(DSR::LWWNodeMsg *object); + bool write(DSR::LWWEdgeMsg *object); + bool write(DSR::LWWNodeAttrVec *object); + bool write(DSR::LWWEdgeAttrVec *object); + bool write(DSR::LWWGraphSnapshot *object); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index c03b6d6d..d631a74c 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -42,16 +42,18 @@ DSRParticipant::DSRParticipant() : mp_participant(nullptr), DSRParticipant::~DSRParticipant() { - - remove_participant_and_entities(); + if (cleanup_enabled_) { + remove_participant_and_entities(); + } qDebug() << "Removing DSRParticipant" ; } -std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id) +std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, bool lww) { domain_id_ = domain_id; + cleanup_enabled_ = !lww; // Create RTPSParticipant DomainParticipantQos PParam; PParam.name(("Participant_" + std::to_string(agent_id)+ " ( " + agent_name + " )").data() ); @@ -111,6 +113,15 @@ std::tuple DSRParticipant::ini } + if (lww) { + dsrgraphType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeMsg")); + graphrequestType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("GraphRequest")); + graphRequestAnswerType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWGraphSnapshot")); + dsrEdgeType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeMsg")); + dsrNodeAttrType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeAttrVec")); + dsrEdgeAttrType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeAttrVec")); + } + //Register types dsrgraphType.register_type(mp_participant); dsrgraphType.register_type(mp_participant); @@ -121,12 +132,12 @@ std::tuple DSRParticipant::ini dsrEdgeAttrType.register_type(mp_participant); //Create topics - topic_node = mp_participant->create_topic("DSR_NODE", dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge = mp_participant->create_topic("DSR_EDGE", dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_node_att = mp_participant->create_topic("DSR_NODE_ATTS", dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge_att = mp_participant->create_topic("DSR_EDGE_ATTS", dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph_request = mp_participant->create_topic("GRAPH_REQUEST", graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph = mp_participant->create_topic("GRAPH_ANSWER", graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node = mp_participant->create_topic(lww ? "LWW_NODE" : "DSR_NODE", dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge = mp_participant->create_topic(lww ? "LWW_EDGE" : "DSR_EDGE", dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node_att = mp_participant->create_topic(lww ? "LWW_NODE_ATTS" : "DSR_NODE_ATTS", dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge_att = mp_participant->create_topic(lww ? "LWW_EDGE_ATTS" : "DSR_EDGE_ATTS", dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph_request = mp_participant->create_topic(lww ? "LWW_GRAPH_REQUEST" : "GRAPH_REQUEST", graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph = mp_participant->create_topic(lww ? "LWW_GRAPH_ANSWER" : "GRAPH_ANSWER", graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); return std::make_tuple(true, mp_participant); } diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index 895f4a17..14e1e3ee 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -182,6 +182,66 @@ bool DSRPublisher::write(DSR::MvregNodeAttrVec *object) { return false; } +bool DSRPublisher::write(DSR::LWWNodeMsg *object) +{ + ReturnCode_t rt; + int retry = 0; + while (retry < 5) { + if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + retry++; + } + qInfo() << "Error writing LWW NODE " << object->id << " after 5 attempts. error code: " << rt; + return false; +} + +bool DSRPublisher::write(DSR::LWWEdgeMsg *object) +{ + ReturnCode_t rt; + int retry = 0; + while (retry < 5) { + if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + retry++; + } + qInfo() << "Error writing LWW EDGE " << object->from << " " << object->to << " " << object->type.data() << " after 5 attempts. error code: " << rt; + return false; +} + +bool DSRPublisher::write(DSR::LWWNodeAttrVec *object) +{ + ReturnCode_t rt; + int retry = 0; + while (retry < 5) { + if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + retry++; + } + qInfo() << "Error writing LWW NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + return false; +} + +bool DSRPublisher::write(DSR::LWWEdgeAttrVec *object) +{ + ReturnCode_t rt; + int retry = 0; + while (retry < 5) { + if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + retry++; + } + qInfo() << "Error writing LWW EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + return false; +} + +bool DSRPublisher::write(DSR::LWWGraphSnapshot *object) +{ + ReturnCode_t rt; + int retry = 0; + while (retry < 5) { + if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + retry++; + } + qInfo() << "Error writing LWW GRAPH " << object->nodes.size() << " nodes after 5 attempts. error code: " << rt; + return false; +} + void DSRPublisher::PubListener::on_publication_matched(eprosima::fastdds::dds::DataWriter* writer, const eprosima::fastdds::dds::PublicationMatchedStatus& info) diff --git a/tests/synchronization/lww_sync_engine.cpp b/tests/synchronization/lww_sync_engine.cpp index 7143a591..edec6d87 100644 --- a/tests/synchronization/lww_sync_engine.cpp +++ b/tests/synchronization/lww_sync_engine.cpp @@ -1,5 +1,8 @@ #include +#include + +#include "../utils.h" #include "dsr/api/dsr_api.h" #include "dsr/api/dsr_lww_sync_engine.h" #include "dsr/core/types/type_checking/dsr_attr_name.h" @@ -7,6 +10,7 @@ #include "dsr/core/types/type_checking/dsr_node_type.h" using namespace DSR; +using namespace std::chrono_literals; namespace { @@ -165,45 +169,48 @@ TEST_CASE("LWW edge tombstones allow newer recreation", "[LWW][ENGINE]") REQUIRE(stored->attrs().at("weight").dec() == 4); } -TEST_CASE("DSRGraph LWW mode supports local core mutations without DDS", "[LWW][GRAPH]") +TEST_CASE("Same-process LWW agents synchronize over DDS", "[LWW][DDS]") { - GraphSettings settings; - settings.agent_id = 31; - settings.graph_name = "lww_local_graph"; - settings.sync_mode = SyncMode::LWW; - settings.same_host = true; - - DSRGraph graph(settings); - - auto parent = make_robot(100, "parent", 1); - auto child = make_robot(101, "child", 2); - - REQUIRE(graph.insert_node_with_id(parent).has_value()); - REQUIRE(graph.insert_node_with_id(child).has_value()); - REQUIRE(graph.size() == 2); + auto ctx = make_edge_config_file(); - auto edge = Edge::create(100, 101); - edge.attrs()["weight"] = Attribute(3, 1, settings.agent_id); - REQUIRE(graph.insert_or_assign_edge(edge)); + GraphSettings loader_settings; + loader_settings.agent_id = static_cast(rand() % 1000 + 2500); + loader_settings.graph_name = random_string(10); + loader_settings.input_file = ctx; + loader_settings.same_host = true; + loader_settings.sync_mode = SyncMode::LWW; - auto stored_parent = graph.get_node(100); - REQUIRE(stored_parent.has_value()); - REQUIRE(stored_parent->name() == "parent"); + GraphSettings follower_settings = loader_settings; + follower_settings.agent_id += 1; + follower_settings.graph_name = random_string(11); + follower_settings.input_file.clear(); - auto stored_edge = graph.get_edge(100, 101, std::string(RT_edge_type::attr_name)); - REQUIRE(stored_edge.has_value()); - REQUIRE(stored_edge->attrs().at("weight").dec() == 3); + DSRGraph loader(loader_settings); + DSRGraph follower(follower_settings); - auto replacement = make_robot(100, "parent", 7); - REQUIRE(graph.update_node(replacement)); - stored_parent = graph.get_node(100); - REQUIRE(stored_parent.has_value()); - REQUIRE(stored_parent->attrs().at("level").dec() == 7); - - REQUIRE(graph.delete_edge(100, 101, std::string(RT_edge_type::attr_name))); - REQUIRE_FALSE(graph.get_edge(100, 101, std::string(RT_edge_type::attr_name)).has_value()); - - REQUIRE(graph.delete_node(100)); - REQUIRE_FALSE(graph.get_node(100).has_value()); - REQUIRE(graph.size() == 1); + auto wait_until = [](auto&& predicate, std::chrono::milliseconds timeout = 3000ms) + { + const auto deadline = std::chrono::steady_clock::now() + timeout; + while (std::chrono::steady_clock::now() < deadline) + { + if (predicate()) + return true; + std::this_thread::sleep_for(50ms); + } + return predicate(); + }; + + REQUIRE(wait_until([&] { return follower.size() == loader.size(); })); + + auto root_loader = loader.get_node("root"); + REQUIRE(root_loader.has_value()); + root_loader->attrs()["lww_loader_sync"] = + Attribute(std::string("loader"), get_unix_timestamp(), loader.get_agent_id()); + REQUIRE(loader.update_node(root_loader.value())); + + REQUIRE(wait_until([&] { + auto root_follower = follower.get_node("root"); + return root_follower.has_value() && + root_follower->attrs().contains("lww_loader_sync"); + })); } From 4af78565a47a3f1d7acacbf49dbc863e0742016f Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 14:57:27 +0200 Subject: [PATCH 12/38] refactor: centralize sync transport profiles --- api/dsr_api.cpp | 1344 ++++++++----------- api/dsr_crdt_sync_engine.cpp | 25 +- api/dsr_lww_sync_engine.cpp | 31 + api/include/dsr/api/dsr_api.h | 25 + api/include/dsr/api/dsr_crdt_sync_engine.h | 1 + api/include/dsr/api/dsr_lww_sync_engine.h | 49 +- api/include/dsr/api/dsr_sync_engine.h | 6 + core/include/dsr/core/rtps/dsrparticipant.h | 4 +- core/include/dsr/core/types/lww_types.h | 55 + core/rtps/dsrparticipant.cpp | 27 +- 10 files changed, 749 insertions(+), 818 deletions(-) create mode 100644 core/include/dsr/core/types/lww_types.h diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 482c3667..df7865a0 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -95,6 +95,8 @@ bool network_compatibility_or_fatal( } } +void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info); + ///////////////////////////////////////////////// ///// PUBLIC METHODS ///////////////////////////////////////////////// @@ -170,7 +172,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : if (!deleted) graph->delete_node(pname); } - }), settings.domain_id, sync_mode == SyncMode::LWW); + }), settings.domain_id, sync_mode_wire_value(sync_mode)); }(); auto[suc, participant_handle] = std::move(participant_init_result); @@ -246,19 +248,15 @@ DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_f DSRGraph::~DSRGraph() { qDebug() << "Removing DSRGraph"; - if (sync_mode == SyncMode::CRDT) { - dsrparticipant.remove_participant_and_entities(); - } - if (!copy && sync_mode == SyncMode::CRDT) { + dsrparticipant.remove_participant_and_entities(); + if (!copy) { qDebug() << "Removing rtps participant"; } } void DSRGraph::reset() { - if (sync_mode == SyncMode::CRDT) { - dsrparticipant.remove_participant_and_entities(); - } + dsrparticipant.remove_participant_and_entities(); engine_ = make_sync_engine(*this, sync_mode); deleted.clear(); name_map.clear(); @@ -289,6 +287,417 @@ const LWWSyncEngine& DSRGraph::lww_engine() const return static_cast(*engine_); } +void DSRGraph::publish_node_message(const NodeDeltaMessage& message) +{ + std::visit([this](const auto& payload) { + auto copy = payload; + dsrpub_node.write(©); + }, message); +} + +void DSRGraph::publish_node_attr_batch(const NodeAttrDeltaBatchMessage& message) +{ + std::visit([this](const auto& payload) { + auto copy = payload; + dsrpub_node_attrs.write(©); + }, message); +} + +void DSRGraph::publish_edge_message(const EdgeDeltaMessage& message) +{ + std::visit([this](const auto& payload) { + auto copy = payload; + dsrpub_edge.write(©); + }, message); +} + +void DSRGraph::publish_edge_attr_batch(const EdgeAttrDeltaBatchMessage& message) +{ + std::visit([this](const auto& payload) { + auto copy = payload; + dsrpub_edge_attrs.write(©); + }, message); +} + +void DSRGraph::publish_full_graph_message(FullGraphMessage&& message, int32_t sender_id) +{ + std::visit([this, sender_id](auto&& payload) { + using T = std::decay_t; + T copy = std::forward(payload); + copy.id = sender_id; + dsrpub_request_answer.write(©); + }, std::move(message)); +} + +const DSRGraph::TransportProfile& DSRGraph::transport_profile() const +{ + static const TransportProfile profiles[] = { + { + &DSRGraph::make_crdt_node_subscription_functor, + &DSRGraph::make_crdt_edge_subscription_functor, + &DSRGraph::make_crdt_edge_attrs_subscription_functor, + &DSRGraph::make_crdt_node_attrs_subscription_functor, + &DSRGraph::make_crdt_fullgraph_request_functor, + }, + { + &DSRGraph::make_lww_node_subscription_functor, + &DSRGraph::make_lww_edge_subscription_functor, + &DSRGraph::make_lww_edge_attrs_subscription_functor, + &DSRGraph::make_lww_node_attrs_subscription_functor, + &DSRGraph::make_lww_fullgraph_request_functor, + }, + }; + return profiles[sync_mode_wire_value(sync_mode)]; +} + +DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_subscription_functor() +{ + auto name = "node_subscription_thread"; + return NewMessageFunctor(this, [this, name, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::MvregNodeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("DSR_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (sample.id == CLEAR_DELETED_SIGNAL) { + std::unique_lock lock(_mutex); + std::unique_lock lck_cache(_mutex_cache_maps); + deleted.clear(); + continue; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " + << m_info.sample_identity.writer_guid().entityId.value; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_subscription_functor() +{ + return NewMessageFunctor(this, [this, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::LWWNodeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("LWW_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_subscription_functor() +{ + auto name = "edge_subscription_thread"; + return NewMessageFunctor(this, [this, name, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::MvregEdgeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("DSR_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " + << m_info.sample_identity.writer_guid().entityId.value; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_subscription_functor() +{ + return NewMessageFunctor(this, [this, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::LWWEdgeMsg sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data && sample.agent_id != agent_id) { + if (!network_compatibility_or_fatal("LWW_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_attrs_subscription_functor() +{ + auto name = "edge_attrs_subscription_thread"; + return NewMessageFunctor(this, [this, name, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::MvregEdgeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data) { + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " + << m_info.sample_identity.writer_guid().entityId.value; + } + if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) + { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("DSR_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_attrs_subscription_functor() +{ + return NewMessageFunctor(this, [this] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::LWWEdgeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("LWW_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_attrs_subscription_functor() +{ + auto name = "node_attrs_subscription_thread"; + return NewMessageFunctor(this, [this, name, showReceived = log_level] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::MvregNodeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (m_info.valid_data) { + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " + << m_info.sample_identity.writer_guid().entityId.value; + } + if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("DSR_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_attrs_subscription_functor() +{ + return NewMessageFunctor(this, [this] + (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); + try { + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::LWWNodeAttrVec samples; + if (reader->take_next_sample(&samples, &m_info) != 0) { + break; + } + if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { + const auto& first = samples.vec.front(); + if (!network_compatibility_or_fatal("LWW_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { + continue; + } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); + }); + } + } + } + catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_crdt_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +{ + return NewMessageFunctor(this, [this, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::OrMap sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); + if (m_info.valid_data) { + if (!network_compatibility_or_fatal("GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (static_cast(sample.id) != graph->get_agent_id()) { + if (sample.id != -1) { + qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value + << " whith " + << sample.m.size() << " elements"; + tp.spawn_task([this, s = std::move(sample)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); + engine_->import_full_graph(FullGraphMessage{std::move(s)}); + }); + qDebug() << "Synchronized."; + sync = true; + break; + } else if (!sync && sample.to_id == agent_id) { + repeated = true; + } + } + } + } + }); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_lww_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +{ + return NewMessageFunctor(this, [this, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + { + [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); + while (true) + { + eprosima::fastdds::dds::SampleInfo m_info; + DSR::LWWGraphSnapshot sample; + if (reader->take_next_sample(&sample, &m_info) != 0) { + break; + } + if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); + if (m_info.valid_data) { + if (!network_compatibility_or_fatal("LWW_GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (static_cast(sample.id) != graph->get_agent_id()) { + if (sample.id != -1) { + tp.spawn_task([this, s = std::move(sample)]() mutable { + engine_->import_full_graph(FullGraphMessage{std::move(s)}); + }); + sync = true; + break; + } else if (!sync && sample.to_id == agent_id) { + repeated = true; + } + } + } + } + }); +} + ////////////////////////////////////// /// NODE METHODS ///////////////////////////////////// @@ -301,10 +710,7 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional id = get_id_from_name(name); if (id.has_value()) { - if (sync_mode == SyncMode::LWW) { - return engine_->get_node(id.value()); - } - if (const auto* n = get_node_ptr_(id.value()); n != nullptr) return Node(*n); + return engine_->get_node(id.value()); } return {}; } @@ -313,11 +719,7 @@ std::optional DSRGraph::get_node(uint64_t id) { CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(id)"); std::shared_lock lock(_mutex); - if (sync_mode == SyncMode::LWW) { - return engine_->get_node(id); - } - if (const auto* n = get_node_ptr_(id); n != nullptr) return Node(*n); - return {}; + return engine_->get_node(id); } std::tuple> DSRGraph::insert_node_(CRDTNode &&node) @@ -329,42 +731,9 @@ template std::optional DSRGraph::insert_node(No &&node) requires (std::is_same_v, DSR::Node>) { - if (sync_mode == SyncMode::LWW) - { - { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node LWW"); - std::unique_lock lock(_mutex); - std::shared_lock lck_cache(_mutex_cache_maps); - uint64_t new_node_id = generator.generate(); - node.id(new_node_id); - if (node.name().empty() or name_map.contains(node.name())) - node.name(node.type() + "_" + id_generator::hex_string(new_node_id)); - lck_cache.unlock(); - auto node_copy = Node(node); - auto effect = engine_->insert_node_local(std::move(node_copy)); - if (!effect.applied) { - return {}; - } - } - if (!copy) - { - if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { - dsrpub_node.write(&delta.value()); - DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); - } - } - } - return node.id(); - } - - std::optional delta; - bool inserted = false; + NodeMutationEffect effect; { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph merge phase"); + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node local"); std::unique_lock lock(_mutex); std::shared_lock lck_cache(_mutex_cache_maps); uint64_t new_node_id = generator.generate(); @@ -372,26 +741,25 @@ std::optional DSRGraph::insert_node(No &&node) if (node.name().empty() or name_map.contains(node.name())) node.name(node.type() + "_" + id_generator::hex_string(new_node_id)); lck_cache.unlock(); - std::tie(inserted, delta) = insert_node_(user_node_to_crdt(std::forward(node))); + effect = engine_->insert_node_local(Node(node)); + if (!effect.applied) { + return {}; + } } - if (inserted) + if (!copy) { - if (!copy) + if (effect.node_delta.has_value()) { - if (delta.has_value()) + publish_node_message(*effect.node_delta); + DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) { - dsrpub_node.write(&delta.value()); - DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); - } + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); } } - return node.id(); } - return {}; + return node.id(); } template std::optional DSRGraph::insert_node(DSR::Node&&); @@ -402,72 +770,36 @@ template std::optional DSRGraph::insert_node_with_id(No &&node) requires (std::is_same_v, DSR::Node>) { - if (sync_mode == SyncMode::LWW) - { - { - std::unique_lock lock(_mutex); - std::shared_lock lck_cache(_mutex_cache_maps); - if (id_map.contains(node.id())) { - DSR_LOG_WARNING("[INSERT_NODE_WITH_ID] Node id already exists", node.id(), node.type()); - return {}; - } - if (node.name().empty() or name_map.contains(node.name())) - node.name(node.type() + "_" + id_generator::hex_string(node.id())); - lck_cache.unlock(); - auto node_copy = Node(node); - auto effect = engine_->insert_node_local(std::move(node_copy)); - if (!effect.applied) { - return {}; - } - } - if (!copy) - { - if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { - dsrpub_node.write(&delta.value()); - DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); - } - } - } - return node.id(); - } - - std::optional delta; - bool inserted = false; + NodeMutationEffect effect; { std::unique_lock lock(_mutex); std::shared_lock lck_cache(_mutex_cache_maps); - //Check id - if (get_node_ptr_(node.id()) != nullptr) { + if (id_map.contains(node.id())) { DSR_LOG_WARNING("[INSERT_NODE_WITH_ID] Node id already exists", node.id(), node.type()); return {}; } if (node.name().empty() or name_map.contains(node.name())) node.name(node.type() + "_" + id_generator::hex_string(node.id())); lck_cache.unlock(); - std::tie(inserted, delta) = insert_node_(user_node_to_crdt(std::forward(node))); + effect = engine_->insert_node_local(Node(node)); + if (!effect.applied) { + return {}; + } } - if (inserted) + if (!copy) { - if (!copy) + if (effect.node_delta.has_value()) { - if (delta.has_value()) + publish_node_message(*effect.node_delta); + DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + for (const auto &[k, v]: node.fano()) { - dsrpub_node.write(&delta.value()); - DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - for (const auto &[k, v]: node.fano()) - { - emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); - } + emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id}); } } - return node.id(); } - return {}; + return node.id(); } template std::optional DSRGraph::insert_node_with_id(DSR::Node&&); @@ -482,49 +814,7 @@ bool DSRGraph::update_node(No &&node) requires (std::is_same_v, DSR::Node>) { CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node"); - - if (sync_mode == SyncMode::LWW) - { - std::vector changed_attributes; - { - std::unique_lock lock(_mutex); - std::shared_lock lck_cache(_mutex_cache_maps); - if (deleted.contains(node.id())) - throw std::runtime_error( - (std::string("Cannot update node in G, " + std::to_string(node.id()) + " is deleted") + __FILE__ + - " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (( id_map.contains(node.id()) and id_map.at(node.id()) != node.name()) or - ( name_map.contains(node.name()) and name_map.at(node.name()) != node.id())) - throw std::runtime_error( - (std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " + - __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (id_map.contains(node.id())) { - lck_cache.unlock(); - auto node_copy = Node(node); - auto effect = engine_->update_node_local(std::move(node_copy)); - if (!effect.applied) { - return false; - } - changed_attributes = std::move(effect.changed_attributes); - } else { - return false; - } - } - if (!copy) { - if (auto delta = lww_engine().export_node_delta(node.id()); delta.has_value()) { - dsrpub_node.write(&delta.value()); - DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - if (!changed_attributes.empty()) { - emitter.update_node_attr_signal(node.id(), changed_attributes, SignalInfo{agent_id}); - } - } - } - return true; - } - - bool updated = false; - std::optional vec_node_attr; + NodeMutationEffect effect; { std::unique_lock lock(_mutex); @@ -538,28 +828,32 @@ requires (std::is_same_v, DSR::Node>) throw std::runtime_error( (std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (get_node_ptr_(node.id()) != nullptr) { + else if (id_map.contains(node.id())) { lck_cache.unlock(); - std::tie(updated, vec_node_attr) = update_node_(user_node_to_crdt(std::forward(node))); + effect = engine_->update_node_local(Node(node)); + if (!effect.applied) { + return false; + } + } else { + return false; } } - if (updated) { - if (!copy) { - if (vec_node_attr.has_value()) { - dsrpub_node_attrs.write(&vec_node_attr.value()); - DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); - emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); - std::vector atts_names(vec_node_attr->vec.size()); - std::transform(std::make_move_iterator(vec_node_attr->vec.begin()), - std::make_move_iterator(vec_node_attr->vec.end()), - atts_names.begin(), - [](auto &&x) { return x.attr_name; }); - emitter.update_node_attr_signal(node.id(), atts_names, SignalInfo{agent_id}); - + if (!copy) { + if (effect.node_delta.has_value()) { + publish_node_message(*effect.node_delta); + } + if (effect.node_attr_batch.has_value()) { + publish_node_attr_batch(*effect.node_attr_batch); + } + if (effect.node_delta.has_value() || effect.node_attr_batch.has_value()) { + DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); + emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); + if (!effect.changed_attributes.empty()) { + emitter.update_node_attr_signal(node.id(), effect.changed_attributes, SignalInfo{agent_id}); } } } - return updated; + return true; } template bool DSRGraph::update_node(DSR::Node&&); @@ -582,130 +876,126 @@ bool DSRGraph::delete_node(const DSR::Node &node) bool DSRGraph::delete_node(const std::string &name) { CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(name)"); - - if (sync_mode == SyncMode::LWW) - { - auto id = get_id_from_name(name); - if (!id.has_value()) { - return false; - } - return delete_node(*id); + auto id = get_id_from_name(name); + if (!id.has_value()) { + return false; } + return delete_node(*id); +} - bool result = false; - std::vector deleted_edges; - std::optional deleted_node; - std::vector delta_vec; - std::optional node_signal; - std::optional node_snapshot; - std::optional id = {}; +bool DSRGraph::delete_node(uint64_t id) +{ + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(id)"); + NodeMutationEffect effect; { - id = get_id_from_name(name); - if (id.has_value()) { - std::unique_lock lock(_mutex); - node_snapshot = get_(*id); - if (!node_snapshot.has_value()) return false; - node_signal = Node(*node_snapshot); - std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id.value(), *node_snapshot); - } else { - return false; - } + std::unique_lock lock(_mutex); + effect = engine_->delete_node_local(id); + } + if (!effect.applied) { + return false; } - if (result) { - if (!copy) { - DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id.value()); - emitter.del_node_signal(id.value(), SignalInfo{agent_id}); - if (node_signal) emitter.deleted_node_signal(*node_signal, SignalInfo{agent_id}); - dsrpub_node.write(&deleted_node.value()); - - for (auto &a : delta_vec) { - dsrpub_edge.write(&a); - } - for (auto &edge : deleted_edges) { - emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); - emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); - } + if (!copy) { + DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); + emitter.del_node_signal(id, SignalInfo{ agent_id }); + if (effect.deleted_node) { + emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); + } + if (effect.node_delta.has_value()) { + publish_node_message(*effect.node_delta); + } + for (const auto &delta : effect.edge_deltas) { + publish_edge_message(delta); + } + for (auto &edge : effect.deleted_edges) { + emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); + emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); } - return true; } - return false; + + return true; } -bool DSRGraph::delete_node(uint64_t id) +template +bool DSRGraph::insert_or_assign_edge(Ed &&attrs) +requires (std::is_same_v, DSR::Edge>) { - CORTEX_PROFILE_ZONE_N("DSRGraph::delete_node(id)"); + CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge"); - if (sync_mode == SyncMode::LWW) + EdgeMutationEffect effect; { - NodeMutationEffect effect; - { - std::unique_lock lock(_mutex); - effect = engine_->delete_node_local(id); - } - + std::unique_lock lock(_mutex); + auto edge_copy = Edge(attrs); + effect = engine_->insert_or_assign_edge_local(std::move(edge_copy)); if (!effect.applied) { + std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << attrs.from() << " or " << attrs.to() + << " not found. Cant update. " << std::endl; return false; } + } + if (!copy) { + DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); + emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); - if (!copy) { - DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); - emitter.del_node_signal(id, SignalInfo{ agent_id }); - if (effect.deleted_node) { - emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); - } - if (auto delta = lww_engine().export_node_delta(id); delta.has_value()) { - dsrpub_node.write(&delta.value()); - } - for (auto &edge : effect.deleted_edges) { - if (auto delta = lww_engine().export_edge_delta(edge.from(), edge.to(), edge.type()); delta.has_value()) { - dsrpub_edge.write(&delta.value()); - } - } - for (auto &edge : effect.deleted_edges) { - emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); - emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); - } + if (effect.edge_delta.has_value()) { + publish_edge_message(*effect.edge_delta); + } + if (effect.edge_attr_batch.has_value()) { + publish_edge_attr_batch(*effect.edge_attr_batch); + } + if (!effect.changed_attributes.empty()) { + emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), effect.changed_attributes, SignalInfo{ agent_id }); } - return true; } + return true; +} + + +template bool DSRGraph::insert_or_assign_edge(DSR::Edge&&); +template bool DSRGraph::insert_or_assign_edge(DSR::Edge&&); +template bool DSRGraph::insert_or_assign_edge(DSR::Edge&); +template bool DSRGraph::insert_or_assign_edge(const DSR::Edge&); + + +std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) +{ + return crdt_engine().delete_edge_raw(from, to, key); +} - bool result = false; - std::vector deleted_edges; - std::optional deleted_node; - std::optional node_signal; - std::optional node_snapshot; - std::vector delta_vec; +bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) +{ + EdgeMutationEffect effect; { std::unique_lock lock(_mutex); - node_snapshot = get_(id); - if (!node_snapshot.has_value()) return false; - node_signal = Node(*node_snapshot); - std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id, *node_snapshot); + effect = engine_->delete_edge_local(from, to, key); } - - if (result) { - if (!copy) { - DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); - emitter.del_node_signal(id, SignalInfo{ agent_id }); - if (node_signal) emitter.deleted_node_signal(*node_signal, SignalInfo{agent_id}); - dsrpub_node.write(&deleted_node.value()); - - for (auto &a : delta_vec) { - dsrpub_edge.write(&a); - } - for (auto &edge : deleted_edges) { - emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); - emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); - } + if (!effect.applied) + { + return false; + } + if (!copy) { + DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key); + emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id }); + if (effect.deleted_edge.has_value()) { + emitter.deleted_edge_signal(*effect.deleted_edge, SignalInfo{ agent_id }); + } + if (effect.edge_delta.has_value()) { + publish_edge_message(*effect.edge_delta); } - return true; } + return true; +} - return false; +bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::string &key) +{ + std::optional id_from = get_id_from_name(from); + std::optional id_to = get_id_from_name(to); + if (!id_from.has_value() || !id_to.has_value()) { + return false; + } + return delete_edge(*id_from, *id_to, key); } - std::vector DSRGraph::get_nodes_by_type(const std::string &type) { std::shared_lock lock(_mutex); @@ -738,7 +1028,6 @@ std::vector DSRGraph::get_nodes() return nodes_; } - std::vector DSRGraph::get_nodes_by_types(const std::vector &types) { std::shared_lock lock(_mutex); @@ -810,187 +1099,12 @@ std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::st return {}; } - std::tuple, std::optional> DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) { return crdt_engine().insert_or_assign_edge_raw(std::move(attrs), from, to); } -template -bool DSRGraph::insert_or_assign_edge(Ed &&attrs) -requires (std::is_same_v, DSR::Edge>) -{ - CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge"); - - if (sync_mode == SyncMode::LWW) - { - std::vector changed_attributes; - { - std::unique_lock lock(_mutex); - auto edge_copy = Edge(attrs); - auto effect = engine_->insert_or_assign_edge_local(std::move(edge_copy)); - if (!effect.applied) { - std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << attrs.from() << " or " << attrs.to() - << " not found. Cant update. " << std::endl; - return false; - } - changed_attributes = std::move(effect.changed_attributes); - } - if (!copy) { - if (auto delta = lww_engine().export_edge_delta(attrs.from(), attrs.to(), attrs.type()); delta.has_value()) { - dsrpub_edge.write(&delta.value()); - DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); - emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); - if (!changed_attributes.empty()) { - emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), changed_attributes, SignalInfo{ agent_id }); - } - } - } - return true; - } - - bool result = false; - std::optional delta_edge; - std::optional delta_attrs; - - { - std::unique_lock lock(_mutex); - uint64_t from = attrs.from(); - uint64_t to = attrs.to(); - if (get_node_ptr_(from) != nullptr && get_node_ptr_(to) != nullptr) { - std::tie(result, delta_edge, delta_attrs) = insert_or_assign_edge_(user_edge_to_crdt(std::forward(attrs)), from, to); - } else { - std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << from << " or " << to - << " not found. Cant update. " << std::endl; - return false; - } - } - if (result) { - if (!copy) { - DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); - emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); - - if (delta_edge.has_value()) { //Insert - dsrpub_edge.write(&delta_edge.value()); - } - if (delta_attrs.has_value()) { //Update - dsrpub_edge_attrs.write(&delta_attrs.value()); - std::vector atts_names(delta_attrs->vec.size()); - std::transform(std::make_move_iterator(delta_attrs->vec.begin()), - std::make_move_iterator(delta_attrs->vec.end()), - atts_names.begin(), - [](auto &&x) { return x.attr_name; }); - - emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), atts_names, SignalInfo{ agent_id }); - - } - } - } - return true; -} - - -template bool DSRGraph::insert_or_assign_edge(DSR::Edge&&); -template bool DSRGraph::insert_or_assign_edge(DSR::Edge&&); -template bool DSRGraph::insert_or_assign_edge(DSR::Edge&); -template bool DSRGraph::insert_or_assign_edge(const DSR::Edge&); - - -std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) -{ - return crdt_engine().delete_edge_raw(from, to, key); -} - -bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) -{ - if (sync_mode == SyncMode::LWW) - { - EdgeMutationEffect effect; - { - std::unique_lock lock(_mutex); - effect = engine_->delete_edge_local(from, to, key); - } - if (!effect.applied) - { - return false; - } - if (!copy) { - DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key); - emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id }); - if (effect.deleted_edge.has_value()) { - emitter.deleted_edge_signal(*effect.deleted_edge, SignalInfo{ agent_id }); - } - if (auto delta = lww_engine().export_edge_delta(from, to, key); delta.has_value()) { - dsrpub_edge.write(&delta.value()); - } - } - return true; - } - - std::optional delta; - std::optional deleted_edge; - { - std::unique_lock lock(_mutex); - deleted_edge = get_edge_(from, to, key); - delta = delete_edge_(from, to, key); - } - if (delta.has_value()) - { - if (!copy) { - DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key); - emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id }); - if (deleted_edge.has_value()) { - emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id }); - } - dsrpub_edge.write(&delta.value()); - } - return true; - } - return false; -} - -bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::string &key) -{ - if (sync_mode == SyncMode::LWW) - { - auto id_from = get_id_from_name(from); - auto id_to = get_id_from_name(to); - if (!id_from.has_value() || !id_to.has_value()) { - return false; - } - return delete_edge(*id_from, *id_to, key); - } - - std::optional id_from = {}; - std::optional id_to = {}; - std::optional delta; - std::optional deleted_edge; - { - id_from = get_id_from_name(from); - id_to = get_id_from_name(to); - std::unique_lock lock(_mutex); - deleted_edge = get_edge_(id_from.value(), id_to.value(), key); - if (id_from.has_value() && id_to.has_value()) - { - delta = delete_edge_(id_from.value(), id_to.value(), key); - } - } - if (delta.has_value()) - { - if (!copy) { - emitter.del_edge_signal(id_from.value(), id_to.value(), key, SignalInfo{ agent_id }); - if (deleted_edge.has_value()) { - emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id }); - } - dsrpub_edge.write(&delta.value()); - } - return true; - } - return false; -} - - std::vector DSRGraph::get_node_edges_by_type(const Node &node, const std::string &type) { std::vector edges_; @@ -1497,63 +1611,7 @@ void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::f void DSRGraph::node_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread setup"); - auto name = __FUNCTION__; - auto lambda_general_topic = [&, name = name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - if (sync_mode == SyncMode::LWW) { - DSR::LWWNodeMsg sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("LWW_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); - }); - } - continue; - } - DSR::MvregNodeMsg sample; - if (reader->take_next_sample(&sample, &m_info) == 0) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("DSR_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (sample.id == CLEAR_DELETED_SIGNAL) { - std::unique_lock lock(_mutex); - std::unique_lock lck_cache(_mutex_cache_maps); - deleted.clear(); - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); - }); - } - } - } else { - break; - } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }; - dsrpub_call_node = NewMessageFunctor(this, lambda_general_topic); + dsrpub_call_node = (this->*transport_profile().make_node_functor)(); auto [res, sub, reader] = dsrsub_node.init(dsrparticipant.getParticipant(), dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), {sub, reader}); } @@ -1561,57 +1619,7 @@ void DSRGraph::node_subscription_thread() void DSRGraph::edge_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread setup"); - auto name = __FUNCTION__; - auto lambda_general_topic = [&, name = name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - if (sync_mode == SyncMode::LWW) { - DSR::LWWEdgeMsg sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("LWW_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); - }); - } - continue; - } - DSR::MvregEdgeMsg sample; - if (reader->take_next_sample(&sample, &m_info) == 0) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("DSR_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); - }); - } - } - } else { - break; - } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }; - dsrpub_call_edge = NewMessageFunctor(this, lambda_general_topic); + dsrpub_call_edge = (this->*transport_profile().make_edge_functor)(); auto [res, sub, reader] = dsrsub_edge.init(dsrparticipant.getParticipant(), dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), {sub, reader}); @@ -1620,61 +1628,7 @@ void DSRGraph::edge_subscription_thread() void DSRGraph::edge_attrs_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread setup"); - auto name = __FUNCTION__; - auto lambda_general_topic = [&, name = name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - if (sync_mode == SyncMode::LWW) { - DSR::LWWEdgeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; - } - if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("LWW_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); - }); - } - continue; - } - DSR::MvregEdgeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) == 0) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) - { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("DSR_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); - engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); - }); - } - } - } else { - break; - } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - - }; - dsrpub_call_edge_attrs = NewMessageFunctor(this, lambda_general_topic); + dsrpub_call_edge_attrs = (this->*transport_profile().make_edge_attrs_functor)(); auto [res, sub, reader] = dsrsub_edge_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge_attrs, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getAttEdgeTopic()->get_name(), {sub, reader}); @@ -1685,60 +1639,7 @@ void DSRGraph::edge_attrs_subscription_thread() void DSRGraph::node_attrs_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread setup"); - auto name = __FUNCTION__; - auto lambda_general_topic = [this, name = name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - if (sync_mode == SyncMode::LWW) { - DSR::LWWNodeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; - } - if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("LWW_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); - }); - } - continue; - } - DSR::MvregNodeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) == 0) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("DSR_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); - engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); - }); - } - } - } else { - break; - } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - - }; - dsrpub_call_node_attrs = NewMessageFunctor(this, lambda_general_topic); + dsrpub_call_node_attrs = (this->*transport_profile().make_node_attrs_functor)(); auto [res, sub, reader] = dsrsub_node_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node_attrs, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getAttNodeTopic()->get_name(), {sub, reader}); @@ -1769,21 +1670,16 @@ void DSRGraph::fullgraph_server_thread() { if (it->second) { lck.unlock(); - if (sync_mode == SyncMode::LWW) { - DSR::LWWGraphSnapshot mp; - mp.id = -1; - mp.to_id = static_cast(sample.id); - mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; - mp.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_request_answer.write(&mp); - } else { - DSR::OrMap mp; - mp.id = -1; - mp.to_id = static_cast(sample.id); - mp.protocol_version = DSR::DSR_PROTOCOL_VERSION; - mp.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_request_answer.write(&mp); - } + auto repeated_graph = graph->engine_->export_full_graph(); + std::visit([&](auto&& payload) { + using T = std::decay_t; + T empty{}; + empty.id = -1; + empty.to_id = static_cast(sample.id); + empty.protocol_version = DSR::DSR_PROTOCOL_VERSION; + empty.sync_mode = sync_mode_wire_value(sync_mode); + dsrpub_request_answer.write(&empty); + }, std::move(repeated_graph)); continue; } else {} } else { @@ -1796,15 +1692,7 @@ void DSRGraph::fullgraph_server_thread() qDebug() << " Received Full Graph request: from " << m_info.sample_identity.writer_guid().entityId.value; auto full_graph_message = graph->engine_->export_full_graph(); - if (sync_mode == SyncMode::LWW) { - auto mp = std::get(std::move(full_graph_message)); - mp.id = static_cast(graph->get_agent_id()); - dsrpub_request_answer.write(&mp); - } else { - auto mp = std::get(std::move(full_graph_message)); - mp.id = static_cast(graph->get_agent_id()); - dsrpub_request_answer.write(&mp); - } + publish_full_graph_message(std::move(full_graph_message), static_cast(graph->get_agent_id())); qDebug() << "Full graph written"; @@ -1827,72 +1715,7 @@ std::pair DSRGraph::fullgraph_request_thread() CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread"); std::atomic sync{false}; std::atomic repeated{false}; - auto lambda_request_answer = [&](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - if (sync_mode == SyncMode::LWW) { - DSR::LWWGraphSnapshot sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (m_info.valid_data) { - if (!network_compatibility_or_fatal("LWW_GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (static_cast(sample.id) != graph->get_agent_id()) { - if (sample.id != -1) { - tp.spawn_task([this, s = std::move(sample)]() mutable { - engine_->import_full_graph(FullGraphMessage{std::move(s)}); - }); - sync = true; - break; - } - else if (!sync && sample.to_id == agent_id) - { - repeated = true; - } - } - } - continue; - } - DSR::OrMap sample; - if (reader->take_next_sample(&sample, &m_info) == 0) { - if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (m_info.valid_data) { - if (!network_compatibility_or_fatal("GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (static_cast(sample.id) != graph->get_agent_id()) { - if (sample.id != -1) { - qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value - << " whith " - << sample.m.size() << " elements"; - tp.spawn_task([this, s = std::move(sample)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); - engine_->import_full_graph(FullGraphMessage{std::move(s)}); - }); - qDebug() << "Synchronized."; - sync = true; - break; - } - else if (!sync && sample.to_id == agent_id) - { - repeated = true; - } - } - } - } else { - break; - } - } - }; - - dsrpub_request_answer_call = NewMessageFunctor(this, lambda_request_answer); + dsrpub_request_answer_call = (this->*transport_profile().make_fullgraph_request_functor)(sync, repeated); auto [res, sub, reader] = dsrsub_request_answer.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id(), dsrpub_request_answer_call, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), {sub, reader}); @@ -1962,18 +1785,7 @@ DSRGraph::DSRGraph(const DSRGraph &G) edgeType = G.edgeType; nodeType = G.nodeType; to_edges = G.to_edges; - if (sync_mode == SyncMode::CRDT) { - engine_ = std::make_unique(*this, G.crdt_engine()); - } else { - for (auto& [id, node] : G.engine_->snapshot()) { - engine_->insert_node_local(Node(node)); - } - for (auto& [id, node] : G.engine_->snapshot()) { - for (const auto& [key, edge] : node.fano()) { - engine_->insert_or_assign_edge_local(Edge(edge)); - } - } - } + engine_ = G.engine_->clone(*this); } std::unique_ptr DSRGraph::G_copy() diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index c4cf0e78..e4f76b91 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -49,6 +49,11 @@ SyncBackendInfo CRDTSyncEngine::backend_info() const return {}; } +std::unique_ptr CRDTSyncEngine::clone(SyncEngineHost& host) const +{ + return std::make_unique(static_cast(host), *this); +} + std::optional CRDTSyncEngine::get_node(uint64_t id) const { if (const auto* node = get_node_ptr(id); node != nullptr) { @@ -126,6 +131,7 @@ NodeMutationEffect CRDTSyncEngine::insert_node_local(Node&& node) effect.applied = applied; if (applied && delta.has_value()) { effect.id = delta->id; + effect.node_delta = NodeDeltaMessage{*delta}; if (const auto* inserted = get_node_ptr(delta->id); inserted != nullptr) { effect.type = inserted->type(); } @@ -139,6 +145,7 @@ NodeMutationEffect CRDTSyncEngine::update_node_local(Node&& node) auto [applied, deltas] = update_node_raw(user_node_to_crdt(std::move(node))); effect.applied = applied; if (applied && deltas.has_value()) { + effect.node_attr_batch = NodeAttrDeltaBatchMessage{*deltas}; effect.changed_attributes.reserve(deltas->vec.size()); for (const auto& item : deltas->vec) { effect.changed_attributes.emplace_back(item.attr_name); @@ -151,13 +158,20 @@ NodeMutationEffect CRDTSyncEngine::delete_node_local(uint64_t id) { NodeMutationEffect effect; if (auto node = get_crdt_node(id); node.has_value()) { - auto [applied, deleted_edges, _delta_node, _delta_edges] = delete_node_raw(id, *node); + auto [applied, deleted_edges, delta_node, delta_edges] = delete_node_raw(id, *node); effect.applied = applied; effect.id = id; effect.deleted_edges = std::move(deleted_edges); if (node.has_value()) { effect.deleted_node = Node(*node); } + if (delta_node.has_value()) { + effect.node_delta = NodeDeltaMessage{*delta_node}; + } + effect.edge_deltas.reserve(delta_edges.size()); + for (const auto& delta : delta_edges) { + effect.edge_deltas.emplace_back(EdgeDeltaMessage{delta}); + } } return effect; } @@ -173,7 +187,11 @@ EdgeMutationEffect CRDTSyncEngine::insert_or_assign_edge_local(Edge&& edge) effect.from = from; effect.to = to; effect.type = std::move(type); + if (_edge_delta.has_value()) { + effect.edge_delta = EdgeDeltaMessage{*_edge_delta}; + } if (attr_deltas.has_value()) { + effect.edge_attr_batch = EdgeAttrDeltaBatchMessage{*attr_deltas}; effect.changed_attributes.reserve(attr_deltas->vec.size()); for (const auto& item : attr_deltas->vec) { effect.changed_attributes.emplace_back(item.attr_name); @@ -186,7 +204,10 @@ EdgeMutationEffect CRDTSyncEngine::delete_edge_local(uint64_t from, uint64_t to, { EdgeMutationEffect effect; effect.deleted_edge = get_edge(from, to, type); - effect.applied = delete_edge_raw(from, to, type).has_value(); + if (auto delta = delete_edge_raw(from, to, type); delta.has_value()) { + effect.edge_delta = EdgeDeltaMessage{*delta}; + effect.applied = true; + } effect.from = from; effect.to = to; effect.type = type; diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index ac14d063..5761b8a7 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -24,11 +24,27 @@ LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, uint64_t tombstone_window_ms) { } +LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, const LWWSyncEngine& other) + : host_(host), + tombstone_window_ms_(other.tombstone_window_ms_), + logical_clock_ms_(other.logical_clock_ms_), + nodes_(other.nodes_), + edges_(other.edges_), + node_tombstones_(other.node_tombstones_), + edge_tombstones_(other.edge_tombstones_) +{ +} + SyncBackendInfo LWWSyncEngine::backend_info() const { return SyncBackendInfo{SyncMode::LWW, DSR_PROTOCOL_VERSION}; } +std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const +{ + return std::make_unique(host, *this); +} + bool LWWSyncEngine::is_newer(const Version& lhs, const Version& rhs) { return lhs.tie() > rhs.tie(); @@ -236,6 +252,7 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) node_tombstones_.erase(node.id()); host_.update_maps_node_insert(node); effect.applied = true; + effect.node_delta = NodeDeltaMessage{*export_node_delta(effect.id)}; return effect; } @@ -275,6 +292,7 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) host_.update_maps_node_delete(node.id(), old_node); host_.update_maps_node_insert(node); effect.applied = true; + effect.node_delta = NodeDeltaMessage{*export_node_delta(effect.id)}; return effect; } @@ -299,6 +317,15 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) store_node_tombstone(id, version, now); nodes_.erase(it); effect.applied = true; + if (auto delta = export_node_delta(id); delta.has_value()) { + effect.node_delta = NodeDeltaMessage{*delta}; + } + effect.edge_deltas.reserve(effect.deleted_edges.size()); + for (const auto& edge : effect.deleted_edges) { + if (auto delta = export_edge_delta(edge.from(), edge.to(), edge.type()); delta.has_value()) { + effect.edge_deltas.emplace_back(EdgeDeltaMessage{*delta}); + } + } return effect; } @@ -333,6 +360,7 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) edge_tombstones_.erase(key); host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); effect.applied = true; + effect.edge_delta = EdgeDeltaMessage{*export_edge_delta(effect.from, effect.to, effect.type)}; return effect; } @@ -358,6 +386,9 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, store_edge_tombstone(from, to, type, version, now); edges_.erase(it); effect.applied = true; + if (auto delta = export_edge_delta(from, to, type); delta.has_value()) { + effect.edge_delta = EdgeDeltaMessage{*delta}; + } return effect; } diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index a0beb287..bddeac13 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -668,6 +668,11 @@ namespace DSR std::optional join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg); std::optional join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg); void join_full_graph(DSR::OrMap &&full_graph); + void publish_node_message(const NodeDeltaMessage &message); + void publish_node_attr_batch(const NodeAttrDeltaBatchMessage &message); + void publish_edge_message(const EdgeDeltaMessage &message); + void publish_edge_attr_batch(const EdgeAttrDeltaBatchMessage &message); + void publish_full_graph_message(FullGraphMessage &&message, int32_t sender_id); // ThreadPools are declared after all data they access so that their // destructors (which join worker threads) run before the data members @@ -689,6 +694,26 @@ namespace DSR void operator()(eprosima::fastdds::dds::DataReader* reader) const { f(reader, graph); }; }; + struct TransportProfile { + NewMessageFunctor (DSRGraph::*make_node_functor)(); + NewMessageFunctor (DSRGraph::*make_edge_functor)(); + NewMessageFunctor (DSRGraph::*make_edge_attrs_functor)(); + NewMessageFunctor (DSRGraph::*make_node_attrs_functor)(); + NewMessageFunctor (DSRGraph::*make_fullgraph_request_functor)(std::atomic&, std::atomic&); + }; + + const TransportProfile& transport_profile() const; + NewMessageFunctor make_crdt_node_subscription_functor(); + NewMessageFunctor make_lww_node_subscription_functor(); + NewMessageFunctor make_crdt_edge_subscription_functor(); + NewMessageFunctor make_lww_edge_subscription_functor(); + NewMessageFunctor make_crdt_edge_attrs_subscription_functor(); + NewMessageFunctor make_lww_edge_attrs_subscription_functor(); + NewMessageFunctor make_crdt_node_attrs_subscription_functor(); + NewMessageFunctor make_lww_node_attrs_subscription_functor(); + NewMessageFunctor make_crdt_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + NewMessageFunctor make_lww_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + //Custom function for each rtps topic class ParticipantChangeFunctor { public: diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 59265065..8704205b 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -23,6 +23,7 @@ class CRDTSyncEngine final : public SyncEngine ~CRDTSyncEngine() override = default; SyncBackendInfo backend_info() const override; + std::unique_ptr clone(SyncEngineHost& host) const override; std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index cd25a0ca..f499621f 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -1,6 +1,7 @@ #pragma once #include "dsr/api/dsr_sync_engine.h" +#include "dsr/core/types/lww_types.h" #include #include @@ -14,26 +15,17 @@ namespace DSR { class LWWSyncEngine final : public SyncEngine { public: - struct Version - { - uint64_t timestamp{}; - uint32_t agent_id{}; - - auto tie() const { return std::tie(timestamp, agent_id); } - }; - - struct Tombstone - { - Version version; - uint64_t expires_at_ms{}; - }; + using Version = LWW::Version; + using Tombstone = LWW::Tombstone; explicit LWWSyncEngine( SyncEngineHost& host, uint64_t tombstone_window_ms = std::chrono::duration_cast(std::chrono::minutes(5)).count()); + LWWSyncEngine(SyncEngineHost& host, const LWWSyncEngine& other); ~LWWSyncEngine() override = default; SyncBackendInfo backend_info() const override; + std::unique_ptr clone(SyncEngineHost& host) const override; std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; @@ -63,33 +55,10 @@ class LWWSyncEngine final : public SyncEngine std::optional export_edge_delta(uint64_t from, uint64_t to, const std::string& type) const; private: - struct AttrState - { - Attribute value; - Version version; - }; - - struct NodeState - { - uint64_t id{}; - std::string type; - std::string name; - uint32_t agent_id{}; - Version version; - std::map attrs; - }; - - struct EdgeState - { - uint64_t from{}; - uint64_t to{}; - std::string type; - uint32_t agent_id{}; - Version version; - std::map attrs; - }; - - using EdgeKey = std::tuple; + using AttrState = LWW::AttrState; + using NodeState = LWW::NodeState; + using EdgeState = LWW::EdgeState; + using EdgeKey = LWW::EdgeKey; static bool is_newer(const Version& lhs, const Version& rhs); static Version version_of(uint64_t timestamp, uint32_t agent_id); diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h index ec83c6dd..c2ce36cf 100644 --- a/api/include/dsr/api/dsr_sync_engine.h +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -39,6 +39,9 @@ struct NodeMutationEffect std::vector> related_edge_keys; std::vector deleted_edges; std::optional deleted_node; + std::optional node_delta; + std::optional node_attr_batch; + std::vector edge_deltas; }; struct EdgeMutationEffect @@ -49,6 +52,8 @@ struct EdgeMutationEffect std::string type; std::vector changed_attributes; std::optional deleted_edge; + std::optional edge_delta; + std::optional edge_attr_batch; }; class SyncEngineHost @@ -76,6 +81,7 @@ class SyncEngine virtual ~SyncEngine() = default; virtual SyncBackendInfo backend_info() const = 0; + virtual std::unique_ptr clone(SyncEngineHost& host) const = 0; virtual std::optional get_node(uint64_t id) const = 0; virtual std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const = 0; diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index 1df9c60b..69924124 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -17,8 +17,9 @@ class DSRParticipant public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, bool lww_mode = false); + [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, uint8_t sync_mode_wire = 0); [[nodiscard]] int8_t get_domain_id() const { return domain_id_; } + [[nodiscard]] uint8_t get_sync_mode_wire() const { return sync_mode_wire_; } [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; [[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->get_name().data();} [[nodiscard]] const char *getRequestTopicName() const { return graphrequestType->get_name().data();} @@ -44,6 +45,7 @@ class DSRParticipant private: int8_t domain_id_ {0}; + uint8_t sync_mode_wire_ {0}; bool cleanup_enabled_ {true}; eprosima::fastdds::dds::DomainParticipant* mp_participant{}; diff --git a/core/include/dsr/core/types/lww_types.h b/core/include/dsr/core/types/lww_types.h new file mode 100644 index 00000000..2d0aa779 --- /dev/null +++ b/core/include/dsr/core/types/lww_types.h @@ -0,0 +1,55 @@ +#pragma once + +#include "dsr/core/types/user_types.h" +#include "dsr/core/utils.h" + +#include +#include +#include +#include + +namespace DSR::LWW { + +struct Version +{ + uint64_t timestamp{}; + uint32_t agent_id{}; + + auto tie() const { return std::tie(timestamp, agent_id); } +}; + +struct Tombstone +{ + Version version; + uint64_t expires_at_ms{}; +}; + +struct AttrState +{ + Attribute value; + Version version; +}; + +struct NodeState +{ + uint64_t id{}; + std::string type; + std::string name; + uint32_t agent_id{}; + Version version; + std::map attrs; +}; + +struct EdgeState +{ + uint64_t from{}; + uint64_t to{}; + std::string type; + uint32_t agent_id{}; + Version version; + std::map attrs; +}; + +using EdgeKey = std::tuple; + +} // namespace DSR::LWW diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index d631a74c..931b1e07 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -27,6 +27,11 @@ std::vector host_ipv4_interfaces() } return ips; } + +bool is_lww_mode(uint8_t sync_mode_wire) +{ + return sync_mode_wire == 1; +} } DSRParticipant::DSRParticipant() : mp_participant(nullptr), @@ -50,10 +55,11 @@ DSRParticipant::~DSRParticipant() } -std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, bool lww) +std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, uint8_t sync_mode_wire) { domain_id_ = domain_id; - cleanup_enabled_ = !lww; + sync_mode_wire_ = sync_mode_wire; + cleanup_enabled_ = !is_lww_mode(sync_mode_wire); // Create RTPSParticipant DomainParticipantQos PParam; PParam.name(("Participant_" + std::to_string(agent_id)+ " ( " + agent_name + " )").data() ); @@ -113,7 +119,7 @@ std::tuple DSRParticipant::ini } - if (lww) { + if (is_lww_mode(sync_mode_wire)) { dsrgraphType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeMsg")); graphrequestType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("GraphRequest")); graphRequestAnswerType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWGraphSnapshot")); @@ -132,12 +138,12 @@ std::tuple DSRParticipant::ini dsrEdgeAttrType.register_type(mp_participant); //Create topics - topic_node = mp_participant->create_topic(lww ? "LWW_NODE" : "DSR_NODE", dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge = mp_participant->create_topic(lww ? "LWW_EDGE" : "DSR_EDGE", dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_node_att = mp_participant->create_topic(lww ? "LWW_NODE_ATTS" : "DSR_NODE_ATTS", dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge_att = mp_participant->create_topic(lww ? "LWW_EDGE_ATTS" : "DSR_EDGE_ATTS", dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph_request = mp_participant->create_topic(lww ? "LWW_GRAPH_REQUEST" : "GRAPH_REQUEST", graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph = mp_participant->create_topic(lww ? "LWW_GRAPH_ANSWER" : "GRAPH_ANSWER", graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_NODE" : "DSR_NODE", dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_EDGE" : "DSR_EDGE", dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node_att = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_NODE_ATTS" : "DSR_NODE_ATTS", dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge_att = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_EDGE_ATTS" : "DSR_EDGE_ATTS", dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph_request = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_GRAPH_REQUEST" : "GRAPH_REQUEST", graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_GRAPH_ANSWER" : "GRAPH_ANSWER", graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); return std::make_tuple(true, mp_participant); } @@ -149,6 +155,9 @@ eprosima::fastdds::dds::DomainParticipant *DSRParticipant::getParticipant() void DSRParticipant::remove_participant_and_entities() { + if (!cleanup_enabled_) { + return; + } if (mp_participant != nullptr) { From bb9b008edec74cd0094e82e38ba59f86e3a4890e Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 15:00:37 +0200 Subject: [PATCH 13/38] refactor: move shared lww state types into core --- api/dsr_lww_sync_engine.cpp | 18 +++--------------- api/include/dsr/api/dsr_lww_sync_engine.h | 4 ---- core/include/dsr/core/types/lww_types.h | 15 +++++++++++++++ 3 files changed, 18 insertions(+), 19 deletions(-) diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 5761b8a7..df251dce 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -3,6 +3,9 @@ #include using namespace DSR; +using DSR::LWW::edge_key; +using DSR::LWW::is_newer; +using DSR::LWW::version_of; namespace { template @@ -45,21 +48,6 @@ std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const return std::make_unique(host, *this); } -bool LWWSyncEngine::is_newer(const Version& lhs, const Version& rhs) -{ - return lhs.tie() > rhs.tie(); -} - -LWWSyncEngine::Version LWWSyncEngine::version_of(uint64_t timestamp, uint32_t agent_id) -{ - return Version{timestamp, agent_id}; -} - -LWWSyncEngine::EdgeKey LWWSyncEngine::edge_key(uint64_t from, uint64_t to, const std::string& type) -{ - return EdgeKey{from, to, type}; -} - uint64_t LWWSyncEngine::current_time_ms() const { return static_cast( diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index f499621f..630163f7 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -60,10 +60,6 @@ class LWWSyncEngine final : public SyncEngine using EdgeState = LWW::EdgeState; using EdgeKey = LWW::EdgeKey; - static bool is_newer(const Version& lhs, const Version& rhs); - static Version version_of(uint64_t timestamp, uint32_t agent_id); - static EdgeKey edge_key(uint64_t from, uint64_t to, const std::string& type); - uint64_t current_time_ms() const; uint64_t next_timestamp(); void prune_tombstones(uint64_t now); diff --git a/core/include/dsr/core/types/lww_types.h b/core/include/dsr/core/types/lww_types.h index 2d0aa779..20f207d4 100644 --- a/core/include/dsr/core/types/lww_types.h +++ b/core/include/dsr/core/types/lww_types.h @@ -52,4 +52,19 @@ struct EdgeState using EdgeKey = std::tuple; +inline bool is_newer(const Version& lhs, const Version& rhs) +{ + return lhs.tie() > rhs.tie(); +} + +inline Version version_of(uint64_t timestamp, uint32_t agent_id) +{ + return Version{timestamp, agent_id}; +} + +inline EdgeKey edge_key(uint64_t from, uint64_t to, const std::string& type) +{ + return EdgeKey{from, to, type}; +} + } // namespace DSR::LWW From 69ac1cd8ded09c488472e02018f82ef5b8233a94 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 17:18:47 +0200 Subject: [PATCH 14/38] refactor: align sync backends around core io helpers --- api/dsr_api.cpp | 24 +-- api/dsr_crdt_sync_engine.cpp | 173 +++++++++-------- api/dsr_lww_sync_engine.cpp | 206 ++++----------------- api/dsr_rt_api.cpp | 6 +- api/include/dsr/api/dsr_api.h | 2 +- api/include/dsr/api/dsr_crdt_sync_engine.h | 14 +- api/include/dsr/api/dsr_lww_sync_engine.h | 6 - core/CMakeLists.txt | 1 + core/include/dsr/core/rtps/dsrpublisher.h | 22 +-- core/include/dsr/core/types/crdt_io.h | 151 +++++++++++++++ core/include/dsr/core/types/lww_io.h | 157 ++++++++++++++++ core/include/dsr/core/types/lww_merge.h | 24 +++ core/include/dsr/core/types/translator.h | 173 +++-------------- core/rtps/dsrpublisher.cpp | 147 ++++++--------- 14 files changed, 567 insertions(+), 539 deletions(-) create mode 100644 core/include/dsr/core/types/crdt_io.h create mode 100644 core/include/dsr/core/types/lww_io.h create mode 100644 core/include/dsr/core/types/lww_merge.h diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index df7865a0..87c3cc0a 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -290,42 +290,36 @@ const LWWSyncEngine& DSRGraph::lww_engine() const void DSRGraph::publish_node_message(const NodeDeltaMessage& message) { std::visit([this](const auto& payload) { - auto copy = payload; - dsrpub_node.write(©); + dsrpub_node.write(payload); }, message); } void DSRGraph::publish_node_attr_batch(const NodeAttrDeltaBatchMessage& message) { std::visit([this](const auto& payload) { - auto copy = payload; - dsrpub_node_attrs.write(©); + dsrpub_node_attrs.write(payload); }, message); } void DSRGraph::publish_edge_message(const EdgeDeltaMessage& message) { std::visit([this](const auto& payload) { - auto copy = payload; - dsrpub_edge.write(©); + dsrpub_edge.write(payload); }, message); } void DSRGraph::publish_edge_attr_batch(const EdgeAttrDeltaBatchMessage& message) { std::visit([this](const auto& payload) { - auto copy = payload; - dsrpub_edge_attrs.write(©); + dsrpub_edge_attrs.write(payload); }, message); } void DSRGraph::publish_full_graph_message(FullGraphMessage&& message, int32_t sender_id) { std::visit([this, sender_id](auto&& payload) { - using T = std::decay_t; - T copy = std::forward(payload); - copy.id = sender_id; - dsrpub_request_answer.write(©); + payload.id = sender_id; + dsrpub_request_answer.write(payload); }, std::move(message)); } @@ -1678,7 +1672,7 @@ void DSRGraph::fullgraph_server_thread() empty.to_id = static_cast(sample.id); empty.protocol_version = DSR::DSR_PROTOCOL_VERSION; empty.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_request_answer.write(&empty); + dsrpub_request_answer.write(empty); }, std::move(repeated_graph)); continue; } else {} @@ -1734,7 +1728,7 @@ std::pair DSRGraph::fullgraph_request_thread() gr.sync_mode = sync_mode_wire_value(sync_mode); { CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread send request"); - dsrpub_graph_request.write(&gr); + dsrpub_graph_request.write(gr); } @@ -1748,7 +1742,7 @@ std::pair DSRGraph::fullgraph_request_thread() qInfo() << " Waiting for the graph ... seconds to timeout [" << std::ceil(std::chrono::duration_cast(end - begin).count() / 10) / 100.0 << "/" << TIMEOUT / 1000 * 3 << "] "; - dsrpub_graph_request.write(&gr); + dsrpub_graph_request.write(gr); } dsrparticipant.delete_publisher(dsrparticipant.getGraphRequestTopic()->get_name()); diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index e4f76b91..ae0080d1 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -3,7 +3,7 @@ #include "dsr/api/dsr_api.h" #include "dsr/api/dsr_logging.h" #include "dsr/core/profiling.h" -#include "dsr/core/types/translator.h" +#include "dsr/core/types/crdt_io.h" #include #include @@ -29,12 +29,12 @@ bool protocol_version_matches( } } -CRDTSyncEngine::CRDTSyncEngine(DSRGraph& host) +CRDTSyncEngine::CRDTSyncEngine(SyncEngineHost& host) : host_(host) { } -CRDTSyncEngine::CRDTSyncEngine(DSRGraph& host, const CRDTSyncEngine& other) +CRDTSyncEngine::CRDTSyncEngine(SyncEngineHost& host, const CRDTSyncEngine& other) : host_(host), nodes_(other.nodes_), unprocessed_delta_node_att_(other.unprocessed_delta_node_att_), @@ -51,7 +51,17 @@ SyncBackendInfo CRDTSyncEngine::backend_info() const std::unique_ptr CRDTSyncEngine::clone(SyncEngineHost& host) const { - return std::make_unique(static_cast(host), *this); + return std::make_unique(host, *this); +} + +DSRGraph& CRDTSyncEngine::graph() +{ + return static_cast(host_); +} + +const DSRGraph& CRDTSyncEngine::graph() const +{ + return static_cast(host_); } std::optional CRDTSyncEngine::get_node(uint64_t id) const @@ -86,10 +96,11 @@ bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { - if (auto it = host_.to_edges.find(to); it != host_.to_edges.end()) { + if (auto it = graph().to_edges.find(to); it != graph().to_edges.end()) { for (const auto& [from, type] : it->second) { if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { Edge out(std::move(*edge)); + //TODO: move here? visitor(from, type, out); } } @@ -100,7 +111,7 @@ bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vi void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { - if (auto it = host_.edgeType.find(type); it != host_.edgeType.end()) { + if (auto it = graph().edgeType.find(type); it != graph().edgeType.end()) { for (const auto& [from, to] : it->second) { if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { Edge out(std::move(*edge)); @@ -239,7 +250,7 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba const auto sample_agent_id = payload->vec.front().agent_id; std::vector changed_attributes; for (auto&& item : payload->vec) { - if (host_.ignored_attributes.contains(item.attr_name)) { + if (graph().ignored_attributes.contains(item.attr_name)) { continue; } if (auto changed = join_delta_node_attr(std::move(item)); changed.has_value()) { @@ -250,13 +261,13 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba if (!changed_attributes.empty()) { std::string type; { - std::shared_lock lock(host_._mutex); + std::shared_lock lock(graph()._mutex); if (const auto* node = get_node_ptr(id); node != nullptr) { type = node->type(); } } - host_.emitter.update_node_attr_signal(id, changed_attributes, SignalInfo{sample_agent_id}); - host_.emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); + graph().emitter.update_node_attr_signal(id, changed_attributes, SignalInfo{sample_agent_id}); + graph().emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); } } @@ -273,7 +284,7 @@ void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& ba const auto sample_agent_id = payload->vec.front().agent_id; std::vector changed_attributes; for (auto&& item : payload->vec) { - if (host_.ignored_attributes.contains(item.attr_name)) { + if (graph().ignored_attributes.contains(item.attr_name)) { continue; } if (auto changed = join_delta_edge_attr(std::move(item)); changed.has_value()) { @@ -282,8 +293,8 @@ void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& ba } if (!changed_attributes.empty()) { - host_.emitter.update_edge_attr_signal(from, to, type, changed_attributes, SignalInfo{sample_agent_id}); - host_.emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); + graph().emitter.update_edge_attr_signal(from, to, type, changed_attributes, SignalInfo{sample_agent_id}); + graph().emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); } } @@ -296,11 +307,11 @@ void CRDTSyncEngine::import_full_graph(FullGraphMessage&& full_graph) FullGraphMessage CRDTSyncEngine::export_full_graph() const { - std::shared_lock lock(host_._mutex); + std::shared_lock lock(graph()._mutex); OrMap map; - map.id = static_cast(host_.agent_id); + map.id = static_cast(graph().agent_id); map.protocol_version = DSR_PROTOCOL_VERSION; - map.sync_mode = sync_mode_wire_value(host_.sync_mode); + map.sync_mode = sync_mode_wire_value(graph().sync_mode); map.m = export_mvreg_map(); return map; } @@ -341,7 +352,7 @@ std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to std::tuple> CRDTSyncEngine::insert_node_raw(CRDTNode&& node) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_node_raw"); - if (!host_.deleted.contains(node.id())) + if (!graph().deleted.contains(node.id())) { if (auto it = nodes_.find(node.id()); it != nodes_.end() and not it->second.empty() and it->second.read_reg() == node) { @@ -349,9 +360,9 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR } uint64_t id = node.id(); - host_.update_maps_node_insert(id, node); + graph().update_maps_node_insert(id, node); auto delta = nodes_[id].write(std::move(node)); - return {true, CRDTNode_to_Msg(host_.agent_id, id, std::move(delta))}; + return {true, crdt_node_to_msg(graph().agent_id, id, std::move(delta))}; } return {false, {}}; } @@ -359,7 +370,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR std::tuple> CRDTSyncEngine::update_node_raw(CRDTNode&& node) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::update_node_raw"); - if (!host_.deleted.contains(node.id())) + if (!graph().deleted.contains(node.id())) { auto nit = nodes_.find(node.id()); if (nit != nodes_.end() && !nit->second.empty()) @@ -371,18 +382,18 @@ std::tuple> CRDTSyncEngine::update_node_ra if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(host_.agent_id, node.id(), node.id(), k, std::move(delta))); + crdt_node_attr_to_msg(graph().agent_id, node.id(), node.id(), k, std::move(delta))); } } auto it_a = iter.begin(); while (it_a != iter.end()) { const std::string& k = it_a->first; - if (host_.ignored_attributes.contains(k)) { + if (graph().ignored_attributes.contains(k)) { it_a = iter.erase(it_a); } else if (!node.attrs().contains(k)) { auto delta = it_a->second.reset(); atts_deltas.vec.emplace_back( - CRDTNodeAttr_to_Msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); + crdt_node_attr_to_msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); it_a = iter.erase(it_a); } else { ++it_a; @@ -408,13 +419,13 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) deleted_edges.emplace_back(v.second.read_reg()); } auto delta = nodes_[id].reset(); - MvregNodeMsg delta_remove = CRDTNode_to_Msg(host_.agent_id, id, std::move(delta)); + MvregNodeMsg delta_remove = crdt_node_to_msg(graph().agent_id, id, std::move(delta)); { - decltype(host_.to_edges)::mapped_type incoming; + decltype(graph().to_edges)::mapped_type incoming; { - std::shared_lock lck_cache(host_._mutex_cache_maps); - if (host_.to_edges.contains(id)) - incoming = host_.to_edges.at(id); + std::shared_lock lck_cache(graph()._mutex_cache_maps); + if (graph().to_edges.contains(id)) + incoming = graph().to_edges.at(id); } for (const auto& [from, type] : incoming) { @@ -422,13 +433,13 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) auto& visited_node = nodes_.at(from).read_reg(); deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); auto delta_fano = visited_node.fano().at({id, type}).reset(); - delta_vec.emplace_back(CRDTEdge_to_Msg(host_.agent_id, from, id, type, std::move(delta_fano))); + delta_vec.emplace_back(crdt_edge_to_msg(graph().agent_id, from, id, type, std::move(delta_fano))); visited_node.fano().erase({id, type}); - host_.update_maps_edge_delete(from, id, type); + graph().update_maps_edge_delete(from, id, type); } } - host_.update_maps_node_delete(id, node); + graph().update_maps_node_delete(id, node); return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; } @@ -440,8 +451,8 @@ std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint6 if (node.fano().contains({to, key})) { auto delta = node.fano().at({to, key}).reset(); node.fano().erase({to, key}); - host_.update_maps_edge_delete(from, to, key); - return CRDTEdge_to_Msg(host_.agent_id, from, to, key, std::move(delta)); + graph().update_maps_edge_delete(from, to, key); + return crdt_edge_to_msg(graph().agent_id, from, to, key, std::move(delta)); } } return {}; @@ -467,7 +478,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(host_.agent_id, from, from, to, attrs.type(), k, std::move(delta))); + crdt_edge_attr_to_msg(graph().agent_id, from, from, to, attrs.type(), k, std::move(delta))); } } auto it = iter_edge.begin(); @@ -477,7 +488,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 auto delta = it->second.reset(); it = iter_edge.erase(it); atts_deltas.vec.emplace_back( - CRDTEdgeAttr_to_Msg(host_.agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); + crdt_edge_attr_to_msg(graph().agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); } else { ++it; } @@ -487,8 +498,8 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 { std::string att_type = attrs.type(); auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); - host_.update_maps_edge_insert(from, to, att_type); - return {true, CRDTEdge_to_Msg(host_.agent_id, from, to, std::move(att_type), std::move(delta)), {}}; + graph().update_maps_edge_insert(from, to, att_type); + return {true, crdt_edge_to_msg(graph().agent_id, from, to, std::move(att_type), std::move(delta)), {}}; } } return {false, {}, {}}; @@ -509,10 +520,10 @@ bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::s edge_reg.join(std::move(delta)); if (edge_reg.empty() || d_empty) { fanout.erase({to, type}); - host_.update_maps_edge_delete(from, to, type); + graph().update_maps_edge_delete(from, to, type); signal = false; } else { - host_.update_maps_edge_insert(from, to, type); + graph().update_maps_edge_insert(from, to, type); signal = !prev.has_value() || prev.value() != edge_reg.read_reg(); } return signal; @@ -547,11 +558,11 @@ void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const s void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node"); - const auto log_level = host_.log_level; + const auto log_level = graph().log_level; std::optional maybe_deleted_node = {}; try { - if (!protocol_version_matches(host_.log_level, "DSR_NODE", mvreg.protocol_version)) { + if (!protocol_version_matches(graph().log_level, "DSR_NODE", mvreg.protocol_version)) { return; } bool signal = false, joined = false; @@ -639,22 +650,22 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node crdt merge"); - std::unique_lock lock(host_._mutex); - if (!host_.deleted.contains(id)) { + std::unique_lock lock(graph()._mutex); + if (!graph().deleted.contains(id)) { if (auto it = nodes_.find(id); it != nodes_.end() && !it->second.empty()) { maybe_deleted_node = it->second.read_reg(); } nodes_[id].join(std::move(crdt_delta)); if (nodes_.at(id).empty() || d_empty) { if (maybe_deleted_node.has_value()) { - cache_map_to_edges = host_.to_edges[id]; + cache_map_to_edges = graph().to_edges[id]; } - host_.update_maps_node_delete(id, maybe_deleted_node); + graph().update_maps_node_delete(id, maybe_deleted_node); delete_unprocessed_deltas(); } else { const auto& reg = nodes_.at(id).read_reg(); current_type = reg.type(); - host_.update_maps_node_insert(id, reg); + graph().update_maps_node_insert(id, reg); consume_unprocessed_deltas(); } signal = !d_empty; @@ -665,33 +676,33 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) if (joined) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node signal emit"); if (signal) { - host_.emitter.update_node_signal(id, current_type, SignalInfo{ mvreg.agent_id }); + graph().emitter.update_node_signal(id, current_type, SignalInfo{ mvreg.agent_id }); if (const auto* current = get_node_ptr(id); current != nullptr) { for (const auto &[k, v] : current->fano()) { - host_.emitter.update_edge_signal(id, k.first, k.second, SignalInfo{ mvreg.agent_id }); + graph().emitter.update_edge_signal(id, k.first, k.second, SignalInfo{ mvreg.agent_id }); } } for (const auto &[k, v]: map_new_to_edges) { - host_.emitter.update_edge_signal(k, id, v, SignalInfo{ mvreg.agent_id }); + graph().emitter.update_edge_signal(k, id, v, SignalInfo{ mvreg.agent_id }); } } else { - host_.emitter.del_node_signal(id, SignalInfo{ mvreg.agent_id }); + graph().emitter.del_node_signal(id, SignalInfo{ mvreg.agent_id }); if (maybe_deleted_node.has_value()) { Node tmp_node(*maybe_deleted_node); - host_.emitter.deleted_node_signal(tmp_node, SignalInfo{ mvreg.agent_id }); + graph().emitter.deleted_node_signal(tmp_node, SignalInfo{ mvreg.agent_id }); for (const auto &node: maybe_deleted_node->fano()) { - host_.emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), + graph().emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), node.second.read_reg().type(), SignalInfo{ mvreg.agent_id }); Edge tmp_edge(node.second.read_reg()); - host_.emitter.deleted_edge_signal(tmp_edge, SignalInfo{ mvreg.agent_id }); + graph().emitter.deleted_edge_signal(tmp_edge, SignalInfo{ mvreg.agent_id }); } } if (cache_map_to_edges.has_value()) { for (const auto &[from, type] : cache_map_to_edges.value()) { - host_.emitter.del_edge_signal(from, id, type, SignalInfo{ mvreg.agent_id }); + graph().emitter.del_edge_signal(from, id, type, SignalInfo{ mvreg.agent_id }); } } } @@ -702,9 +713,9 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge"); - const auto log_level = host_.log_level; + const auto log_level = graph().log_level; try { - if (!protocol_version_matches(host_.log_level, "DSR_EDGE", mvreg.protocol_version)) { + if (!protocol_version_matches(graph().log_level, "DSR_EDGE", mvreg.protocol_version)) { return; } bool signal = false, joined = false; @@ -744,10 +755,10 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge crdt merge"); - std::unique_lock lock(host_._mutex); + std::unique_lock lock(graph()._mutex); deleted_edge = get_edge(from, to, type); bool cfrom{nodes_.contains(from)}, cto{nodes_.contains(to)}; - bool dfrom{host_.deleted.contains(from)}, dto{host_.deleted.contains(to)}; + bool dfrom{graph().deleted.contains(from)}, dto{graph().deleted.contains(to)}; if (cfrom && cto) { signal = process_delta_edge(from, to, type, std::move(crdt_delta)); @@ -789,11 +800,11 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) if (joined) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge signal emit"); if (signal) { - host_.emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); + graph().emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); } else { - host_.emitter.del_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); + graph().emitter.del_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); if (deleted_edge.has_value()) { - host_.emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ mvreg.agent_id }); + graph().emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ mvreg.agent_id }); } } } @@ -804,7 +815,7 @@ std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node_attr"); try { - if (!protocol_version_matches(host_.log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { + if (!protocol_version_matches(graph().log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { return {}; } auto id = mvreg.node; @@ -814,13 +825,13 @@ std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg auto d_empty = crdt_delta.empty(); { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node_attr crdt merge"); - std::unique_lock lock(host_._mutex); + std::unique_lock lock(graph()._mutex); if (nodes_.contains(id)) { process_delta_node_attr(id, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_node_att_, [id = id, att_name = att_name](auto &it){ return it.first == id && std::get<0>(it.second) == att_name;}); return att_name; - } else if (!host_.deleted.contains(id)) { + } else if (!graph().deleted.contains(id)) { bool find = false; for (auto [begin, end] = unprocessed_delta_node_att_.equal_range(id); begin != end; ++begin) { if (std::get<0>(begin->second) == att_name){ @@ -848,7 +859,7 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge_attr"); try { - if (!protocol_version_matches(host_.log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { + if (!protocol_version_matches(graph().log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { return {}; } auto from = mvreg.from_node; @@ -860,14 +871,14 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg auto d_empty = crdt_delta.empty(); { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); - std::unique_lock lock(host_._mutex); + std::unique_lock lock(graph()._mutex); if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({to, type})) { process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_edge_att_, [from = from, to = to, type = type, att_name = att_name](auto &it){ return it.first == std::tuple{from, to, type} && std::get<0>(it.second) == att_name;}); return att_name; - } else if (!host_.deleted.contains(from) && !host_.deleted.contains(to)) { + } else if (!graph().deleted.contains(from) && !graph().deleted.contains(to)) { bool find = false; for (auto [begin, end] = unprocessed_delta_edge_att_.equal_range(std::tuple{from, to, type}); begin != end; ++begin) { if (std::get<0>(begin->second) == att_name){ @@ -894,8 +905,8 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_full_graph"); - const auto log_level = host_.log_level; - if (!protocol_version_matches(host_.log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { + const auto log_level = graph().log_level; + if (!protocol_version_matches(graph().log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { return; } @@ -975,7 +986,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; { - std::unique_lock lock(host_._mutex); + std::unique_lock lock(graph()._mutex); for (auto &[k, val] : full_graph.m) { auto mv = std::move(val.dk); @@ -985,18 +996,18 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) std::optional nd = (it != nodes_.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; id = k; - if (!host_.deleted.contains(k)) { + if (!graph().deleted.contains(k)) { if (it == nodes_.end()) { it = nodes_.emplace(k, mvreg{}).first; } it->second.join(std::move(mv)); if (mv_empty or it->second.empty()) { - host_.update_maps_node_delete(k, nd); + graph().update_maps_node_delete(k, nd); updates.emplace_back(false, k, "", std::nullopt, std::nullopt); delete_unprocessed_deltas(); } else { const auto& reg = it->second.read_reg(); - host_.update_maps_node_insert(k, reg); + graph().update_maps_node_insert(k, reg); updates.emplace_back(true, k, reg.type(), nd, reg); consume_unprocessed_deltas(); } @@ -1008,28 +1019,28 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) for (auto &[signal, node_id, type, nd, current_nd] : updates) { if (signal) { if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { - host_.emitter.update_node_signal(node_id, type, SignalInfo{ agent_id_ch }); + graph().emitter.update_node_signal(node_id, type, SignalInfo{ agent_id_ch }); } else if (nd.value() != *current_nd) { const auto& iter = current_nd->fano(); for (const auto &[k, v] : nd->fano()) { if (!iter.contains(k)) { - host_.emitter.del_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); + graph().emitter.del_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); if (v.dk.ds.size() > 0) { Edge tmp_edge(v.read_reg()); - host_.emitter.deleted_edge_signal(tmp_edge, SignalInfo{ host_.agent_id }); + graph().emitter.deleted_edge_signal(tmp_edge, SignalInfo{ graph().agent_id }); } } } for (const auto &[k, v] : iter) { if (auto it = nd->fano().find(k); it == nd->fano().end() or it->second != v) - host_.emitter.update_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); + graph().emitter.update_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); } } } else { - host_.emitter.del_node_signal(node_id, SignalInfo{ agent_id_ch }); + graph().emitter.del_node_signal(node_id, SignalInfo{ agent_id_ch }); if (nd.has_value()) { Node tmp_node(*nd); - host_.emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); + graph().emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); } } } @@ -1044,10 +1055,10 @@ std::map CRDTSyncEngine::export_mvreg_map() const MvregNodeMsg msg; msg.dk = kv.second; msg.id = kv.first; - msg.agent_id = host_.agent_id; + msg.agent_id = graph().agent_id; msg.timestamp = get_unix_timestamp(); msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(host_.sync_mode); + msg.sync_mode = sync_mode_wire_value(graph().sync_mode); m.emplace(kv.first, std::move(msg)); } return m; diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index df251dce..cd38e02c 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -1,4 +1,6 @@ #include "dsr/api/dsr_lww_sync_engine.h" +#include "dsr/core/types/lww_io.h" +#include "dsr/core/types/lww_merge.h" #include @@ -67,43 +69,14 @@ void LWWSyncEngine::prune_tombstones(uint64_t now) erase_if_compat(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); } -Node LWWSyncEngine::to_node(const NodeState& state) const -{ - Node out(state.agent_id, state.type); - out.id(state.id); - out.name(state.name); - auto& attrs = out.attrs(); - for (const auto& [name, attr] : state.attrs) { - attrs.emplace(name, attr.value); - } - auto& fano = out.fano(); - for (const auto& [key, edge] : edges_) { - if (edge.from != state.id) { - continue; - } - fano.emplace(std::pair{edge.to, edge.type}, to_edge(edge)); - } - return out; -} - -Edge LWWSyncEngine::to_edge(const EdgeState& state) const -{ - Edge out(state.to, state.from, state.type, {}, state.agent_id); - auto& attrs = out.attrs(); - for (const auto& [name, attr] : state.attrs) { - attrs.emplace(name, attr.value); - } - return out; -} - void LWWSyncEngine::store_node_tombstone(uint64_t id, Version version, uint64_t now) { - node_tombstones_[id] = Tombstone{version, now + tombstone_window_ms_}; + node_tombstones_[id] = LWW::make_tombstone(version, now, tombstone_window_ms_); } void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now) { - edge_tombstones_[edge_key(from, to, type)] = Tombstone{version, now + tombstone_window_ms_}; + edge_tombstones_[edge_key(from, to, type)] = LWW::make_tombstone(version, now, tombstone_window_ms_); } void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) @@ -113,7 +86,7 @@ void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint6 host_.update_maps_edge_delete(it->second.from, it->second.to, it->second.type); store_edge_tombstone(it->second.from, it->second.to, it->second.type, version, now); if (removed_edges != nullptr) { - removed_edges->emplace_back(to_edge(it->second)); + removed_edges->emplace_back(LWW::to_user_edge(it->second)); } it = edges_.erase(it); } else { @@ -122,32 +95,10 @@ void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint6 } } -bool LWWSyncEngine::node_delta_is_stale(uint64_t id, const Version& version) const -{ - if (auto it = node_tombstones_.find(id); it != node_tombstones_.end() && !is_newer(version, it->second.version)) { - return true; - } - if (auto it = nodes_.find(id); it != nodes_.end() && !is_newer(version, it->second.version)) { - return true; - } - return false; -} - -bool LWWSyncEngine::edge_delta_is_stale(uint64_t from, uint64_t to, const std::string& type, const Version& version) const -{ - if (auto it = edge_tombstones_.find(edge_key(from, to, type)); it != edge_tombstones_.end() && !is_newer(version, it->second.version)) { - return true; - } - if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end() && !is_newer(version, it->second.version)) { - return true; - } - return false; -} - std::optional LWWSyncEngine::get_node(uint64_t id) const { if (auto it = nodes_.find(id); it != nodes_.end()) { - return to_node(it->second); + return LWW::to_user_node(it->second, edges_); } return {}; } @@ -155,7 +106,7 @@ std::optional LWWSyncEngine::get_node(uint64_t id) const std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end()) { - return to_edge(it->second); + return LWW::to_user_edge(it->second); } return {}; } @@ -167,7 +118,7 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& } for (const auto& [key, edge] : edges_) { if (edge.from == from) { - Edge out = to_edge(edge); + Edge out = LWW::to_user_edge(edge); visitor(edge.to, edge.type, out); } } @@ -179,7 +130,7 @@ bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vis bool found = false; for (const auto& [key, edge] : edges_) { if (edge.to == to) { - Edge out = to_edge(edge); + Edge out = LWW::to_user_edge(edge); visitor(edge.from, edge.type, out); found = true; } @@ -191,7 +142,7 @@ void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEd { for (const auto& [key, edge] : edges_) { if (edge.type == type) { - Edge out = to_edge(edge); + Edge out = LWW::to_user_edge(edge); visitor(edge.from, edge.to, out); } } @@ -206,7 +157,7 @@ std::map LWWSyncEngine::snapshot() const { std::map out; for (const auto& [id, node] : nodes_) { - out.emplace(id, to_node(node)); + out.emplace(id, LWW::to_user_node(node, edges_)); } return out; } @@ -221,18 +172,12 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) effect.type = node.type(); auto version = version_of(now, host_.local_agent_id()); - if (node_delta_is_stale(node.id(), version)) { + if (LWW::delta_is_stale(node_tombstones_, nodes_, node.id(), version)) { return effect; } - NodeState state; - state.id = node.id(); - state.type = node.type(); - state.name = node.name(); - state.agent_id = host_.local_agent_id(); - state.version = version; - for (const auto& [name, attr] : node.attrs()) { - state.attrs.emplace(name, AttrState{attr, version}); + NodeState state = LWW::to_node_state(node, version, host_.local_agent_id()); + for (const auto& [name, _] : node.attrs()) { effect.changed_attributes.emplace_back(name); } @@ -258,16 +203,15 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) return effect; } - auto old_node = to_node(it->second); + auto old_node = LWW::to_user_node(it->second, edges_); auto version = version_of(now, host_.local_agent_id()); it->second.type = node.type(); it->second.name = node.name(); it->second.version = version; it->second.agent_id = host_.local_agent_id(); - std::map next_attrs; - for (const auto& [name, attr] : node.attrs()) { - next_attrs.emplace(name, AttrState{attr, version}); + std::map next_attrs = LWW::to_attr_state_map(node.attrs(), version); + for (const auto& [name, _] : node.attrs()) { effect.changed_attributes.emplace_back(name); } for (const auto& [name, _] : it->second.attrs) { @@ -297,7 +241,7 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) } auto version = version_of(now, host_.local_agent_id()); - auto deleted_node = to_node(it->second); + auto deleted_node = LWW::to_user_node(it->second, edges_); effect.deleted_node = deleted_node; effect.deleted_edges.clear(); erase_related_edges(id, version, now, &effect.deleted_edges); @@ -329,20 +273,14 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) auto version = version_of(now, host_.local_agent_id()); if (!nodes_.contains(edge.from()) || !nodes_.contains(edge.to()) || - edge_delta_is_stale(edge.from(), edge.to(), edge.type(), version)) { + LWW::delta_is_stale(edge_tombstones_, edges_, edge_key(edge.from(), edge.to(), edge.type()), version)) { return effect; } auto key = edge_key(edge.from(), edge.to(), edge.type()); auto& state = edges_[key]; - state.from = edge.from(); - state.to = edge.to(); - state.type = edge.type(); - state.version = version; - state.agent_id = host_.local_agent_id(); - state.attrs.clear(); - for (const auto& [name, attr] : edge.attrs()) { - state.attrs.emplace(name, AttrState{attr, version}); + state = LWW::to_edge_state(edge, version, host_.local_agent_id()); + for (const auto& [name, _] : edge.attrs()) { effect.changed_attributes.emplace_back(name); } edge_tombstones_.erase(key); @@ -369,7 +307,7 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, } auto version = version_of(now, host_.local_agent_id()); - effect.deleted_edge = to_edge(it->second); + effect.deleted_edge = LWW::to_user_edge(it->second); host_.update_maps_edge_delete(from, to, type); store_edge_tombstone(from, to, type, version, now); edges_.erase(it); @@ -392,13 +330,13 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) prune_tombstones(now); auto version = version_of(payload->timestamp, payload->agent_id); - if (node_delta_is_stale(payload->id, version)) { + if (LWW::delta_is_stale(node_tombstones_, nodes_, payload->id, version)) { return; } if (payload->deleted) { if (auto it = nodes_.find(payload->id); it != nodes_.end()) { - auto deleted_node = to_node(it->second); + auto deleted_node = LWW::to_user_node(it->second, edges_); erase_related_edges(payload->id, version, now); host_.update_maps_node_delete(payload->id, deleted_node); nodes_.erase(it); @@ -407,15 +345,7 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) return; } - NodeState state; - state.id = payload->id; - state.type = payload->type; - state.name = payload->name; - state.agent_id = payload->agent_id; - state.version = version; - for (const auto& [name, attr] : payload->attrs) { - state.attrs.emplace(name, AttrState{attr, version}); - } + NodeState state = LWW::to_node_state(*payload); auto maybe_old = get_node(payload->id); if (maybe_old.has_value()) { @@ -438,7 +368,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) prune_tombstones(now); auto version = version_of(payload->timestamp, payload->agent_id); - if (edge_delta_is_stale(payload->from, payload->to, payload->type, version)) { + if (LWW::delta_is_stale(edge_tombstones_, edges_, edge_key(payload->from, payload->to, payload->type), version)) { return; } if (!nodes_.contains(payload->from) || !nodes_.contains(payload->to)) { @@ -455,15 +385,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) return; } - EdgeState state; - state.from = payload->from; - state.to = payload->to; - state.type = payload->type; - state.agent_id = payload->agent_id; - state.version = version; - for (const auto& [name, attr] : payload->attrs) { - state.attrs.emplace(name, AttrState{attr, version}); - } + EdgeState state = LWW::to_edge_state(*payload); edges_[key] = std::move(state); edge_tombstones_.erase(key); @@ -545,33 +467,11 @@ FullGraphMessage LWWSyncEngine::export_full_graph() const snapshot.tombstone_window_ms = tombstone_window_ms_; for (const auto& [id, node] : nodes_) { - LWWNodeMsg item; - item.id = id; - item.type = node.type; - item.name = node.name; - item.agent_id = node.agent_id; - item.timestamp = node.version.timestamp; - item.protocol_version = DSR_PROTOCOL_VERSION; - item.sync_mode = sync_mode_wire_value(SyncMode::LWW); - for (const auto& [name, attr] : node.attrs) { - item.attrs.emplace(name, attr.value); - } - snapshot.nodes.emplace_back(std::move(item)); + snapshot.nodes.emplace_back(LWW::to_node_msg(node)); } for (const auto& [key, edge] : edges_) { - LWWEdgeMsg item; - item.from = edge.from; - item.to = edge.to; - item.type = edge.type; - item.agent_id = edge.agent_id; - item.timestamp = edge.version.timestamp; - item.protocol_version = DSR_PROTOCOL_VERSION; - item.sync_mode = sync_mode_wire_value(SyncMode::LWW); - for (const auto& [name, attr] : edge.attrs) { - item.attrs.emplace(name, attr.value); - } - snapshot.edges.emplace_back(std::move(item)); + snapshot.edges.emplace_back(LWW::to_edge_msg(edge)); } return snapshot; @@ -596,29 +496,10 @@ std::optional LWWSyncEngine::edge_tombstone(uint64_t f std::optional LWWSyncEngine::export_node_delta(uint64_t id) const { if (auto it = nodes_.find(id); it != nodes_.end()) { - LWWNodeMsg msg; - msg.id = it->second.id; - msg.type = it->second.type; - msg.name = it->second.name; - msg.agent_id = it->second.agent_id; - msg.timestamp = it->second.version.timestamp; - msg.deleted = false; - msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); - for (const auto& [name, attr] : it->second.attrs) { - msg.attrs.emplace(name, attr.value); - } - return msg; + return LWW::to_node_msg(it->second); } if (auto it = node_tombstones_.find(id); it != node_tombstones_.end()) { - LWWNodeMsg msg; - msg.id = id; - msg.agent_id = it->second.version.agent_id; - msg.timestamp = it->second.version.timestamp; - msg.deleted = true; - msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); - return msg; + return LWW::to_node_tombstone_msg(id, it->second); } return {}; } @@ -627,31 +508,10 @@ std::optional LWWSyncEngine::export_edge_delta(uint64_t from, uint64 { auto key = edge_key(from, to, type); if (auto it = edges_.find(key); it != edges_.end()) { - LWWEdgeMsg msg; - msg.from = it->second.from; - msg.to = it->second.to; - msg.type = it->second.type; - msg.agent_id = it->second.agent_id; - msg.timestamp = it->second.version.timestamp; - msg.deleted = false; - msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); - for (const auto& [name, attr] : it->second.attrs) { - msg.attrs.emplace(name, attr.value); - } - return msg; + return LWW::to_edge_msg(it->second); } if (auto it = edge_tombstones_.find(key); it != edge_tombstones_.end()) { - LWWEdgeMsg msg; - msg.from = from; - msg.to = to; - msg.type = type; - msg.agent_id = it->second.version.agent_id; - msg.timestamp = it->second.version.timestamp; - msg.deleted = true; - msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); - return msg; + return LWW::to_edge_tombstone_msg(from, to, type, it->second); } return {}; } diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index b4f43c8b..fbfa7a07 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -608,11 +608,11 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectordsrpub_edge.write(&node1_insert.value()); + G->dsrpub_edge.write(node1_insert.value()); } - if (node1_update.has_value()) G->dsrpub_edge_attrs.write(&node1_update.value()); + if (node1_update.has_value()) G->dsrpub_edge_attrs.write(node1_update.value()); - if (!no_send and node2.has_value()) G->dsrpub_node_attrs.write(&node2.value()); + if (!no_send and node2.has_value()) G->dsrpub_node_attrs.write(node2.value()); G->emitter.update_edge_attr_signal(n.id(), to, "RT", updated_attributes, SignalInfo{ G->agent_id }); G->emitter.update_edge_signal(n.id(), to, "RT", SignalInfo{ G->agent_id }); diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index bddeac13..501f4d58 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -485,7 +485,7 @@ namespace DSR signal.agent_id = agent_id; signal.protocol_version = DSR::DSR_PROTOCOL_VERSION; signal.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_node.write(&signal); + dsrpub_node.write(signal); } } diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 8704205b..780c97be 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -11,15 +11,14 @@ namespace DSR { -class DSRGraph; - class CRDTSyncEngine final : public SyncEngine { public: using Nodes = std::unordered_map>; + friend class DSRGraph; - explicit CRDTSyncEngine(DSRGraph& host); - CRDTSyncEngine(DSRGraph& host, const CRDTSyncEngine& other); + explicit CRDTSyncEngine(SyncEngineHost& host); + CRDTSyncEngine(SyncEngineHost& host, const CRDTSyncEngine& other); ~CRDTSyncEngine() override = default; SyncBackendInfo backend_info() const override; @@ -47,6 +46,7 @@ class CRDTSyncEngine final : public SyncEngine void import_full_graph(FullGraphMessage&& full_graph) override; FullGraphMessage export_full_graph() const override; +private: const CRDTNode* get_node_ptr(uint64_t id) const; std::optional get_crdt_node(uint64_t id) const; std::optional get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const; @@ -67,12 +67,14 @@ class CRDTSyncEngine final : public SyncEngine std::map export_mvreg_map() const; -private: + class DSRGraph& graph(); + const class DSRGraph& graph() const; + bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta); void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr); void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr); - DSRGraph& host_; + SyncEngineHost& host_; Nodes nodes_; std::unordered_multimap, uint64_t>> unprocessed_delta_node_att_; std::unordered_multimap, uint64_t>> unprocessed_delta_edge_from_; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index 630163f7..902ba461 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -64,16 +64,10 @@ class LWWSyncEngine final : public SyncEngine uint64_t next_timestamp(); void prune_tombstones(uint64_t now); - Node to_node(const NodeState& state) const; - Edge to_edge(const EdgeState& state) const; - void store_node_tombstone(uint64_t id, Version version, uint64_t now); void store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now); void erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges = nullptr); - bool node_delta_is_stale(uint64_t id, const Version& version) const; - bool edge_delta_is_stale(uint64_t from, uint64_t to, const std::string& type, const Version& version) const; - SyncEngineHost& host_; uint64_t tombstone_window_ms_; uint64_t logical_clock_ms_{0}; diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 8a3ae00a..d3d1ef86 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -19,6 +19,7 @@ target_sources(dsr_core include/dsr/core/types/crdt_types.h include/dsr/core/types/user_types.h include/dsr/core/types/common_types.h + include/dsr/core/types/crdt_io.h include/dsr/core/types/translator.h include/dsr/core/types/type_checking/dsr_attr_name.h include/dsr/core/types/type_checking/dsr_edge_type.h diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index 66cd3012..10ad57cc 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -22,17 +22,17 @@ class DSRPublisher int8_t domain_id, bool isStreamData = false); [[nodiscard]] eprosima::fastdds::rtps::GUID_t getParticipantID() const; - bool write(DSR::GraphRequest *object); - bool write(DSR::MvregNodeMsg *object); - bool write(DSR::OrMap *object); - bool write(DSR::MvregEdgeMsg *object); - bool write(DSR::MvregEdgeAttrVec *object); - bool write(DSR::MvregNodeAttrVec *object); - bool write(DSR::LWWNodeMsg *object); - bool write(DSR::LWWEdgeMsg *object); - bool write(DSR::LWWNodeAttrVec *object); - bool write(DSR::LWWEdgeAttrVec *object); - bool write(DSR::LWWGraphSnapshot *object); + bool write(const DSR::GraphRequest &object); + bool write(const DSR::MvregNodeMsg &object); + bool write(const DSR::OrMap &object); + bool write(const DSR::MvregEdgeMsg &object); + bool write(const DSR::MvregEdgeAttrVec &object); + bool write(const DSR::MvregNodeAttrVec &object); + bool write(const DSR::LWWNodeMsg &object); + bool write(const DSR::LWWEdgeMsg &object); + bool write(const DSR::LWWNodeAttrVec &object); + bool write(const DSR::LWWEdgeAttrVec &object); + bool write(const DSR::LWWGraphSnapshot &object); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; diff --git a/core/include/dsr/core/types/crdt_io.h b/core/include/dsr/core/types/crdt_io.h new file mode 100644 index 00000000..db48e2b2 --- /dev/null +++ b/core/include/dsr/core/types/crdt_io.h @@ -0,0 +1,151 @@ +// +// CRDT conversion helpers kept separate from backend engines. +// + +#pragma once + +#include "dsr/core/types/user_types.h" +#include "dsr/core/types/crdt_types.h" +#include "dsr/core/types/internal_types.h" + +namespace DSR { + +inline MvregNodeMsg crdt_node_to_msg(uint32_t agent_id, uint64_t id, mvreg&& data) +{ + MvregNodeMsg msg; + msg.dk = std::move(data); + msg.id = id; + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR_PROTOCOL_VERSION; + return msg; +} + +template +inline MvregEdgeMsg crdt_edge_to_msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) +{ + MvregEdgeMsg msg; + msg.dk = std::move(data); + msg.id = from; + msg.to = to; + msg.from = from; + msg.type = std::forward(type); + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR_PROTOCOL_VERSION; + return msg; +} + +template +inline MvregNodeAttrMsg crdt_node_attr_to_msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) +{ + MvregNodeAttrMsg msg; + msg.dk = std::move(data); + msg.id = id; + msg.node = node; + msg.attr_name = std::forward(attr); + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR_PROTOCOL_VERSION; + return msg; +} + +template +inline MvregEdgeAttrMsg crdt_edge_attr_to_msg(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, + TS&& type, AS&& attr, mvreg&& data) +{ + MvregEdgeAttrMsg msg; + msg.dk = std::move(data); + msg.id = id; + msg.from_node = from; + msg.to_node = to; + msg.type = std::forward(type); + msg.attr_name = std::forward(attr); + msg.agent_id = agent_id; + msg.timestamp = get_unix_timestamp(); + msg.protocol_version = DSR_PROTOCOL_VERSION; + return msg; +} + +inline CRDTEdge user_edge_to_crdt(Edge&& edge) +{ + CRDTEdge crdt_edge; + + crdt_edge.agent_id(edge.agent_id()); + crdt_edge.from(edge.from()); + crdt_edge.to(edge.to()); + crdt_edge.type(std::move(edge.type())); + for (auto&& [k, v] : edge.attrs()) { + mvreg mv; + mv.write(std::move(v)); + crdt_edge.attrs().emplace(k, std::move(mv)); + } + + return crdt_edge; +} + +inline CRDTEdge user_edge_to_crdt(const Edge& edge) +{ + CRDTEdge crdt_edge; + + crdt_edge.agent_id(edge.agent_id()); + crdt_edge.from(edge.from()); + crdt_edge.to(edge.to()); + crdt_edge.type(edge.type()); + for (auto& [k, v] : edge.attrs()) { + mvreg mv; + mv.write(v); + crdt_edge.attrs().emplace(k, std::move(mv)); + } + + return crdt_edge; +} + +inline CRDTNode user_node_to_crdt(Node&& node) +{ + CRDTNode crdt_node; + + crdt_node.agent_id(node.agent_id()); + crdt_node.id(node.id()); + crdt_node.type(std::move(node.type())); + crdt_node.name(std::move(node.name())); + + for (auto&& [k, val] : node.attrs()) { + mvreg mv; + mv.write(std::move(val)); + crdt_node.attrs().emplace(k, std::move(mv)); + } + + for (auto& [k, v] : node.fano()) { + mvreg mv; + mv.write(user_edge_to_crdt(std::move(v))); + crdt_node.fano().emplace(k, std::move(mv)); + } + + return crdt_node; +} + +inline CRDTNode user_node_to_crdt(const Node& node) +{ + CRDTNode crdt_node; + + crdt_node.agent_id(node.agent_id()); + crdt_node.id(node.id()); + crdt_node.type(node.type()); + crdt_node.name(node.name()); + for (auto& [k, v] : node.attrs()) { + mvreg mv; + mv.write(v); + crdt_node.attrs().emplace(k, std::move(mv)); + } + + for (auto& [k, v] : node.fano()) { + mvreg mv; + mv.write(user_edge_to_crdt(v)); + crdt_node.fano().emplace(k, std::move(mv)); + } + + return crdt_node; +} + +} // namespace DSR diff --git a/core/include/dsr/core/types/lww_io.h b/core/include/dsr/core/types/lww_io.h new file mode 100644 index 00000000..9d3005bd --- /dev/null +++ b/core/include/dsr/core/types/lww_io.h @@ -0,0 +1,157 @@ +#pragma once + +#include "dsr/core/types/internal_types.h" +#include "dsr/core/types/lww_types.h" + +namespace DSR::LWW { + +inline std::map to_attr_state_map(const std::map& attrs, const Version& version) +{ + std::map out; + for (const auto& [name, attr] : attrs) { + out.emplace(name, AttrState{attr, version}); + } + return out; +} + +inline NodeState to_node_state(const Node& node, const Version& version, uint32_t agent_id) +{ + NodeState state; + state.id = node.id(); + state.type = node.type(); + state.name = node.name(); + state.agent_id = agent_id; + state.version = version; + state.attrs = to_attr_state_map(node.attrs(), version); + return state; +} + +inline EdgeState to_edge_state(const Edge& edge, const Version& version, uint32_t agent_id) +{ + EdgeState state; + state.from = edge.from(); + state.to = edge.to(); + state.type = edge.type(); + state.agent_id = agent_id; + state.version = version; + state.attrs = to_attr_state_map(edge.attrs(), version); + return state; +} + +inline NodeState to_node_state(const LWWNodeMsg& msg) +{ + const auto version = version_of(msg.timestamp, msg.agent_id); + NodeState state; + state.id = msg.id; + state.type = msg.type; + state.name = msg.name; + state.agent_id = msg.agent_id; + state.version = version; + state.attrs = to_attr_state_map(msg.attrs, version); + return state; +} + +inline EdgeState to_edge_state(const LWWEdgeMsg& msg) +{ + const auto version = version_of(msg.timestamp, msg.agent_id); + EdgeState state; + state.from = msg.from; + state.to = msg.to; + state.type = msg.type; + state.agent_id = msg.agent_id; + state.version = version; + state.attrs = to_attr_state_map(msg.attrs, version); + return state; +} + +inline Edge to_user_edge(const EdgeState& state) +{ + Edge out(state.to, state.from, state.type, {}, state.agent_id); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : state.attrs) { + attrs.emplace(name, attr.value); + } + return out; +} + +template +Node to_user_node(const NodeState& state, const EdgeMap& edges) +{ + Node out(state.agent_id, state.type); + out.id(state.id); + out.name(state.name); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : state.attrs) { + attrs.emplace(name, attr.value); + } + auto& fano = out.fano(); + for (const auto& [key, edge] : edges) { + if (edge.from != state.id) { + continue; + } + fano.emplace(std::pair{edge.to, edge.type}, to_user_edge(edge)); + } + return out; +} + +inline LWWNodeMsg to_node_msg(const NodeState& state) +{ + LWWNodeMsg msg; + msg.id = state.id; + msg.type = state.type; + msg.name = state.name; + msg.agent_id = state.agent_id; + msg.timestamp = state.version.timestamp; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : state.attrs) { + msg.attrs.emplace(name, attr.value); + } + return msg; +} + +inline LWWNodeMsg to_node_tombstone_msg(uint64_t id, const Tombstone& tombstone) +{ + LWWNodeMsg msg; + msg.id = id; + msg.agent_id = tombstone.version.agent_id; + msg.timestamp = tombstone.version.timestamp; + msg.deleted = true; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; +} + +inline LWWEdgeMsg to_edge_msg(const EdgeState& state) +{ + LWWEdgeMsg msg; + msg.from = state.from; + msg.to = state.to; + msg.type = state.type; + msg.agent_id = state.agent_id; + msg.timestamp = state.version.timestamp; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + for (const auto& [name, attr] : state.attrs) { + msg.attrs.emplace(name, attr.value); + } + return msg; +} + +inline LWWEdgeMsg to_edge_tombstone_msg(uint64_t from, uint64_t to, const std::string& type, const Tombstone& tombstone) +{ + LWWEdgeMsg msg; + msg.from = from; + msg.to = to; + msg.type = type; + msg.agent_id = tombstone.version.agent_id; + msg.timestamp = tombstone.version.timestamp; + msg.deleted = true; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; +} + +} // namespace DSR::LWW diff --git a/core/include/dsr/core/types/lww_merge.h b/core/include/dsr/core/types/lww_merge.h new file mode 100644 index 00000000..3b08fb40 --- /dev/null +++ b/core/include/dsr/core/types/lww_merge.h @@ -0,0 +1,24 @@ +#pragma once + +#include "dsr/core/types/lww_types.h" + +namespace DSR::LWW { + +inline Tombstone make_tombstone(const Version& version, uint64_t now, uint64_t tombstone_window_ms) +{ + return Tombstone{version, now + tombstone_window_ms}; +} + +template +bool delta_is_stale(const TombstoneMap& tombstones, const StateMap& states, const Key& key, const Version& version) +{ + if (auto it = tombstones.find(key); it != tombstones.end() && !is_newer(version, it->second.version)) { + return true; + } + if (auto it = states.find(key); it != states.end() && !is_newer(version, it->second.version)) { + return true; + } + return false; +} + +} // namespace DSR::LWW diff --git a/core/include/dsr/core/types/translator.h b/core/include/dsr/core/types/translator.h index 65fd8139..28d0df2e 100644 --- a/core/include/dsr/core/types/translator.h +++ b/core/include/dsr/core/types/translator.h @@ -1,163 +1,38 @@ // -// Created by juancarlos on 1/7/20. +// Legacy compatibility shim. Prefer including `crdt_io.h` directly in new code. // #ifndef CONVERTER_H #define CONVERTER_H -#include "user_types.h" -#include "crdt_types.h" -#include "internal_types.h" -#include +#include "dsr/core/types/crdt_io.h" namespace DSR { - // ---- CRDT → DSR message type helpers ------------------------------------ - - inline static DSR::MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg&& data) - { - DSR::MvregNodeMsg msg; - msg.dk = std::move(data); - msg.id = id; - msg.agent_id = agent_id; - msg.timestamp = get_unix_timestamp(); - msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; - return msg; - } - - template - inline static DSR::MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, - S&& type, mvreg&& data) - { - DSR::MvregEdgeMsg msg; - msg.dk = std::move(data); - msg.id = from; - msg.to = to; - msg.from = from; - msg.type = std::forward(type); - msg.agent_id = agent_id; - msg.timestamp = get_unix_timestamp(); - msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; - return msg; - } - - template - inline static DSR::MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, - S&& attr, mvreg&& data) - { - DSR::MvregNodeAttrMsg msg; - msg.dk = std::move(data); - msg.id = id; - msg.node = node; - msg.attr_name = std::forward(attr); - msg.agent_id = agent_id; - msg.timestamp = get_unix_timestamp(); - msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; - return msg; - } - - template - inline static DSR::MvregEdgeAttrMsg CRDTEdgeAttr_to_Msg(uint32_t agent_id, uint64_t id, - uint64_t from, uint64_t to, - TS&& type, AS&& attr, - mvreg&& data) - { - DSR::MvregEdgeAttrMsg msg; - msg.dk = std::move(data); - msg.id = id; - msg.from_node = from; - msg.to_node = to; - msg.type = std::forward(type); - msg.attr_name = std::forward(attr); - msg.agent_id = agent_id; - msg.timestamp = get_unix_timestamp(); - msg.protocol_version = DSR::DSR_PROTOCOL_VERSION; - return msg; - } - - // ---- User ↔ CRDT helpers (kept unchanged) -------------------------------- - - inline static CRDTEdge user_edge_to_crdt(Edge&& edge) - { - CRDTEdge crdt_edge; - - crdt_edge.agent_id(edge.agent_id()); - crdt_edge.from(edge.from()); - crdt_edge.to(edge.to()); - crdt_edge.type(std::move(edge.type())); - for (auto &&[k,v] : edge.attrs()) { - mvreg mv; - mv.write(std::move(v)); - crdt_edge.attrs().emplace(k, std::move(mv)); - } - - return crdt_edge; - } - - inline static CRDTEdge user_edge_to_crdt(const Edge& edge) - { - CRDTEdge crdt_edge; - - crdt_edge.agent_id(edge.agent_id()); - crdt_edge.from(edge.from()); - crdt_edge.to(edge.to()); - crdt_edge.type(edge.type()); - for (auto &[k,v] : edge.attrs()) { - mvreg mv; - mv.write(v); - crdt_edge.attrs().emplace(k, std::move(mv)); - } - - return crdt_edge; - } - - inline static CRDTNode user_node_to_crdt(Node&& node) - { - CRDTNode crdt_node; - - crdt_node.agent_id(node.agent_id()); - crdt_node.id(node.id()); - crdt_node.type(std::move(node.type())); - crdt_node.name(std::move(node.name())); - - - for (auto &&[k, val] : node.attrs()) { - mvreg mv; - mv.write(std::move(val)); - crdt_node.attrs().emplace(k, std::move(mv)); - } - - for (auto &[k,v] : node.fano()) { - mvreg mv; - mv.write(user_edge_to_crdt(std::move(v))); - crdt_node.fano().emplace(k, std::move(mv)); - } - - return crdt_node; - } - - inline static CRDTNode user_node_to_crdt(const Node& node) - { - CRDTNode crdt_node; +inline MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg&& data) +{ + return crdt_node_to_msg(agent_id, id, std::move(data)); +} - crdt_node.agent_id(node.agent_id()); - crdt_node.id(node.id()); - crdt_node.type(node.type()); - crdt_node.name(node.name()); - for (auto &[k,v] : node.attrs()) { - mvreg mv; - mv.write(v); - crdt_node.attrs().emplace(k, std::move(mv)); - } +template +inline MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) +{ + return crdt_edge_to_msg(agent_id, from, to, std::forward(type), std::move(data)); +} - for (auto &[k,v] : node.fano()) { - mvreg mv; - mv.write(user_edge_to_crdt(v)); - crdt_node.fano().emplace(k, std::move(mv)); - } +template +inline MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) +{ + return crdt_node_attr_to_msg(agent_id, id, node, std::forward(attr), std::move(data)); +} - return crdt_node; - } +template +inline MvregEdgeAttrMsg CRDTEdgeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, + TS&& type, AS&& attr, mvreg&& data) +{ + return crdt_edge_attr_to_msg(agent_id, id, from, to, std::forward(type), std::forward(attr), std::move(data)); } -#endif //CONVERTER_H +} // namespace DSR + +#endif // CONVERTER_H diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index 14e1e3ee..ee6d8de7 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -108,138 +108,97 @@ GUID_t DSRPublisher::getParticipantID() const return mp_participant->guid(); } - -bool DSRPublisher::write(DSR::MvregNodeMsg *object) +namespace { +template +bool write_with_retry(eprosima::fastdds::dds::DataWriter* writer, const T& object, LogFn&& log_error) { ReturnCode_t rt; int retry = 0; while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; + if (rt = writer->write(const_cast(&object)); rt == RETCODE_OK) return true; retry++; } - qInfo() << "Error writing NODE " << object->id << " after 5 attempts. error code: " << rt; + log_error(rt); return false; } +} +bool DSRPublisher::write(const DSR::MvregNodeMsg& object) +{ + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing NODE " << object.id << " after 5 attempts. error code: " << rt; + }); +} -bool DSRPublisher::write(DSR::MvregEdgeMsg *object) + +bool DSRPublisher::write(const DSR::MvregEdgeMsg& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing EDGE " << object->from << " " << object->to << " " << object->type.data() << " after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing EDGE " << object.from << " " << object.to << " " << object.type.data() << " after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::OrMap *object) +bool DSRPublisher::write(const DSR::OrMap& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing GRAPH " << object->m.size() << " after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing GRAPH " << object.m.size() << " after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::GraphRequest *object) +bool DSRPublisher::write(const DSR::GraphRequest& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing GRAPH REQUEST after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing GRAPH REQUEST after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::MvregEdgeAttrVec *object) +bool DSRPublisher::write(const DSR::MvregEdgeAttrVec& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::MvregNodeAttrVec *object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; - return false; +bool DSRPublisher::write(const DSR::MvregNodeAttrVec& object) { + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::LWWNodeMsg *object) +bool DSRPublisher::write(const DSR::LWWNodeMsg& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing LWW NODE " << object->id << " after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing LWW NODE " << object.id << " after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::LWWEdgeMsg *object) +bool DSRPublisher::write(const DSR::LWWEdgeMsg& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing LWW EDGE " << object->from << " " << object->to << " " << object->type.data() << " after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing LWW EDGE " << object.from << " " << object.to << " " << object.type.data() << " after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::LWWNodeAttrVec *object) +bool DSRPublisher::write(const DSR::LWWNodeAttrVec& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing LWW NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing LWW NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::LWWEdgeAttrVec *object) +bool DSRPublisher::write(const DSR::LWWEdgeAttrVec& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing LWW EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing LWW EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; + }); } -bool DSRPublisher::write(DSR::LWWGraphSnapshot *object) +bool DSRPublisher::write(const DSR::LWWGraphSnapshot& object) { - ReturnCode_t rt; - int retry = 0; - while (retry < 5) { - if (rt = mp_writer->write(object); rt == RETCODE_OK) return true; - retry++; - } - qInfo() << "Error writing LWW GRAPH " << object->nodes.size() << " nodes after 5 attempts. error code: " << rt; - return false; + return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { + qInfo() << "Error writing LWW GRAPH " << object.nodes.size() << " nodes after 5 attempts. error code: " << rt; + }); } From 1ac3b0c7de2c3858f0b472fe025f914384888cf6 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 17:30:01 +0200 Subject: [PATCH 15/38] refactor: reduce legacy crdt graph wrappers --- api/dsr_api.cpp | 223 +----------------- api/dsr_rt_api.cpp | 208 +++++++++++++++- api/include/dsr/api/dsr_api.h | 21 -- api/include/dsr/api/dsr_crdt_sync_engine.h | 1 + .../synchronization/graph_synchronization.cpp | 27 ++- 5 files changed, 220 insertions(+), 260 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 87c3cc0a..d0fa631b 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -6,7 +6,6 @@ #include "dsr/api/dsr_crdt_sync_engine.h" #include "dsr/api/dsr_lww_sync_engine.h" #include "dsr/core/types/internal_types.h" -#include "dsr/core/types/translator.h" #include "dsr/core/profiling.h" #include "dsr/api/dsr_signal_emitter.h" #include @@ -716,11 +715,6 @@ std::optional DSRGraph::get_node(uint64_t id) return engine_->get_node(id); } -std::tuple> DSRGraph::insert_node_(CRDTNode &&node) -{ - return crdt_engine().insert_node_raw(std::move(node)); -} - template std::optional DSRGraph::insert_node(No &&node) requires (std::is_same_v, DSR::Node>) @@ -799,10 +793,6 @@ std::optional DSRGraph::insert_node_with_id(No &&node) template std::optional DSRGraph::insert_node_with_id(DSR::Node&&); template std::optional DSRGraph::insert_node_with_id(DSR::Node&); -std::tuple> DSRGraph::update_node_(CRDTNode &&node) -{ - return crdt_engine().update_node_raw(std::move(node)); -} template bool DSRGraph::update_node(No &&node) requires (std::is_same_v, DSR::Node>) @@ -857,11 +847,6 @@ template bool DSRGraph::update_node(DSR::Node&&); -std::tuple, std::optional, std::vector> -DSRGraph::delete_node_(uint64_t id, const CRDTNode &node) { - return crdt_engine().delete_node_raw(id, node); - -} bool DSRGraph::delete_node(const DSR::Node &node) { return delete_node(node.id()); @@ -951,11 +936,6 @@ template bool DSRGraph::insert_or_assign_edge(DSR::Edge&); template bool DSRGraph::insert_or_assign_edge(const DSR::Edge&); -std::optional DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key) -{ - return crdt_engine().delete_edge_raw(from, to, key); -} - bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) { EdgeMutationEffect effect; @@ -1052,11 +1032,6 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector DSRGraph::get_edge_(uint64_t from, uint64_t to, const std::string &key) -{ - return crdt_engine().get_crdt_edge(from, to, key); -} - std::optional DSRGraph::get_edge(const std::string &from, const std::string &to, const std::string &key) { std::shared_lock lock(_mutex); @@ -1093,12 +1068,6 @@ std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::st return {}; } -std::tuple, std::optional> -DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to) -{ - return crdt_engine().insert_or_assign_edge_raw(std::move(attrs), from, to); -} - std::vector DSRGraph::get_node_edges_by_type(const Node &node, const std::string &type) { std::vector edges_; @@ -1170,11 +1139,6 @@ std::map DSRGraph::getCopy() const ///// CORE ////////////////////////////////////////////////////////////////////////////// -std::optional DSRGraph::get_(uint64_t id) -{ - return crdt_engine().get_crdt_node(id); -} - const CRDTNode* DSRGraph::get_node_ptr_(uint64_t id) const { return crdt_engine().get_node_ptr(id); @@ -1364,185 +1328,8 @@ size_t DSRGraph::size() const { bool DSRGraph::empty(const uint64_t &id) { - return get_node_ptr_(id) == nullptr; -} - -void DSRGraph::join_delta_node(DSR::MvregNodeMsg &&mvreg) -{ - crdt_engine().join_delta_node(std::move(mvreg)); -} - - -void DSRGraph::join_delta_edge(DSR::MvregEdgeMsg &&mvreg) -{ - crdt_engine().join_delta_edge(std::move(mvreg)); -} - -std::optional DSRGraph::join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg) -{ - return crdt_engine().join_delta_node_attr(std::move(mvreg)); -} - - -std::optional DSRGraph::join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg) -{ - return crdt_engine().join_delta_edge_attr(std::move(mvreg)); -} - -void DSRGraph::join_full_graph(DSR::OrMap &&full_graph) -{ - crdt_engine().join_full_graph(std::move(full_graph)); -#if 0 - CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph"); - if (!protocol_version_matches(log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { - return; - } - // 5th element: post-join node snapshot captured inside the lock, used for - // signal emission after the lock is released to avoid racing with - // insert_node_/update_node (same pattern as join_delta_node). - std::vector, std::optional>> updates; - - uint64_t id{0}, timestamp{0}; - uint32_t agent_id_ch{0}; - auto delete_unprocessed_deltas = [&](){ - unprocessed_delta_node_att.erase(id); - decltype(unprocessed_delta_edge_from)::node_type node_handle = unprocessed_delta_edge_from.extract(id); - while (!node_handle.empty()) - { - unprocessed_delta_edge_att.erase(std::tuple{id, std::get<0>(node_handle.mapped()), std::get<1>(node_handle.mapped())}); - node_handle = unprocessed_delta_edge_from.extract(id); - } - std::erase_if(unprocessed_delta_edge_to, - [&](auto &it){ return std::get<0>(it.second) == id;}); - }; - - auto consume_unprocessed_deltas = [&](){ - decltype(unprocessed_delta_node_att)::node_type node_handle_node_att = unprocessed_delta_node_att.extract(id); - while (!node_handle_node_att.empty()) - { - auto &[att_name, delta, timestamp_node_att] = node_handle_node_att.mapped(); - if (timestamp < timestamp_node_att) { - process_delta_node_attr(id, att_name,std::move(delta)); - } - node_handle_node_att = unprocessed_delta_node_att.extract(id); - } - - - decltype(unprocessed_delta_edge_from)::node_type node_handle_edge = unprocessed_delta_edge_from.extract(id); - while (!node_handle_edge.empty()) { - auto &[to, type, delta, timestamp_edge] = node_handle_edge.mapped(); - auto att_key = std::tuple{id, to, type}; - DSR_LOG_DEBUG("[JOIN_FULL] unprocessed_delta_edge_from", id, to, type, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge) { - //TODO: este se debería hacer después de insertar el nodo? - process_delta_edge(id, to, type, std::move(delta)); - } - if (nodes.contains(id) and nodes.at(id).read_reg().fano().contains({to, type})) { - decltype(unprocessed_delta_edge_att)::node_type node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - while (!node_handle_edge_att.empty()) { - auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); - DSR_LOG_DEBUG("[JOIN_FULL] edge_att", id, to, type, att_name, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge_att) { - process_delta_edge_attr(id, to, type, att_name, std::move(delta)); - } - node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - } - } - //TODO: Check - std::erase_if(unprocessed_delta_edge_to, - [to = to, id = id, type = type](auto& it) { return it.first == to && std::get<0>(it.second) == id && std::get<1>(it.second) == type;}); - node_handle_edge = unprocessed_delta_edge_from.extract(id); - } - - //TODO: Check - node_handle_edge = unprocessed_delta_edge_to.extract(id); - while (!node_handle_edge.empty()) { - auto &[from, type, delta, timestamp_edge] = node_handle_edge.mapped(); - auto att_key = std::tuple{from, id, type}; - DSR_LOG_DEBUG("[JOIN_FULL] unprocessed_delta_edge_to", from, id, type, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge) { - process_delta_edge(from, id, type, std::move(delta)); - } - if (nodes.contains(from) and nodes.at(from).read_reg().fano().contains({id, type})) { - decltype(unprocessed_delta_edge_att)::node_type node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - while (!node_handle_edge_att.empty()) { - auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); - DSR_LOG_DEBUG("[JOIN_FULL] edge_att", from, id, type, att_name, (timestamp < timestamp_edge)); - if (timestamp < timestamp_edge_att) { - process_delta_edge_attr(from, id, type, att_name, std::move(delta)); - } - node_handle_edge_att = unprocessed_delta_edge_att.extract(att_key); - } - } - - node_handle_edge = unprocessed_delta_edge_to.extract(id); - } - - }; - - { - std::unique_lock lock(_mutex); - - for (auto &[k, val] : full_graph.m) { - auto mv = std::move(val.dk); - bool mv_empty = mv.empty(); - agent_id_ch = val.agent_id; - auto it = nodes.find(k); - std::optional nd = - (it != nodes.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; - id = k; - if (!deleted.contains(k)) { - if (it == nodes.end()) { - it = nodes.emplace(k, mvreg{}).first; - } - it->second.join(std::move(mv)); - if (mv_empty or it->second.empty()) { - update_maps_node_delete(k, nd); - updates.emplace_back(false, k, "", std::nullopt, std::nullopt); - delete_unprocessed_deltas(); - } else { - const auto& reg = it->second.read_reg(); - update_maps_node_insert(k, reg); - updates.emplace_back(true, k, reg.type(), nd, reg); - consume_unprocessed_deltas(); - } - } - } - - } - { - CORTEX_PROFILE_ZONE_N("DSRGraph::join_full_graph emit phase"); - for (auto &[signal, id, type, nd, current_nd] : updates) - if (signal) { - //check what change is joined — use the snapshot captured inside the lock, - //not nodes[id], which races with concurrent insert_node_/update_node calls. - if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { - emitter.update_node_signal(id, type, SignalInfo{ agent_id_ch }); - } else if (nd.value() != *current_nd) { - const auto& iter = current_nd->fano(); - for (const auto &[k, v] : nd->fano()) { - if (!iter.contains(k)) { - emitter.del_edge_signal(id, k.first, k.second, SignalInfo{ agent_id_ch }); - if (v.dk.ds.size() > 0) { - Edge tmp_edge(v.read_reg()); - emitter.deleted_edge_signal(tmp_edge, SignalInfo{ agent_id }); - } - } - } - for (const auto &[k, v] : iter) { - if (auto it = nd->fano().find(k); it == nd->fano().end() or it->second != v) - emitter.update_edge_signal(id, k.first, k.second, SignalInfo{ agent_id_ch }); - } - } - } else { - emitter.del_node_signal(id, SignalInfo{ agent_id_ch }); - if (nd.has_value()) { - Node tmp_node(*nd); - emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); - } - } - } -#endif + std::shared_lock lock(_mutex); + return !engine_->get_node(id).has_value(); } std::pair DSRGraph::start_fullgraph_request_thread() @@ -1572,12 +1359,6 @@ void DSRGraph::start_subscription_threads() if (delta_edge_attrs_thread.joinable()) delta_edge_attrs_thread.join(); } -std::map DSRGraph::Map() -{ - std::shared_lock lock(_mutex); - return crdt_engine().export_mvreg_map(); -} - void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info) { double milliseconds_send = static_cast(info.source_timestamp.seconds()) * 1000.0; diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index fbfa7a07..1ee5c0ec 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -366,7 +366,203 @@ std::optional> RT_API::get_covariance_matrix(uint64_ void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, const std::vector &trans, const std::vector &rot_euler, std::optional timestamp) { CORTEX_PROFILE_ZONE_N("RT_API::insert_or_assign_edge_RT(copy)"); +<<<<<<< HEAD insert_or_assign_edge_RT_impl(n, to, trans, rot_euler, std::nullopt, timestamp); +======= + bool r1 = false; + bool r2 = false; + bool no_send = true; + + std::optional node1_insert; + std::optional node1_update; + std::optional node2; + std::optional to_n_mut; + std::optional to_n_id; + std::optional to_n_type; + { + std::unique_lock lock(G->_mutex); + if (const auto* to_n = G->crdt_engine().get_node_ptr(to); to_n != nullptr) + { + to_n_id = to_n->id(); + to_n_type = to_n->type(); + CRDTEdge e; + if (HISTORY_SIZE <= 0) + { + e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); + CRDTAttribute tr(trans, get_unix_timestamp(), 0); + CRDTAttribute rot(rot_euler, get_unix_timestamp(), 0); + + auto [it, new_el] = e.attrs().emplace("rt_rotation_euler_xyz", mvreg ()); + it->second.write(std::move(rot)); + auto [it2, new_el2] = e.attrs().emplace("rt_translation", mvreg ()); + it2->second.write(std::move(tr)); + } else { + + e = G->crdt_engine().get_crdt_edge(n.id(), to, "RT").value_or(CRDTEdge()); + e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); + auto head_o = G->get_attrib_by_name(e); + std::optional> tstamps_o = G->get_attrib_by_name(e); + std::optional> tr_pack_o = G->get_attrib_by_name(e); + std::optional> rot_pack_o = G->get_attrib_by_name(e); + auto time_stamps = tstamps_o.value_or(std::vector(HISTORY_SIZE, 0)); + auto tr_pack = tr_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); + auto rot_pack = rot_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); + + if (time_stamps.size() < BLOCK_SIZE * HISTORY_SIZE) time_stamps.resize(HISTORY_SIZE); + if (tr_pack.size() < BLOCK_SIZE * HISTORY_SIZE) tr_pack.resize(BLOCK_SIZE * HISTORY_SIZE); + if (rot_pack.size() < BLOCK_SIZE * HISTORY_SIZE) rot_pack.resize(BLOCK_SIZE * HISTORY_SIZE); + + bool update_index = true; + auto timestamp_index = 0; + if (!head_o.has_value()) { + timestamp_index = 0; + } else { + timestamp_index = (int)(head_o.value_or(0)/BLOCK_SIZE) % HISTORY_SIZE; + } + int index = timestamp_index * BLOCK_SIZE; + + auto timestamp_v = (timestamp.has_value()) ? *timestamp : static_cast( + std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count()); + + + + if (timestamp_v < time_stamps[prev(timestamp_index, HISTORY_SIZE)]) { + std::vector diffs; + std::transform(time_stamps.begin(), time_stamps.end(), std::back_inserter(diffs), + [t = *timestamp](auto &val) { + return ((int64_t)t - (int64_t)val > 0) ? ((int64_t)t - (int64_t)val) : std::numeric_limits::min(); + }); + + auto pos = (((std::min_element(diffs.begin(), diffs.end())) - diffs.begin())) % HISTORY_SIZE; + + // too old to insert it + if (pos == timestamp_index && timestamp_v < time_stamps[pos]) {return;} + if (pos > timestamp_index) { + update_index = false; + } + + time_stamps.erase(time_stamps.begin() + timestamp_index); + tr_pack.erase(tr_pack.begin() + index, tr_pack.begin() + index + 3); + rot_pack.erase(rot_pack.begin() + index, rot_pack.begin() + index + 3); + + tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE, trans[0]); + tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 1, trans[1]); + tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 2, trans[2]); + rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE, rot_euler[0]); + rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 1, rot_euler[1]); + rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 2, rot_euler[2]); + time_stamps.insert(time_stamps.begin() + pos, *timestamp); + + } else { + + tr_pack[index] = trans[0]; + tr_pack[index + 1] = trans[1]; + tr_pack[index + 2] = trans[2]; + rot_pack[index] = rot_euler[0]; + rot_pack[index + 1] = rot_euler[1]; + rot_pack[index + 2] = rot_euler[2]; + time_stamps[timestamp_index] = timestamp_v; + } + + CRDTAttribute tr(std::move(tr_pack), get_unix_timestamp(), 0); + CRDTAttribute rot(std::move(rot_pack), get_unix_timestamp(), 0); + CRDTAttribute head_index(index+3, get_unix_timestamp(), 0); + CRDTAttribute timestamps(std::move(time_stamps), get_unix_timestamp(), 0); + + auto [it, new_el] = e.attrs().insert_or_assign("rt_rotation_euler_xyz", mvreg ()); + it->second.write(std::move(rot)); + std::tie(it, new_el) = e.attrs().insert_or_assign("rt_translation", mvreg ()); + it->second.write(std::move(tr)); + if (update_index) { + std::tie(it, new_el) = e.attrs().insert_or_assign("rt_head_index", mvreg ()); + it->second.write(std::move(head_index)); + } + std::tie(it, new_el) = e.attrs().insert_or_assign("rt_timestamps", mvreg ()); + it->second.write(std::move(timestamps)); + } + + const auto ensure_mutable_to_n = [&]() -> CRDTNode& { + if (!to_n_mut.has_value()) to_n_mut = *to_n; + return to_n_mut.value(); + }; + + if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) + { + if ( x.value() != n.id()) + { + no_send = !G->modify_attrib_local(ensure_mutable_to_n(), n.id()); + } + } + else + { + no_send = !G->add_attrib_local(ensure_mutable_to_n(), n.id()); + } + + if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) + { + if (x.value() != G->get_node_level(n).value() + 1) + { + no_send = !G->modify_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); + } + } + else + { + no_send = !G->add_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); + } + + //Check if RT edge exist. + if (!n.fano().contains({to, "RT"})) + { + //Create -> insert edge, update to-node attrs + std::tie(r1, node1_insert, std::ignore) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); + if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); + + } + else + { + //Update -> update edge attrs, update to-node attrs + std::tie(r1, std::ignore, node1_update) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); + if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); + + } + if (!r1) + { + throw std::runtime_error( + "Could not insert Node " + std::to_string(n.id()) + " in G in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); + } + if (!r2 and !no_send) + { + throw std::runtime_error( + "Could not insert Node " + std::to_string(to_n_id.value()) + " in G in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); + } + } else + throw std::runtime_error( + "Destination node " + std::to_string(to) + " not found in G in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); + } + if (!G->copy) + { + if (node1_insert.has_value()) + { + G->dsrpub_edge.write(node1_insert.value()); + + } + if (node1_update.has_value()) G->dsrpub_edge_attrs.write(node1_update.value()); + + if (!no_send and node2.has_value()) G->dsrpub_node_attrs.write(node2.value()); + + G->emitter.update_edge_attr_signal(n.id(), to, "RT" ,{"rt_rotation_euler_xyz", "rt_translation"}, SignalInfo{ G->agent_id }); + G->emitter.update_edge_signal(n.id(), to, "RT", SignalInfo{ G->agent_id }); + if (!no_send) + { + G->emitter.update_node_signal(to_n_id.value(), to_n_type.value(), SignalInfo{ G->agent_id }); + G->emitter.update_node_attr_signal(to_n_id.value(), {"level", "parent"}, SignalInfo{ G->agent_id }); + } + } +>>>>>>> 5ae1438 (refactor: reduce legacy crdt graph wrappers) } void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, std::vector &&trans, std::vector &&rot_euler, std::optional timestamp) @@ -406,7 +602,7 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector to_n_type; { std::unique_lock lock(G->_mutex); - if (const auto* to_n = G->get_node_ptr_(to); to_n != nullptr) + if (const auto* to_n = G->crdt_engine().get_node_ptr(to); to_n != nullptr) { to_n_id = to_n->id(); to_n_type = to_n->type(); @@ -429,7 +625,7 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectorget_edge_(n.id(), to, "RT").value_or(CRDTEdge()); + e = G->crdt_engine().get_crdt_edge(n.id(), to, "RT").value_or(CRDTEdge()); e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); auto head_o = G->get_attrib_by_name(e); std::optional> tstamps_o = G->get_attrib_by_name(e); @@ -572,15 +768,15 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vector insert edge, update to-node attrs - std::tie(r1, node1_insert, std::ignore) = G->insert_or_assign_edge_(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n_mut.value())); + std::tie(r1, node1_insert, std::ignore) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); + if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); } else { //Update -> update edge attrs, update to-node attrs - std::tie(r1, std::ignore, node1_update) = G->insert_or_assign_edge_(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->update_node_(std::move(to_n_mut.value())); + std::tie(r1, std::ignore, node1_update) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); + if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); } if (!r1) diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 501f4d58..718a8579 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -22,7 +22,6 @@ #include "dsr/core/rtps/dsrsubscriber.h" #include "dsr/core/types/crdt_types.h" #include "dsr/core/types/user_types.h" -#include "dsr/core/types/translator.h" #include "dsr/core/traits.h" #include "dsr/api/dsr_agent_info_api.h" #include "dsr/api/dsr_inner_eigen_api.h" @@ -647,27 +646,7 @@ namespace DSR // Non-blocking graph operations ////////////////////////////////////////////////////////////////////////// const CRDTNode* get_node_ptr_(uint64_t id) const; - std::optional get_(uint64_t id); - std::optional get_edge_(uint64_t from, uint64_t to, const std::string &key); - std::tuple> insert_node_(CRDTNode &&node); - std::tuple> update_node_(CRDTNode &&node); - std::tuple, std::optional, std::vector> delete_node_(uint64_t id, const CRDTNode &node); - std::optional delete_edge_(uint64_t from, uint64_t t, const std::string &key); - std::tuple, std::optional> insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to); - ////////////////////////////////////////////////////////////////////////// - // Other methods - ////////////////////////////////////////////////////////////////////////// - std::map Map(); - - ////////////////////////////////////////////////////////////////////////// - // CRDT join operations - /////////////////////////////////////////////////////////////////////////// - void join_delta_node(DSR::MvregNodeMsg &&mvreg); - void join_delta_edge(DSR::MvregEdgeMsg &&mvreg); - std::optional join_delta_node_attr(DSR::MvregNodeAttrMsg &&mvreg); - std::optional join_delta_edge_attr(DSR::MvregEdgeAttrMsg &&mvreg); - void join_full_graph(DSR::OrMap &&full_graph); void publish_node_message(const NodeDeltaMessage &message); void publish_node_attr_batch(const NodeAttrDeltaBatchMessage &message); void publish_edge_message(const EdgeDeltaMessage &message); diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 780c97be..1dd3dcf4 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -16,6 +16,7 @@ class CRDTSyncEngine final : public SyncEngine public: using Nodes = std::unordered_map>; friend class DSRGraph; + friend class RT_API; explicit CRDTSyncEngine(SyncEngineHost& host); CRDTSyncEngine(SyncEngineHost& host, const CRDTSyncEngine& other); diff --git a/tests/synchronization/graph_synchronization.cpp b/tests/synchronization/graph_synchronization.cpp index 526a4843..2e71954c 100644 --- a/tests/synchronization/graph_synchronization.cpp +++ b/tests/synchronization/graph_synchronization.cpp @@ -18,19 +18,22 @@ namespace DSR class DSRGraphTestAccess { public: - static std::map Map(DSRGraph& graph) + static std::map export_crdt_map(DSRGraph& graph) { - return graph.Map(); + auto full_graph = graph.engine_->export_full_graph(); + auto* payload = std::get_if(&full_graph); + REQUIRE(payload != nullptr); + return payload->m; } - static void join_delta_node(DSRGraph& graph, DSR::MvregNodeMsg&& delta) + static void apply_node_delta(DSRGraph& graph, DSR::MvregNodeMsg&& delta) { - graph.join_delta_node(std::move(delta)); + graph.engine_->apply_remote_node_delta(DSR::NodeDeltaMessage{std::move(delta)}); } - static void join_full_graph(DSRGraph& graph, DSR::OrMap&& full_graph) + static void import_full_graph(DSRGraph& graph, DSR::OrMap&& full_graph) { - graph.join_full_graph(std::move(full_graph)); + graph.engine_->import_full_graph(DSR::FullGraphMessage{std::move(full_graph)}); } }; } @@ -116,13 +119,13 @@ TEST_CASE("Full graph join does not leave empty node registers after local delet DSR::OrMap full_graph; full_graph.id = graph.get_agent_id(); full_graph.to_id = graph.get_agent_id(); - full_graph.m = DSRGraphTestAccess::Map(graph); + full_graph.m = DSRGraphTestAccess::export_crdt_map(graph); REQUIRE(graph.delete_node(node.id())); REQUIRE(graph.size() == initial_size); REQUIRE_FALSE(graph.get_node(node.id()).has_value()); - DSRGraphTestAccess::join_full_graph(graph, std::move(full_graph)); + DSRGraphTestAccess::import_full_graph(graph, std::move(full_graph)); REQUIRE(graph.size() == initial_size); REQUIRE_FALSE(graph.get_node(node.id()).has_value()); @@ -145,9 +148,9 @@ TEST_CASE("Full graph join rejects incompatible protocol versions", "[SYNCHRONIZ full_graph.id = static_cast(sender.get_agent_id()); full_graph.to_id = receiver.get_agent_id(); full_graph.protocol_version = DSR::DSR_PROTOCOL_VERSION + 1; - full_graph.m = DSRGraphTestAccess::Map(sender); + full_graph.m = DSRGraphTestAccess::export_crdt_map(sender); - DSRGraphTestAccess::join_full_graph(receiver, std::move(full_graph)); + DSRGraphTestAccess::import_full_graph(receiver, std::move(full_graph)); REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); } @@ -165,13 +168,13 @@ TEST_CASE("Node delta join rejects incompatible protocol versions", "[SYNCHRONIZ REQUIRE(sender.insert_node_with_id(node).has_value()); REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); - auto map = DSRGraphTestAccess::Map(sender); + auto map = DSRGraphTestAccess::export_crdt_map(sender); auto it = map.find(node.id()); REQUIRE(it != map.end()); auto delta = std::move(it->second); delta.protocol_version = DSR::DSR_PROTOCOL_VERSION + 1; - DSRGraphTestAccess::join_delta_node(receiver, std::move(delta)); + DSRGraphTestAccess::apply_node_delta(receiver, std::move(delta)); REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); } From 7c344600f10ac6c4ebe4fa92df4f158693192023 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 18:59:05 +0200 Subject: [PATCH 16/38] refactor: decouple sync engines from graph internals --- api/dsr_api.cpp | 95 ++++++++- api/dsr_crdt_sync_engine.cpp | 220 +++++++++------------ api/dsr_lww_sync_engine.cpp | 186 +++++++++++------ api/dsr_rt_api.cpp | 1 + api/include/dsr/api/dsr_api.h | 14 +- api/include/dsr/api/dsr_crdt_sync_engine.h | 3 - api/include/dsr/api/dsr_lww_sync_engine.h | 8 + api/include/dsr/api/dsr_sync_engine.h | 18 ++ 8 files changed, 345 insertions(+), 200 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index d0fa631b..1c7e1341 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -375,6 +375,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_subscription_functor() << m_info.sample_identity.writer_guid().entityId.value; } tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); }); } @@ -405,6 +406,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_subscription_functor() continue; } tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); }); } @@ -440,6 +442,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_subscription_functor() << m_info.sample_identity.writer_guid().entityId.value; } tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); }); } @@ -470,6 +473,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_subscription_functor() continue; } tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); }); } @@ -509,6 +513,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_attrs_subscription_functor( } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); }); } @@ -540,6 +545,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_attrs_subscription_functor() continue; } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); }); } @@ -578,6 +584,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_attrs_subscription_functor( } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); }); } @@ -609,6 +616,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_attrs_subscription_functor() continue; } tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + std::unique_lock lock(_mutex); engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); }); } @@ -643,6 +651,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_fullgraph_request_functor(std::a << sample.m.size() << " elements"; tp.spawn_task([this, s = std::move(sample)]() mutable { CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); + std::unique_lock lock(_mutex); engine_->import_full_graph(FullGraphMessage{std::move(s)}); }); qDebug() << "Synchronized."; @@ -678,6 +687,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_lww_fullgraph_request_functor(std::at if (static_cast(sample.id) != graph->get_agent_id()) { if (sample.id != -1) { tp.spawn_task([this, s = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); engine_->import_full_graph(FullGraphMessage{std::move(s)}); }); sync = true; @@ -1084,17 +1094,10 @@ std::vector DSRGraph::get_edges_by_type(const std::string &type) std::vector edges_; if (edgeType.contains(type)) { edges_.reserve(edgeType.at(type).size()); - engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { - edges_.emplace_back(edge); - }); - } else { - engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { - edges_.emplace_back(edge); - }); - if (!edges_.empty()) { - edges_.shrink_to_fit(); - } } + engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { + edges_.emplace_back(edge); + }); return edges_; } @@ -1300,7 +1303,79 @@ void DSRGraph::update_maps_edge_insert(uint64_t from, uint64_t to, const std::st edges[{from, to}].insert(key); to_edges[to].insert({from, key}); edgeType[key].insert({from, to}); +} + +bool DSRGraph::is_attribute_ignored(const std::string& name) const +{ + return ignored_attributes.contains(name); +} + +bool DSRGraph::is_node_deleted(uint64_t id) const +{ + std::shared_lock lck(_mutex_cache_maps); + return deleted.contains(id); +} + +void DSRGraph::for_each_incoming_edge(uint64_t to_id, std::function visitor) const +{ + std::shared_lock lck(_mutex_cache_maps); + if (auto it = to_edges.find(to_id); it != to_edges.end()) { + for (const auto& [from, type] : it->second) { + visitor(from, type); + } + } +} +void DSRGraph::for_each_edge_of_type_cache(const std::string& type, std::function visitor) const +{ + std::shared_lock lck(_mutex_cache_maps); + if (auto it = edgeType.find(type); it != edgeType.end()) { + for (const auto& [from, to] : it->second) { + visitor(from, to); + } + } +} + +void DSRGraph::on_remote_node_updated(uint64_t id, const std::string& type, uint32_t agent_id) +{ + emitter.update_node_signal(id, type, SignalInfo{agent_id}); +} + +void DSRGraph::on_remote_node_deleted(uint64_t id, const std::optional& node, const std::vector& removed_edges, uint32_t agent_id) +{ + emitter.del_node_signal(id, SignalInfo{agent_id}); + if (node.has_value()) { + emitter.deleted_node_signal(*node, SignalInfo{agent_id}); + } + for (const auto& edge : removed_edges) { + emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{agent_id}); + emitter.deleted_edge_signal(edge, SignalInfo{agent_id}); + } +} + +void DSRGraph::on_remote_edge_updated(uint64_t from, uint64_t to, const std::string& type, uint32_t agent_id) +{ + emitter.update_edge_signal(from, to, type, SignalInfo{agent_id}); +} + +void DSRGraph::on_remote_edge_deleted(uint64_t from, uint64_t to, const std::string& type, const std::optional& edge, uint32_t agent_id) +{ + emitter.del_edge_signal(from, to, type, SignalInfo{agent_id}); + if (edge.has_value()) { + emitter.deleted_edge_signal(*edge, SignalInfo{agent_id}); + } +} + +void DSRGraph::on_remote_node_attrs_updated(uint64_t id, const std::string& type, const std::vector& attrs, uint32_t agent_id) +{ + emitter.update_node_attr_signal(id, attrs, SignalInfo{agent_id}); + emitter.update_node_signal(id, type, SignalInfo{agent_id}); +} + +void DSRGraph::on_remote_edge_attrs_updated(uint64_t from, uint64_t to, const std::string& type, const std::vector& attrs, uint32_t agent_id) +{ + emitter.update_edge_attr_signal(from, to, type, attrs, SignalInfo{agent_id}); + emitter.update_edge_signal(from, to, type, SignalInfo{agent_id}); } diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index ae0080d1..17a3c85c 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -1,6 +1,5 @@ #include "dsr/api/dsr_crdt_sync_engine.h" -#include "dsr/api/dsr_api.h" #include "dsr/api/dsr_logging.h" #include "dsr/core/profiling.h" #include "dsr/core/types/crdt_io.h" @@ -54,15 +53,6 @@ std::unique_ptr CRDTSyncEngine::clone(SyncEngineHost& host) const return std::make_unique(host, *this); } -DSRGraph& CRDTSyncEngine::graph() -{ - return static_cast(host_); -} - -const DSRGraph& CRDTSyncEngine::graph() const -{ - return static_cast(host_); -} std::optional CRDTSyncEngine::get_node(uint64_t id) const { @@ -96,29 +86,25 @@ bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { - if (auto it = graph().to_edges.find(to); it != graph().to_edges.end()) { - for (const auto& [from, type] : it->second) { - if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { - Edge out(std::move(*edge)); - //TODO: move here? - visitor(from, type, out); - } + bool found = false; + host_.for_each_incoming_edge(to, [&](uint64_t from, const std::string& type) { + found = true; + if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + Edge out(std::move(*edge)); + visitor(from, type, out); } - return true; - } - return false; + }); + return found; } void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { - if (auto it = graph().edgeType.find(type); it != graph().edgeType.end()) { - for (const auto& [from, to] : it->second) { - if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { - Edge out(std::move(*edge)); - visitor(from, to, out); - } + host_.for_each_edge_of_type_cache(type, [&](uint64_t from, uint64_t to) { + if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + Edge out(std::move(*edge)); + visitor(from, to, out); } - } + }); } size_t CRDTSyncEngine::size() const @@ -250,7 +236,7 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba const auto sample_agent_id = payload->vec.front().agent_id; std::vector changed_attributes; for (auto&& item : payload->vec) { - if (graph().ignored_attributes.contains(item.attr_name)) { + if (host_.is_attribute_ignored(item.attr_name)) { continue; } if (auto changed = join_delta_node_attr(std::move(item)); changed.has_value()) { @@ -260,14 +246,10 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba if (!changed_attributes.empty()) { std::string type; - { - std::shared_lock lock(graph()._mutex); - if (const auto* node = get_node_ptr(id); node != nullptr) { - type = node->type(); - } + if (const auto* node = get_node_ptr(id); node != nullptr) { + type = node->type(); } - graph().emitter.update_node_attr_signal(id, changed_attributes, SignalInfo{sample_agent_id}); - graph().emitter.update_node_signal(id, type, SignalInfo{sample_agent_id}); + host_.on_remote_node_attrs_updated(id, type, changed_attributes, sample_agent_id); } } @@ -284,7 +266,7 @@ void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& ba const auto sample_agent_id = payload->vec.front().agent_id; std::vector changed_attributes; for (auto&& item : payload->vec) { - if (graph().ignored_attributes.contains(item.attr_name)) { + if (host_.is_attribute_ignored(item.attr_name)) { continue; } if (auto changed = join_delta_edge_attr(std::move(item)); changed.has_value()) { @@ -293,8 +275,7 @@ void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& ba } if (!changed_attributes.empty()) { - graph().emitter.update_edge_attr_signal(from, to, type, changed_attributes, SignalInfo{sample_agent_id}); - graph().emitter.update_edge_signal(from, to, type, SignalInfo{sample_agent_id}); + host_.on_remote_edge_attrs_updated(from, to, type, changed_attributes, sample_agent_id); } } @@ -307,11 +288,10 @@ void CRDTSyncEngine::import_full_graph(FullGraphMessage&& full_graph) FullGraphMessage CRDTSyncEngine::export_full_graph() const { - std::shared_lock lock(graph()._mutex); OrMap map; - map.id = static_cast(graph().agent_id); + map.id = static_cast(host_.local_agent_id()); map.protocol_version = DSR_PROTOCOL_VERSION; - map.sync_mode = sync_mode_wire_value(graph().sync_mode); + map.sync_mode = sync_mode_wire_value(host_.local_sync_mode()); map.m = export_mvreg_map(); return map; } @@ -352,7 +332,7 @@ std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to std::tuple> CRDTSyncEngine::insert_node_raw(CRDTNode&& node) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_node_raw"); - if (!graph().deleted.contains(node.id())) + if (!host_.is_node_deleted(node.id())) { if (auto it = nodes_.find(node.id()); it != nodes_.end() and not it->second.empty() and it->second.read_reg() == node) { @@ -360,9 +340,9 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR } uint64_t id = node.id(); - graph().update_maps_node_insert(id, node); + host_.update_maps_node_insert(Node(node)); auto delta = nodes_[id].write(std::move(node)); - return {true, crdt_node_to_msg(graph().agent_id, id, std::move(delta))}; + return {true, crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta))}; } return {false, {}}; } @@ -370,7 +350,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR std::tuple> CRDTSyncEngine::update_node_raw(CRDTNode&& node) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::update_node_raw"); - if (!graph().deleted.contains(node.id())) + if (!host_.is_node_deleted(node.id())) { auto nit = nodes_.find(node.id()); if (nit != nodes_.end() && !nit->second.empty()) @@ -382,13 +362,13 @@ std::tuple> CRDTSyncEngine::update_node_ra if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - crdt_node_attr_to_msg(graph().agent_id, node.id(), node.id(), k, std::move(delta))); + crdt_node_attr_to_msg(host_.local_agent_id(), node.id(), node.id(), k, std::move(delta))); } } auto it_a = iter.begin(); while (it_a != iter.end()) { const std::string& k = it_a->first; - if (graph().ignored_attributes.contains(k)) { + if (host_.is_attribute_ignored(k)) { it_a = iter.erase(it_a); } else if (!node.attrs().contains(k)) { auto delta = it_a->second.reset(); @@ -419,27 +399,25 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) deleted_edges.emplace_back(v.second.read_reg()); } auto delta = nodes_[id].reset(); - MvregNodeMsg delta_remove = crdt_node_to_msg(graph().agent_id, id, std::move(delta)); + MvregNodeMsg delta_remove = crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta)); { - decltype(graph().to_edges)::mapped_type incoming; - { - std::shared_lock lck_cache(graph()._mutex_cache_maps); - if (graph().to_edges.contains(id)) - incoming = graph().to_edges.at(id); - } + std::vector> incoming; + host_.for_each_incoming_edge(id, [&](uint64_t from, const std::string& type) { + incoming.emplace_back(from, type); + }); for (const auto& [from, type] : incoming) { if (!nodes_.contains(from)) continue; auto& visited_node = nodes_.at(from).read_reg(); deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); auto delta_fano = visited_node.fano().at({id, type}).reset(); - delta_vec.emplace_back(crdt_edge_to_msg(graph().agent_id, from, id, type, std::move(delta_fano))); + delta_vec.emplace_back(crdt_edge_to_msg(host_.local_agent_id(), from, id, type, std::move(delta_fano))); visited_node.fano().erase({id, type}); - graph().update_maps_edge_delete(from, id, type); + host_.update_maps_edge_delete(from, id, type); } } - graph().update_maps_node_delete(id, node); + host_.update_maps_node_delete(id, std::make_optional(Node(node))); return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; } @@ -451,8 +429,8 @@ std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint6 if (node.fano().contains({to, key})) { auto delta = node.fano().at({to, key}).reset(); node.fano().erase({to, key}); - graph().update_maps_edge_delete(from, to, key); - return crdt_edge_to_msg(graph().agent_id, from, to, key, std::move(delta)); + host_.update_maps_edge_delete(from, to, key); + return crdt_edge_to_msg(host_.local_agent_id(), from, to, key, std::move(delta)); } } return {}; @@ -478,7 +456,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); atts_deltas.vec.emplace_back( - crdt_edge_attr_to_msg(graph().agent_id, from, from, to, attrs.type(), k, std::move(delta))); + crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type(), k, std::move(delta))); } } auto it = iter_edge.begin(); @@ -488,7 +466,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 auto delta = it->second.reset(); it = iter_edge.erase(it); atts_deltas.vec.emplace_back( - crdt_edge_attr_to_msg(graph().agent_id, from, from, to, attrs.type(), std::move(att), std::move(delta))); + crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type(), std::move(att), std::move(delta))); } else { ++it; } @@ -498,8 +476,8 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 { std::string att_type = attrs.type(); auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); - graph().update_maps_edge_insert(from, to, att_type); - return {true, crdt_edge_to_msg(graph().agent_id, from, to, std::move(att_type), std::move(delta)), {}}; + host_.update_maps_edge_insert(from, to, att_type); + return {true, crdt_edge_to_msg(host_.local_agent_id(), from, to, std::move(att_type), std::move(delta)), {}}; } } return {false, {}, {}}; @@ -520,10 +498,10 @@ bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::s edge_reg.join(std::move(delta)); if (edge_reg.empty() || d_empty) { fanout.erase({to, type}); - graph().update_maps_edge_delete(from, to, type); + host_.update_maps_edge_delete(from, to, type); signal = false; } else { - graph().update_maps_edge_insert(from, to, type); + host_.update_maps_edge_insert(from, to, type); signal = !prev.has_value() || prev.value() != edge_reg.read_reg(); } return signal; @@ -558,11 +536,11 @@ void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const s void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node"); - const auto log_level = graph().log_level; + const auto log_level = host_.get_log_level(); std::optional maybe_deleted_node = {}; try { - if (!protocol_version_matches(graph().log_level, "DSR_NODE", mvreg.protocol_version)) { + if (!protocol_version_matches(log_level, "DSR_NODE", mvreg.protocol_version)) { return; } bool signal = false, joined = false; @@ -572,7 +550,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) auto d_empty = crdt_delta.empty(); std::unordered_set,hash_tuple> map_new_to_edges = {}; std::unordered_set,hash_tuple> map_new_from_edges = {}; - std::optional,hash_tuple>> cache_map_to_edges = {}; + std::vector> incoming_edge_cache; std::string current_type; auto delete_unprocessed_deltas = [&](){ @@ -650,22 +628,25 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node crdt merge"); - std::unique_lock lock(graph()._mutex); - if (!graph().deleted.contains(id)) { + if (!host_.is_node_deleted(id)) { if (auto it = nodes_.find(id); it != nodes_.end() && !it->second.empty()) { maybe_deleted_node = it->second.read_reg(); } nodes_[id].join(std::move(crdt_delta)); if (nodes_.at(id).empty() || d_empty) { if (maybe_deleted_node.has_value()) { - cache_map_to_edges = graph().to_edges[id]; + host_.for_each_incoming_edge(id, [&](uint64_t from, const std::string& type) { + incoming_edge_cache.emplace_back(from, type); + }); } - graph().update_maps_node_delete(id, maybe_deleted_node); + std::optional deleted_node_user = maybe_deleted_node.has_value() + ? std::make_optional(Node(*maybe_deleted_node)) : std::nullopt; + host_.update_maps_node_delete(id, deleted_node_user); delete_unprocessed_deltas(); } else { const auto& reg = nodes_.at(id).read_reg(); current_type = reg.type(); - graph().update_maps_node_insert(id, reg); + host_.update_maps_node_insert(Node(reg)); consume_unprocessed_deltas(); } signal = !d_empty; @@ -676,34 +657,27 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) if (joined) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node signal emit"); if (signal) { - graph().emitter.update_node_signal(id, current_type, SignalInfo{ mvreg.agent_id }); + host_.on_remote_node_updated(id, current_type, mvreg.agent_id); if (const auto* current = get_node_ptr(id); current != nullptr) { - for (const auto &[k, v] : current->fano()) { - graph().emitter.update_edge_signal(id, k.first, k.second, SignalInfo{ mvreg.agent_id }); + for (const auto& [k, v] : current->fano()) { + host_.on_remote_edge_updated(id, k.first, k.second, mvreg.agent_id); } } - - for (const auto &[k, v]: map_new_to_edges) - { - graph().emitter.update_edge_signal(k, id, v, SignalInfo{ mvreg.agent_id }); + for (const auto& [to, type] : map_new_to_edges) { + host_.on_remote_edge_updated(to, id, type, mvreg.agent_id); } } else { - graph().emitter.del_node_signal(id, SignalInfo{ mvreg.agent_id }); + std::optional deleted_node_user = maybe_deleted_node.has_value() + ? std::make_optional(Node(*maybe_deleted_node)) : std::nullopt; + std::vector deleted_edges_user; if (maybe_deleted_node.has_value()) { - Node tmp_node(*maybe_deleted_node); - graph().emitter.deleted_node_signal(tmp_node, SignalInfo{ mvreg.agent_id }); - for (const auto &node: maybe_deleted_node->fano()) { - graph().emitter.del_edge_signal(node.second.read_reg().from(), node.second.read_reg().to(), - node.second.read_reg().type(), SignalInfo{ mvreg.agent_id }); - Edge tmp_edge(node.second.read_reg()); - graph().emitter.deleted_edge_signal(tmp_edge, SignalInfo{ mvreg.agent_id }); + for (const auto& [key, mvreg_edge] : maybe_deleted_node->fano()) { + deleted_edges_user.emplace_back(mvreg_edge.read_reg()); } } - - if (cache_map_to_edges.has_value()) { - for (const auto &[from, type] : cache_map_to_edges.value()) { - graph().emitter.del_edge_signal(from, id, type, SignalInfo{ mvreg.agent_id }); - } + host_.on_remote_node_deleted(id, deleted_node_user, deleted_edges_user, mvreg.agent_id); + for (const auto& [from, type] : incoming_edge_cache) { + host_.on_remote_edge_deleted(from, id, type, std::nullopt, mvreg.agent_id); } } } @@ -713,9 +687,9 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge"); - const auto log_level = graph().log_level; + const auto log_level = host_.get_log_level(); try { - if (!protocol_version_matches(graph().log_level, "DSR_EDGE", mvreg.protocol_version)) { + if (!protocol_version_matches(log_level, "DSR_EDGE", mvreg.protocol_version)) { return; } bool signal = false, joined = false; @@ -755,10 +729,9 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge crdt merge"); - std::unique_lock lock(graph()._mutex); deleted_edge = get_edge(from, to, type); bool cfrom{nodes_.contains(from)}, cto{nodes_.contains(to)}; - bool dfrom{graph().deleted.contains(from)}, dto{graph().deleted.contains(to)}; + bool dfrom{host_.is_node_deleted(from)}, dto{host_.is_node_deleted(to)}; if (cfrom && cto) { signal = process_delta_edge(from, to, type, std::move(crdt_delta)); @@ -800,12 +773,9 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) if (joined) { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge signal emit"); if (signal) { - graph().emitter.update_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); + host_.on_remote_edge_updated(from, to, type, mvreg.agent_id); } else { - graph().emitter.del_edge_signal(from, to, type, SignalInfo{ mvreg.agent_id }); - if (deleted_edge.has_value()) { - graph().emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ mvreg.agent_id }); - } + host_.on_remote_edge_deleted(from, to, type, deleted_edge, mvreg.agent_id); } } } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } @@ -815,7 +785,7 @@ std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node_attr"); try { - if (!protocol_version_matches(graph().log_level, "DSR_NODE_ATTS", mvreg.protocol_version)) { + if (!protocol_version_matches(host_.get_log_level(), "DSR_NODE_ATTS", mvreg.protocol_version)) { return {}; } auto id = mvreg.node; @@ -825,13 +795,12 @@ std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg auto d_empty = crdt_delta.empty(); { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node_attr crdt merge"); - std::unique_lock lock(graph()._mutex); if (nodes_.contains(id)) { process_delta_node_attr(id, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_node_att_, [id = id, att_name = att_name](auto &it){ return it.first == id && std::get<0>(it.second) == att_name;}); return att_name; - } else if (!graph().deleted.contains(id)) { + } else if (!host_.is_node_deleted(id)) { bool find = false; for (auto [begin, end] = unprocessed_delta_node_att_.equal_range(id); begin != end; ++begin) { if (std::get<0>(begin->second) == att_name){ @@ -859,7 +828,7 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_edge_attr"); try { - if (!protocol_version_matches(graph().log_level, "DSR_EDGE_ATTS", mvreg.protocol_version)) { + if (!protocol_version_matches(host_.get_log_level(), "DSR_EDGE_ATTS", mvreg.protocol_version)) { return {}; } auto from = mvreg.from_node; @@ -871,14 +840,13 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg auto d_empty = crdt_delta.empty(); { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); - std::unique_lock lock(graph()._mutex); if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({to, type})) { process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_edge_att_, [from = from, to = to, type = type, att_name = att_name](auto &it){ return it.first == std::tuple{from, to, type} && std::get<0>(it.second) == att_name;}); return att_name; - } else if (!graph().deleted.contains(from) && !graph().deleted.contains(to)) { + } else if (!host_.is_node_deleted(from) && !host_.is_node_deleted(to)) { bool find = false; for (auto [begin, end] = unprocessed_delta_edge_att_.equal_range(std::tuple{from, to, type}); begin != end; ++begin) { if (std::get<0>(begin->second) == att_name){ @@ -905,8 +873,8 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_full_graph"); - const auto log_level = graph().log_level; - if (!protocol_version_matches(graph().log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { + const auto log_level = host_.get_log_level(); + if (!protocol_version_matches(log_level, "GRAPH_ANSWER", full_graph.protocol_version)) { return; } @@ -986,8 +954,6 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; { - std::unique_lock lock(graph()._mutex); - for (auto &[k, val] : full_graph.m) { auto mv = std::move(val.dk); bool mv_empty = mv.empty(); @@ -996,18 +962,19 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) std::optional nd = (it != nodes_.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; id = k; - if (!graph().deleted.contains(k)) { + if (!host_.is_node_deleted(k)) { if (it == nodes_.end()) { it = nodes_.emplace(k, mvreg{}).first; } it->second.join(std::move(mv)); if (mv_empty or it->second.empty()) { - graph().update_maps_node_delete(k, nd); + std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; + host_.update_maps_node_delete(k, nd_user); updates.emplace_back(false, k, "", std::nullopt, std::nullopt); delete_unprocessed_deltas(); } else { const auto& reg = it->second.read_reg(); - graph().update_maps_node_insert(k, reg); + host_.update_maps_node_insert(Node(reg)); updates.emplace_back(true, k, reg.type(), nd, reg); consume_unprocessed_deltas(); } @@ -1019,29 +986,24 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) for (auto &[signal, node_id, type, nd, current_nd] : updates) { if (signal) { if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { - graph().emitter.update_node_signal(node_id, type, SignalInfo{ agent_id_ch }); + host_.on_remote_node_updated(node_id, type, agent_id_ch); } else if (nd.value() != *current_nd) { const auto& iter = current_nd->fano(); for (const auto &[k, v] : nd->fano()) { if (!iter.contains(k)) { - graph().emitter.del_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); - if (v.dk.ds.size() > 0) { - Edge tmp_edge(v.read_reg()); - graph().emitter.deleted_edge_signal(tmp_edge, SignalInfo{ graph().agent_id }); - } + std::optional del_edge = (v.dk.ds.size() > 0) + ? std::make_optional(Edge(v.read_reg())) : std::nullopt; + host_.on_remote_edge_deleted(node_id, k.first, k.second, del_edge, agent_id_ch); } } for (const auto &[k, v] : iter) { if (auto it = nd->fano().find(k); it == nd->fano().end() or it->second != v) - graph().emitter.update_edge_signal(node_id, k.first, k.second, SignalInfo{ agent_id_ch }); + host_.on_remote_edge_updated(node_id, k.first, k.second, agent_id_ch); } } } else { - graph().emitter.del_node_signal(node_id, SignalInfo{ agent_id_ch }); - if (nd.has_value()) { - Node tmp_node(*nd); - graph().emitter.deleted_node_signal(tmp_node, SignalInfo{ agent_id_ch }); - } + std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; + host_.on_remote_node_deleted(node_id, nd_user, {}, agent_id_ch); } } } @@ -1055,10 +1017,10 @@ std::map CRDTSyncEngine::export_mvreg_map() const MvregNodeMsg msg; msg.dk = kv.second; msg.id = kv.first; - msg.agent_id = graph().agent_id; + msg.agent_id = host_.local_agent_id(); msg.timestamp = get_unix_timestamp(); msg.protocol_version = DSR_PROTOCOL_VERSION; - msg.sync_mode = sync_mode_wire_value(graph().sync_mode); + msg.sync_mode = sync_mode_wire_value(host_.local_sync_mode()); m.emplace(kv.first, std::move(msg)); } return m; diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index cd38e02c..ec537ad6 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -9,20 +9,6 @@ using DSR::LWW::edge_key; using DSR::LWW::is_newer; using DSR::LWW::version_of; -namespace { -template -void erase_if_compat(Map& map, Predicate&& predicate) -{ - for (auto it = map.begin(); it != map.end(); ) { - if (predicate(*it)) { - it = map.erase(it); - } else { - ++it; - } - } -} -} - LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, uint64_t tombstone_window_ms) : host_(host), tombstone_window_ms_(tombstone_window_ms) @@ -38,6 +24,9 @@ LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, const LWWSyncEngine& other) node_tombstones_(other.node_tombstones_), edge_tombstones_(other.edge_tombstones_) { + for (const auto& [key, _] : edges_) { + idx_insert(key); + } } SyncBackendInfo LWWSyncEngine::backend_info() const @@ -50,6 +39,29 @@ std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const return std::make_unique(host, *this); } +void LWWSyncEngine::idx_insert(const EdgeKey& key) +{ + from_idx_[std::get<0>(key)].insert(key); + to_idx_[std::get<1>(key)].insert(key); + type_idx_[std::get<2>(key)].insert(key); +} + +void LWWSyncEngine::idx_erase(const EdgeKey& key) +{ + if (auto it = from_idx_.find(std::get<0>(key)); it != from_idx_.end()) { + it->second.erase(key); + if (it->second.empty()) from_idx_.erase(it); + } + if (auto it = to_idx_.find(std::get<1>(key)); it != to_idx_.end()) { + it->second.erase(key); + if (it->second.empty()) to_idx_.erase(it); + } + if (auto it = type_idx_.find(std::get<2>(key)); it != type_idx_.end()) { + it->second.erase(key); + if (it->second.empty()) type_idx_.erase(it); + } +} + uint64_t LWWSyncEngine::current_time_ms() const { return static_cast( @@ -65,8 +77,8 @@ uint64_t LWWSyncEngine::next_timestamp() void LWWSyncEngine::prune_tombstones(uint64_t now) { - erase_if_compat(node_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); - erase_if_compat(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); + std::erase_if(node_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); + std::erase_if(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); } void LWWSyncEngine::store_node_tombstone(uint64_t id, Version version, uint64_t now) @@ -81,26 +93,46 @@ void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std:: void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) { - for (auto it = edges_.begin(); it != edges_.end(); ) { - if (it->second.from == node_id || it->second.to == node_id) { - host_.update_maps_edge_delete(it->second.from, it->second.to, it->second.type); - store_edge_tombstone(it->second.from, it->second.to, it->second.type, version, now); - if (removed_edges != nullptr) { - removed_edges->emplace_back(LWW::to_user_edge(it->second)); - } - it = edges_.erase(it); - } else { - ++it; + std::unordered_set to_erase; + if (auto it = from_idx_.find(node_id); it != from_idx_.end()) { + to_erase.insert(it->second.begin(), it->second.end()); + } + if (auto it = to_idx_.find(node_id); it != to_idx_.end()) { + to_erase.insert(it->second.begin(), it->second.end()); + } + for (const auto& key : to_erase) { + auto eit = edges_.find(key); + if (eit == edges_.end()) continue; + host_.update_maps_edge_delete(eit->second.from, eit->second.to, eit->second.type); + store_edge_tombstone(eit->second.from, eit->second.to, eit->second.type, version, now); + if (removed_edges != nullptr) { + removed_edges->emplace_back(LWW::to_user_edge(eit->second)); } + idx_erase(key); + edges_.erase(eit); } } std::optional LWWSyncEngine::get_node(uint64_t id) const { - if (auto it = nodes_.find(id); it != nodes_.end()) { - return LWW::to_user_node(it->second, edges_); + auto it = nodes_.find(id); + if (it == nodes_.end()) return {}; + + const auto& state = it->second; + Node out(state.agent_id, state.type); + out.id(state.id); + out.name(state.name); + for (const auto& [name, attr] : state.attrs) { + out.attrs().emplace(name, attr.value); + } + if (auto fidx = from_idx_.find(id); fidx != from_idx_.end()) { + for (const auto& key : fidx->second) { + if (auto eit = edges_.find(key); eit != edges_.end()) { + out.fano().emplace(std::pair{eit->second.to, eit->second.type}, LWW::to_user_edge(eit->second)); + } + } } - return {}; + return out; } std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const @@ -116,10 +148,10 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& if (!nodes_.contains(from)) { return false; } - for (const auto& [key, edge] : edges_) { - if (edge.from == from) { - Edge out = LWW::to_user_edge(edge); - visitor(edge.to, edge.type, out); + if (auto it = from_idx_.find(from); it != from_idx_.end()) { + for (const auto& key : it->second) { + const auto& edge = edges_.at(key); + visitor(edge.to, edge.type, LWW::to_user_edge(edge)); } } return true; @@ -127,24 +159,24 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { - bool found = false; - for (const auto& [key, edge] : edges_) { - if (edge.to == to) { - Edge out = LWW::to_user_edge(edge); - visitor(edge.from, edge.type, out); - found = true; - } + auto it = to_idx_.find(to); + if (it == to_idx_.end()) { + return false; + } + for (const auto& key : it->second) { + const auto& edge = edges_.at(key); + visitor(edge.from, edge.type, LWW::to_user_edge(edge)); } - return found; + return true; } void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { - for (const auto& [key, edge] : edges_) { - if (edge.type == type) { - Edge out = LWW::to_user_edge(edge); - visitor(edge.from, edge.to, out); - } + auto it = type_idx_.find(type); + if (it == type_idx_.end()) return; + for (const auto& key : it->second) { + const auto& edge = edges_.at(key); + visitor(edge.from, edge.to, LWW::to_user_edge(edge)); } } @@ -156,8 +188,8 @@ size_t LWWSyncEngine::size() const std::map LWWSyncEngine::snapshot() const { std::map out; - for (const auto& [id, node] : nodes_) { - out.emplace(id, LWW::to_user_node(node, edges_)); + for (const auto& [id, _] : nodes_) { + out.emplace(id, *get_node(id)); } return out; } @@ -203,7 +235,7 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) return effect; } - auto old_node = LWW::to_user_node(it->second, edges_); + auto old_node = get_node(node.id()); auto version = version_of(now, host_.local_agent_id()); it->second.type = node.type(); it->second.name = node.name(); @@ -241,7 +273,7 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) } auto version = version_of(now, host_.local_agent_id()); - auto deleted_node = LWW::to_user_node(it->second, edges_); + auto deleted_node = get_node(id); effect.deleted_node = deleted_node; effect.deleted_edges.clear(); erase_related_edges(id, version, now, &effect.deleted_edges); @@ -278,8 +310,8 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) } auto key = edge_key(edge.from(), edge.to(), edge.type()); - auto& state = edges_[key]; - state = LWW::to_edge_state(edge, version, host_.local_agent_id()); + edges_[key] = LWW::to_edge_state(edge, version, host_.local_agent_id()); + idx_insert(key); // idempotent for updates for (const auto& [name, _] : edge.attrs()) { effect.changed_attributes.emplace_back(name); } @@ -310,6 +342,7 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, effect.deleted_edge = LWW::to_user_edge(it->second); host_.update_maps_edge_delete(from, to, type); store_edge_tombstone(from, to, type, version, now); + idx_erase(key); edges_.erase(it); effect.applied = true; if (auto delta = export_edge_delta(from, to, type); delta.has_value()) { @@ -335,13 +368,16 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) } if (payload->deleted) { + std::optional deleted_node; + std::vector deleted_edges; if (auto it = nodes_.find(payload->id); it != nodes_.end()) { - auto deleted_node = LWW::to_user_node(it->second, edges_); - erase_related_edges(payload->id, version, now); + deleted_node = get_node(payload->id); + erase_related_edges(payload->id, version, now, &deleted_edges); host_.update_maps_node_delete(payload->id, deleted_node); nodes_.erase(it); } store_node_tombstone(payload->id, version, now); + host_.on_remote_node_deleted(payload->id, deleted_node, deleted_edges, payload->agent_id); return; } @@ -354,6 +390,7 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) nodes_[payload->id] = std::move(state); node_tombstones_.erase(payload->id); host_.update_maps_node_insert(*get_node(payload->id)); + host_.on_remote_node_updated(payload->id, payload->type, payload->agent_id); } void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) @@ -377,19 +414,24 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) auto key = edge_key(payload->from, payload->to, payload->type); if (payload->deleted) { - if (edges_.contains(key)) { + std::optional deleted_edge; + if (auto it = edges_.find(key); it != edges_.end()) { + deleted_edge = LWW::to_user_edge(it->second); host_.update_maps_edge_delete(payload->from, payload->to, payload->type); - edges_.erase(key); + idx_erase(key); + edges_.erase(it); } store_edge_tombstone(payload->from, payload->to, payload->type, version, now); + host_.on_remote_edge_deleted(payload->from, payload->to, payload->type, deleted_edge, payload->agent_id); return; } EdgeState state = LWW::to_edge_state(*payload); - edges_[key] = std::move(state); + idx_insert(key); edge_tombstones_.erase(key); host_.update_maps_edge_insert(payload->from, payload->to, payload->type); + host_.on_remote_edge_updated(payload->from, payload->to, payload->type, payload->agent_id); } void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) @@ -399,6 +441,13 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat return; } + struct NodeAttrBatchChange + { + std::string type; + std::vector attrs; + uint32_t agent_id{0}; + }; + std::unordered_map changes; for (const auto& item : payload->vec) { auto it = nodes_.find(item.node_id); if (it == nodes_.end()) { @@ -414,6 +463,16 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat } else { it->second.attrs[item.attr_name] = AttrState{item.value, version}; } + auto& change = changes[item.node_id]; + if (change.type.empty()) { + change.type = it->second.type; + } + change.agent_id = item.agent_id; + change.attrs.push_back(item.attr_name); + } + + for (const auto& [id, change] : changes) { + host_.on_remote_node_attrs_updated(id, change.type, change.attrs, change.agent_id); } } @@ -424,6 +483,12 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat return; } + struct EdgeAttrBatchChange + { + std::vector attrs; + uint32_t agent_id{0}; + }; + std::map changes; for (const auto& item : payload->vec) { auto it = edges_.find(edge_key(item.from, item.to, item.type)); if (it == edges_.end()) { @@ -439,6 +504,13 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat } else { it->second.attrs[item.attr_name] = AttrState{item.value, version}; } + auto& change = changes[edge_key(item.from, item.to, item.type)]; + change.agent_id = item.agent_id; + change.attrs.push_back(item.attr_name); + } + + for (const auto& [key, change] : changes) { + host_.on_remote_edge_attrs_updated(std::get<0>(key), std::get<1>(key), std::get<2>(key), change.attrs, change.agent_id); } } diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index 1ee5c0ec..3c876cdb 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -2,6 +2,7 @@ #include #include #include +#include #include using namespace DSR; diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 718a8579..c6430b22 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -636,6 +636,19 @@ namespace DSR void update_maps_node_insert(const Node& node) override; void update_maps_node_delete(uint64_t id, const std::optional& node) override; + GraphSettings::LOGLEVEL get_log_level() const override { return log_level; } + bool is_attribute_ignored(const std::string& name) const override; + bool is_node_deleted(uint64_t id) const override; + void for_each_incoming_edge(uint64_t to, std::function visitor) const override; + void for_each_edge_of_type_cache(const std::string& type, std::function visitor) const override; + + void on_remote_node_updated(uint64_t id, const std::string& type, uint32_t agent_id) override; + void on_remote_node_deleted(uint64_t id, const std::optional& node, const std::vector& edges, uint32_t agent_id) override; + void on_remote_edge_updated(uint64_t from, uint64_t to, const std::string& type, uint32_t agent_id) override; + void on_remote_edge_deleted(uint64_t from, uint64_t to, const std::string& type, const std::optional& edge, uint32_t agent_id) override; + void on_remote_node_attrs_updated(uint64_t id, const std::string& type, const std::vector& attrs, uint32_t agent_id) override; + void on_remote_edge_attrs_updated(uint64_t from, uint64_t to, const std::string& type, const std::vector& attrs, uint32_t agent_id) override; + CRDTSyncEngine& crdt_engine(); const CRDTSyncEngine& crdt_engine() const; LWWSyncEngine& lww_engine(); @@ -646,7 +659,6 @@ namespace DSR // Non-blocking graph operations ////////////////////////////////////////////////////////////////////////// const CRDTNode* get_node_ptr_(uint64_t id) const; - void publish_node_message(const NodeDeltaMessage &message); void publish_node_attr_batch(const NodeAttrDeltaBatchMessage &message); void publish_edge_message(const EdgeDeltaMessage &message); diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 1dd3dcf4..20efe2e1 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -68,9 +68,6 @@ class CRDTSyncEngine final : public SyncEngine std::map export_mvreg_map() const; - class DSRGraph& graph(); - const class DSRGraph& graph() const; - bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta); void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr); void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr); diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index 902ba461..f7fa5d4e 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -68,6 +68,10 @@ class LWWSyncEngine final : public SyncEngine void store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now); void erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges = nullptr); + // Secondary indices — maintained in sync with edges_ for O(degree) lookup. + void idx_insert(const EdgeKey& key); + void idx_erase(const EdgeKey& key); + SyncEngineHost& host_; uint64_t tombstone_window_ms_; uint64_t logical_clock_ms_{0}; @@ -75,6 +79,10 @@ class LWWSyncEngine final : public SyncEngine std::unordered_map edges_; std::unordered_map node_tombstones_; std::unordered_map edge_tombstones_; + + std::unordered_map> from_idx_; + std::unordered_map> to_idx_; + std::unordered_map> type_idx_; }; } // namespace DSR diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h index c2ce36cf..ca95ed3a 100644 --- a/api/include/dsr/api/dsr_sync_engine.h +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -69,6 +69,24 @@ class SyncEngineHost virtual void update_maps_node_delete(uint64_t id, const std::optional& node) = 0; virtual void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string& type) = 0; virtual void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string& type) = 0; + + // Graph configuration queries — default impls safe for unit-test hosts. + virtual GraphSettings::LOGLEVEL get_log_level() const { return GraphSettings::LOGLEVEL::INFOL; } + virtual bool is_attribute_ignored(const std::string& /*name*/) const { return false; } + virtual bool is_node_deleted(uint64_t /*id*/) const { return false; } + + // Secondary-index traversal — default no-ops; DSRGraph overrides with cache-map reads. + virtual void for_each_incoming_edge(uint64_t /*to*/, std::function /*visitor*/) const {} + virtual void for_each_edge_of_type_cache(const std::string& /*type*/, std::function /*visitor*/) const {} + + // Signal hooks for remote apply — called by the engine after state is updated. + // Default no-ops; DSRGraph overrides to emit Qt signals. + virtual void on_remote_node_updated(uint64_t /*id*/, const std::string& /*type*/, uint32_t /*agent_id*/) {} + virtual void on_remote_node_deleted(uint64_t /*id*/, const std::optional& /*node*/, const std::vector& /*edges*/, uint32_t /*agent_id*/) {} + virtual void on_remote_edge_updated(uint64_t /*from*/, uint64_t /*to*/, const std::string& /*type*/, uint32_t /*agent_id*/) {} + virtual void on_remote_edge_deleted(uint64_t /*from*/, uint64_t /*to*/, const std::string& /*type*/, const std::optional& /*edge*/, uint32_t /*agent_id*/) {} + virtual void on_remote_node_attrs_updated(uint64_t /*id*/, const std::string& /*type*/, const std::vector& /*attrs*/, uint32_t /*agent_id*/) {} + virtual void on_remote_edge_attrs_updated(uint64_t /*from*/, uint64_t /*to*/, const std::string& /*type*/, const std::vector& /*attrs*/, uint32_t /*agent_id*/) {} }; class SyncEngine From 222ce82e028daa27ca1dbdb0cf39ca13a0cc90f4 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 19:13:39 +0200 Subject: [PATCH 17/38] refactor: simplify sync transport callbacks --- api/dsr_api.cpp | 433 ++++++++-------------- api/dsr_lww_sync_engine.cpp | 59 +-- api/include/dsr/api/dsr_api.h | 35 +- api/include/dsr/api/dsr_lww_sync_engine.h | 10 +- core/CMakeLists.txt | 1 + core/include/dsr/core/types/lww_index.h | 108 ++++++ 6 files changed, 298 insertions(+), 348 deletions(-) create mode 100644 core/include/dsr/core/types/lww_index.h diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 1c7e1341..8fe91e06 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -92,6 +92,35 @@ bool network_compatibility_or_fatal( return true; } + +template +uint32_t remote_agent_id_of(const Sample& sample) +{ + return sample.agent_id; +} + +template +bool batch_is_from_remote(const Batch& batch, uint32_t local_agent_id) +{ + return !batch.vec.empty() && remote_agent_id_of(batch.vec.front()) != local_agent_id; +} + +template +bool batch_is_compatible(const char* channel, const Batch& batch, DSR::SyncMode local_sync_mode) +{ + return !batch.vec.empty() && + network_compatibility_or_fatal(channel, batch.vec.front().protocol_version, batch.vec.front().sync_mode, local_sync_mode); +} + +inline size_t full_graph_payload_size(const DSR::OrMap& sample) +{ + return sample.m.size(); +} + +inline size_t full_graph_payload_size(const DSR::LWWGraphSnapshot& sample) +{ + return sample.nodes.size() + sample.edges.size(); +} } void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info); @@ -322,31 +351,11 @@ void DSRGraph::publish_full_graph_message(FullGraphMessage&& message, int32_t se }, std::move(message)); } -const DSRGraph::TransportProfile& DSRGraph::transport_profile() const -{ - static const TransportProfile profiles[] = { - { - &DSRGraph::make_crdt_node_subscription_functor, - &DSRGraph::make_crdt_edge_subscription_functor, - &DSRGraph::make_crdt_edge_attrs_subscription_functor, - &DSRGraph::make_crdt_node_attrs_subscription_functor, - &DSRGraph::make_crdt_fullgraph_request_functor, - }, - { - &DSRGraph::make_lww_node_subscription_functor, - &DSRGraph::make_lww_edge_subscription_functor, - &DSRGraph::make_lww_edge_attrs_subscription_functor, - &DSRGraph::make_lww_node_attrs_subscription_functor, - &DSRGraph::make_lww_fullgraph_request_functor, - }, - }; - return profiles[sync_mode_wire_value(sync_mode)]; -} - -DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_subscription_functor() +template +DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal) { auto name = "node_subscription_thread"; - return NewMessageFunctor(this, [this, name, showReceived = log_level] + return NewMessageFunctor(this, [this, channel, name, showReceived = log_level, clear_deleted_signal] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); @@ -355,71 +364,42 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_subscription_functor() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - DSR::MvregNodeMsg sample; + Sample sample; if (reader->take_next_sample(&sample, &m_info) != 0) { break; } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("DSR_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (sample.id == CLEAR_DELETED_SIGNAL) { - std::unique_lock lock(_mutex); - std::unique_lock lck_cache(_mutex_cache_maps); - deleted.clear(); - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); - }); + if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { + continue; } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); -} - -DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_subscription_functor() -{ - return NewMessageFunctor(this, [this, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::LWWNodeMsg sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("LWW_NODE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); - }); + if (clear_deleted_signal && sample.id == CLEAR_DELETED_SIGNAL) { + std::unique_lock lock(_mutex); + std::unique_lock lck_cache(_mutex_cache_maps); + deleted.clear(); + continue; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " + << m_info.sample_identity.writer_guid().entityId.value; } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); } } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } }); } -DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_subscription_functor() +template +DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor_impl(const char* channel) { auto name = "edge_subscription_thread"; - return NewMessageFunctor(this, [this, name, showReceived = log_level] + return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); @@ -428,65 +408,32 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_subscription_functor() while (true) { eprosima::fastdds::dds::SampleInfo m_info; - DSR::MvregEdgeMsg sample; + Sample sample; if (reader->take_next_sample(&sample, &m_info) != 0) { break; } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("DSR_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); - }); - } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); -} - -DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_subscription_functor() -{ - return NewMessageFunctor(this, [this, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::LWWEdgeMsg sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; + if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { + continue; } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data && sample.agent_id != agent_id) { - if (!network_compatibility_or_fatal("LWW_EDGE", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); - }); + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); } } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } }); } -DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_attrs_subscription_functor() +template +DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor_impl(const char* channel) { auto name = "edge_attrs_subscription_thread"; - return NewMessageFunctor(this, [this, name, showReceived = log_level] + return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); @@ -495,70 +442,37 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_edge_attrs_subscription_functor( while (true) { eprosima::fastdds::dds::SampleInfo m_info; - DSR::MvregEdgeAttrVec samples; + Batch samples; if (reader->take_next_sample(&samples, &m_info) != 0) { break; } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) - { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("DSR_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); - }); - } + if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { + continue; } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); -} - -DSRGraph::NewMessageFunctor DSRGraph::make_lww_edge_attrs_subscription_functor() -{ - return NewMessageFunctor(this, [this] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::LWWEdgeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; + if (!batch_is_compatible(channel, samples, sync_mode)) { + continue; } - if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("LWW_EDGE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " + << m_info.sample_identity.writer_guid().entityId.value; } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); + }); } } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } }); } -DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_attrs_subscription_functor() +template +DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor_impl(const char* channel) { auto name = "node_attrs_subscription_thread"; - return NewMessageFunctor(this, [this, name, showReceived = log_level] + return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); @@ -567,138 +481,111 @@ DSRGraph::NewMessageFunctor DSRGraph::make_crdt_node_attrs_subscription_functor( while (true) { eprosima::fastdds::dds::SampleInfo m_info; - DSR::MvregNodeAttrVec samples; + Batch samples; if (reader->take_next_sample(&samples, &m_info) != 0) { break; } if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (m_info.valid_data) { - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - if (!samples.vec.empty() and samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("DSR_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); - std::unique_lock lock(_mutex); - engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); - }); - } + if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { + continue; } - } - } - catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); -} - -DSRGraph::NewMessageFunctor DSRGraph::make_lww_node_attrs_subscription_functor() -{ - return NewMessageFunctor(this, [this] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); - try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::LWWNodeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; + if (!batch_is_compatible(channel, samples, sync_mode)) { + continue; } - if (m_info.valid_data && !samples.vec.empty() && samples.vec.at(0).agent_id != agent_id) { - const auto& first = samples.vec.front(); - if (!network_compatibility_or_fatal("LWW_NODE_ATTS", first.protocol_version, first.sync_mode, sync_mode)) { - continue; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " + << m_info.sample_identity.writer_guid().entityId.value; } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); + }); } } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } }); } -DSRGraph::NewMessageFunctor DSRGraph::make_crdt_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +template +DSRGraph::NewMessageFunctor DSRGraph::make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated) { - return NewMessageFunctor(this, [this, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + return NewMessageFunctor(this, [this, channel, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); while (true) { eprosima::fastdds::dds::SampleInfo m_info; - DSR::OrMap sample; + GraphSample sample; if (reader->take_next_sample(&sample, &m_info) != 0) { break; } if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (m_info.valid_data) { - if (!network_compatibility_or_fatal("GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (static_cast(sample.id) != graph->get_agent_id()) { - if (sample.id != -1) { - qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value - << " whith " - << sample.m.size() << " elements"; - tp.spawn_task([this, s = std::move(sample)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); - std::unique_lock lock(_mutex); - engine_->import_full_graph(FullGraphMessage{std::move(s)}); - }); - qDebug() << "Synchronized."; - sync = true; - break; - } else if (!sync && sample.to_id == agent_id) { - repeated = true; - } + if (!m_info.valid_data) { + continue; + } + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + continue; + } + if (static_cast(sample.id) != graph->get_agent_id()) { + if (sample.id != -1) { + qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value + << " whith " << full_graph_payload_size(sample) << " elements"; + tp.spawn_task([this, s = std::move(sample)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); + std::unique_lock lock(_mutex); + engine_->import_full_graph(FullGraphMessage{std::move(s)}); + }); + qDebug() << "Synchronized."; + sync = true; + break; + } else if (!sync && sample.to_id == agent_id) { + repeated = true; } } } }); } -DSRGraph::NewMessageFunctor DSRGraph::make_lww_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor() { - return NewMessageFunctor(this, [this, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) - { - [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::LWWGraphSnapshot sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (m_info.valid_data) { - if (!network_compatibility_or_fatal("LWW_GRAPH_ANSWER", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (static_cast(sample.id) != graph->get_agent_id()) { - if (sample.id != -1) { - tp.spawn_task([this, s = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->import_full_graph(FullGraphMessage{std::move(s)}); - }); - sync = true; - break; - } else if (!sync && sample.to_id == agent_id) { - repeated = true; - } - } - } - } - }); + if (sync_mode == SyncMode::LWW) { + return make_node_subscription_functor_impl("LWW_NODE"); + } + return make_node_subscription_functor_impl("DSR_NODE", true); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor() +{ + if (sync_mode == SyncMode::LWW) { + return make_edge_subscription_functor_impl("LWW_EDGE"); + } + return make_edge_subscription_functor_impl("DSR_EDGE"); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor() +{ + if (sync_mode == SyncMode::LWW) { + return make_edge_attrs_subscription_functor_impl("LWW_EDGE_ATTS"); + } + return make_edge_attrs_subscription_functor_impl("DSR_EDGE_ATTS"); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor() +{ + if (sync_mode == SyncMode::LWW) { + return make_node_attrs_subscription_functor_impl("LWW_NODE_ATTS"); + } + return make_node_attrs_subscription_functor_impl("DSR_NODE_ATTS"); +} + +DSRGraph::NewMessageFunctor DSRGraph::make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +{ + if (sync_mode == SyncMode::LWW) { + return make_fullgraph_request_functor_impl("LWW_GRAPH_ANSWER", sync, repeated); + } + return make_fullgraph_request_functor_impl("GRAPH_ANSWER", sync, repeated); } ////////////////////////////////////// @@ -1461,7 +1348,7 @@ void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::f void DSRGraph::node_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread setup"); - dsrpub_call_node = (this->*transport_profile().make_node_functor)(); + dsrpub_call_node = make_node_subscription_functor(); auto [res, sub, reader] = dsrsub_node.init(dsrparticipant.getParticipant(), dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), {sub, reader}); } @@ -1469,7 +1356,7 @@ void DSRGraph::node_subscription_thread() void DSRGraph::edge_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread setup"); - dsrpub_call_edge = (this->*transport_profile().make_edge_functor)(); + dsrpub_call_edge = make_edge_subscription_functor(); auto [res, sub, reader] = dsrsub_edge.init(dsrparticipant.getParticipant(), dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), {sub, reader}); @@ -1478,7 +1365,7 @@ void DSRGraph::edge_subscription_thread() void DSRGraph::edge_attrs_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread setup"); - dsrpub_call_edge_attrs = (this->*transport_profile().make_edge_attrs_functor)(); + dsrpub_call_edge_attrs = make_edge_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_edge_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge_attrs, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getAttEdgeTopic()->get_name(), {sub, reader}); @@ -1489,7 +1376,7 @@ void DSRGraph::edge_attrs_subscription_thread() void DSRGraph::node_attrs_subscription_thread() { CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread setup"); - dsrpub_call_node_attrs = (this->*transport_profile().make_node_attrs_functor)(); + dsrpub_call_node_attrs = make_node_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_node_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node_attrs, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getAttNodeTopic()->get_name(), {sub, reader}); @@ -1565,7 +1452,7 @@ std::pair DSRGraph::fullgraph_request_thread() CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread"); std::atomic sync{false}; std::atomic repeated{false}; - dsrpub_request_answer_call = (this->*transport_profile().make_fullgraph_request_functor)(sync, repeated); + dsrpub_request_answer_call = make_fullgraph_request_functor(sync, repeated); auto [res, sub, reader] = dsrsub_request_answer.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id(), dsrpub_request_answer_call, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), {sub, reader}); diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index ec537ad6..00968b0e 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -41,25 +41,12 @@ std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const void LWWSyncEngine::idx_insert(const EdgeKey& key) { - from_idx_[std::get<0>(key)].insert(key); - to_idx_[std::get<1>(key)].insert(key); - type_idx_[std::get<2>(key)].insert(key); + LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, key); } void LWWSyncEngine::idx_erase(const EdgeKey& key) { - if (auto it = from_idx_.find(std::get<0>(key)); it != from_idx_.end()) { - it->second.erase(key); - if (it->second.empty()) from_idx_.erase(it); - } - if (auto it = to_idx_.find(std::get<1>(key)); it != to_idx_.end()) { - it->second.erase(key); - if (it->second.empty()) to_idx_.erase(it); - } - if (auto it = type_idx_.find(std::get<2>(key)); it != type_idx_.end()) { - it->second.erase(key); - if (it->second.empty()) type_idx_.erase(it); - } + LWW::edge_index_erase(from_idx_, to_idx_, type_idx_, key); } uint64_t LWWSyncEngine::current_time_ms() const @@ -117,22 +104,7 @@ std::optional LWWSyncEngine::get_node(uint64_t id) const { auto it = nodes_.find(id); if (it == nodes_.end()) return {}; - - const auto& state = it->second; - Node out(state.agent_id, state.type); - out.id(state.id); - out.name(state.name); - for (const auto& [name, attr] : state.attrs) { - out.attrs().emplace(name, attr.value); - } - if (auto fidx = from_idx_.find(id); fidx != from_idx_.end()) { - for (const auto& key : fidx->second) { - if (auto eit = edges_.find(key); eit != edges_.end()) { - out.fano().emplace(std::pair{eit->second.to, eit->second.type}, LWW::to_user_edge(eit->second)); - } - } - } - return out; + return LWW::to_user_node(it->second, edges_, from_idx_); } std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const @@ -148,36 +120,17 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& if (!nodes_.contains(from)) { return false; } - if (auto it = from_idx_.find(from); it != from_idx_.end()) { - for (const auto& key : it->second) { - const auto& edge = edges_.at(key); - visitor(edge.to, edge.type, LWW::to_user_edge(edge)); - } - } - return true; + return LWW::for_each_edge_from(edges_, from_idx_, from, visitor); } bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { - auto it = to_idx_.find(to); - if (it == to_idx_.end()) { - return false; - } - for (const auto& key : it->second) { - const auto& edge = edges_.at(key); - visitor(edge.from, edge.type, LWW::to_user_edge(edge)); - } - return true; + return LWW::for_each_edge_to(edges_, to_idx_, to, visitor); } void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { - auto it = type_idx_.find(type); - if (it == type_idx_.end()) return; - for (const auto& key : it->second) { - const auto& edge = edges_.at(key); - visitor(edge.from, edge.to, LWW::to_user_edge(edge)); - } + LWW::for_each_edge_of_type(edges_, type_idx_, type, visitor); } size_t LWWSyncEngine::size() const diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index c6430b22..f0b48190 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -685,25 +685,22 @@ namespace DSR void operator()(eprosima::fastdds::dds::DataReader* reader) const { f(reader, graph); }; }; - struct TransportProfile { - NewMessageFunctor (DSRGraph::*make_node_functor)(); - NewMessageFunctor (DSRGraph::*make_edge_functor)(); - NewMessageFunctor (DSRGraph::*make_edge_attrs_functor)(); - NewMessageFunctor (DSRGraph::*make_node_attrs_functor)(); - NewMessageFunctor (DSRGraph::*make_fullgraph_request_functor)(std::atomic&, std::atomic&); - }; - - const TransportProfile& transport_profile() const; - NewMessageFunctor make_crdt_node_subscription_functor(); - NewMessageFunctor make_lww_node_subscription_functor(); - NewMessageFunctor make_crdt_edge_subscription_functor(); - NewMessageFunctor make_lww_edge_subscription_functor(); - NewMessageFunctor make_crdt_edge_attrs_subscription_functor(); - NewMessageFunctor make_lww_edge_attrs_subscription_functor(); - NewMessageFunctor make_crdt_node_attrs_subscription_functor(); - NewMessageFunctor make_lww_node_attrs_subscription_functor(); - NewMessageFunctor make_crdt_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); - NewMessageFunctor make_lww_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + NewMessageFunctor make_node_subscription_functor(); + NewMessageFunctor make_edge_subscription_functor(); + NewMessageFunctor make_edge_attrs_subscription_functor(); + NewMessageFunctor make_node_attrs_subscription_functor(); + NewMessageFunctor make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + + template + NewMessageFunctor make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal = false); + template + NewMessageFunctor make_edge_subscription_functor_impl(const char* channel); + template + NewMessageFunctor make_edge_attrs_subscription_functor_impl(const char* channel); + template + NewMessageFunctor make_node_attrs_subscription_functor_impl(const char* channel); + template + NewMessageFunctor make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated); //Custom function for each rtps topic class ParticipantChangeFunctor { diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index f7fa5d4e..a6ebc584 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -1,6 +1,7 @@ #pragma once #include "dsr/api/dsr_sync_engine.h" +#include "dsr/core/types/lww_index.h" #include "dsr/core/types/lww_types.h" #include @@ -59,6 +60,9 @@ class LWWSyncEngine final : public SyncEngine using NodeState = LWW::NodeState; using EdgeState = LWW::EdgeState; using EdgeKey = LWW::EdgeKey; + using FromIndex = LWW::FromIndex; + using ToIndex = LWW::ToIndex; + using TypeIndex = LWW::TypeIndex; uint64_t current_time_ms() const; uint64_t next_timestamp(); @@ -80,9 +84,9 @@ class LWWSyncEngine final : public SyncEngine std::unordered_map node_tombstones_; std::unordered_map edge_tombstones_; - std::unordered_map> from_idx_; - std::unordered_map> to_idx_; - std::unordered_map> type_idx_; + FromIndex from_idx_; + ToIndex to_idx_; + TypeIndex type_idx_; }; } // namespace DSR diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index d3d1ef86..09164253 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -20,6 +20,7 @@ target_sources(dsr_core include/dsr/core/types/user_types.h include/dsr/core/types/common_types.h include/dsr/core/types/crdt_io.h + include/dsr/core/types/lww_index.h include/dsr/core/types/translator.h include/dsr/core/types/type_checking/dsr_attr_name.h include/dsr/core/types/type_checking/dsr_edge_type.h diff --git a/core/include/dsr/core/types/lww_index.h b/core/include/dsr/core/types/lww_index.h new file mode 100644 index 00000000..c9febcfc --- /dev/null +++ b/core/include/dsr/core/types/lww_index.h @@ -0,0 +1,108 @@ +#pragma once + +#include "dsr/core/types/lww_io.h" + +#include +#include + +namespace DSR::LWW { + +using EdgeSet = std::unordered_set; +using FromIndex = std::unordered_map; +using ToIndex = std::unordered_map; +using TypeIndex = std::unordered_map; + +inline void edge_index_insert(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeKey& key) +{ + from_idx[std::get<0>(key)].insert(key); + to_idx[std::get<1>(key)].insert(key); + type_idx[std::get<2>(key)].insert(key); +} + +inline void edge_index_erase(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeKey& key) +{ + if (auto it = from_idx.find(std::get<0>(key)); it != from_idx.end()) { + it->second.erase(key); + if (it->second.empty()) { + from_idx.erase(it); + } + } + if (auto it = to_idx.find(std::get<1>(key)); it != to_idx.end()) { + it->second.erase(key); + if (it->second.empty()) { + to_idx.erase(it); + } + } + if (auto it = type_idx.find(std::get<2>(key)); it != type_idx.end()) { + it->second.erase(key); + if (it->second.empty()) { + type_idx.erase(it); + } + } +} + +template +Node to_user_node(const NodeState& state, const EdgeMap& edges, const FromIndex& from_idx) +{ + Node out(state.agent_id, state.type); + out.id(state.id); + out.name(state.name); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : state.attrs) { + attrs.emplace(name, attr.value); + } + auto fit = from_idx.find(state.id); + if (fit == from_idx.end()) { + return out; + } + auto& fano = out.fano(); + for (const auto& key : fit->second) { + if (auto eit = edges.find(key); eit != edges.end()) { + fano.emplace(std::pair{eit->second.to, eit->second.type}, to_user_edge(eit->second)); + } + } + return out; +} + +template +bool for_each_edge_from(const EdgeMap& edges, const FromIndex& from_idx, uint64_t from, Visitor&& visitor) +{ + auto it = from_idx.find(from); + if (it == from_idx.end()) { + return false; + } + for (const auto& key : it->second) { + const auto& edge = edges.at(key); + visitor(edge.to, edge.type, to_user_edge(edge)); + } + return true; +} + +template +bool for_each_edge_to(const EdgeMap& edges, const ToIndex& to_idx, uint64_t to, Visitor&& visitor) +{ + auto it = to_idx.find(to); + if (it == to_idx.end()) { + return false; + } + for (const auto& key : it->second) { + const auto& edge = edges.at(key); + visitor(edge.from, edge.type, to_user_edge(edge)); + } + return true; +} + +template +void for_each_edge_of_type(const EdgeMap& edges, const TypeIndex& type_idx, const std::string& type, Visitor&& visitor) +{ + auto it = type_idx.find(type); + if (it == type_idx.end()) { + return; + } + for (const auto& key : it->second) { + const auto& edge = edges.at(key); + visitor(edge.from, edge.to, to_user_edge(edge)); + } +} + +} // namespace DSR::LWW From 1a4ee138a7a28ea4d1aac9d8cba2ff89d56fbe20 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 19:17:19 +0200 Subject: [PATCH 18/38] refactor: clean dds participant creation --- core/rtps/dsrparticipant.cpp | 85 ++++++++++++++++++++++++++++-------- 1 file changed, 68 insertions(+), 17 deletions(-) diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 931b1e07..6cf2f92a 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -32,6 +32,60 @@ bool is_lww_mode(uint8_t sync_mode_wire) { return sync_mode_wire == 1; } + +struct TransportFamily +{ + const char* node_topic_name; + const char* edge_topic_name; + const char* node_attr_topic_name; + const char* edge_attr_topic_name; + const char* graph_request_topic_name; + const char* graph_answer_topic_name; + eprosima::fastdds::dds::TypeSupport node_type; + eprosima::fastdds::dds::TypeSupport graph_request_type; + eprosima::fastdds::dds::TypeSupport graph_answer_type; + eprosima::fastdds::dds::TypeSupport edge_type; + eprosima::fastdds::dds::TypeSupport node_attr_type; + eprosima::fastdds::dds::TypeSupport edge_attr_type; + bool cleanup_enabled{true}; +}; + +TransportFamily make_transport_family(uint8_t sync_mode_wire) +{ + if (is_lww_mode(sync_mode_wire)) { + return TransportFamily{ + "LWW_NODE", + "LWW_EDGE", + "LWW_NODE_ATTS", + "LWW_EDGE_ATTS", + "LWW_GRAPH_REQUEST", + "LWW_GRAPH_ANSWER", + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeMsg")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("GraphRequest")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWGraphSnapshot")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeMsg")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeAttrVec")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeAttrVec")), + false + }; + } + + return TransportFamily{ + "DSR_NODE", + "DSR_EDGE", + "DSR_NODE_ATTS", + "DSR_EDGE_ATTS", + "GRAPH_REQUEST", + "GRAPH_ANSWER", + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("MvregNodeMsg")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("GraphRequest")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("OrMap")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("MvregEdgeMsg")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("MvregNodeAttrVec")), + eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("MvregEdgeAttrVec")), + true + }; +} } DSRParticipant::DSRParticipant() : mp_participant(nullptr), @@ -59,7 +113,8 @@ std::tuple DSRParticipant::ini { domain_id_ = domain_id; sync_mode_wire_ = sync_mode_wire; - cleanup_enabled_ = !is_lww_mode(sync_mode_wire); + auto family = make_transport_family(sync_mode_wire); + cleanup_enabled_ = family.cleanup_enabled; // Create RTPSParticipant DomainParticipantQos PParam; PParam.name(("Participant_" + std::to_string(agent_id)+ " ( " + agent_name + " )").data() ); @@ -117,16 +172,12 @@ std::tuple DSRParticipant::ini { qFatal("Could not create particpant after 5 attemps"); } - - - if (is_lww_mode(sync_mode_wire)) { - dsrgraphType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeMsg")); - graphrequestType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("GraphRequest")); - graphRequestAnswerType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWGraphSnapshot")); - dsrEdgeType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeMsg")); - dsrNodeAttrType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWNodeAttrVec")); - dsrEdgeAttrType = eprosima::fastdds::dds::TypeSupport(new CRDTPubSubType("LWWEdgeAttrVec")); - } + dsrgraphType = std::move(family.node_type); + graphrequestType = std::move(family.graph_request_type); + graphRequestAnswerType = std::move(family.graph_answer_type); + dsrEdgeType = std::move(family.edge_type); + dsrNodeAttrType = std::move(family.node_attr_type); + dsrEdgeAttrType = std::move(family.edge_attr_type); //Register types dsrgraphType.register_type(mp_participant); @@ -138,12 +189,12 @@ std::tuple DSRParticipant::ini dsrEdgeAttrType.register_type(mp_participant); //Create topics - topic_node = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_NODE" : "DSR_NODE", dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_EDGE" : "DSR_EDGE", dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_node_att = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_NODE_ATTS" : "DSR_NODE_ATTS", dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_edge_att = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_EDGE_ATTS" : "DSR_EDGE_ATTS", dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph_request = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_GRAPH_REQUEST" : "GRAPH_REQUEST", graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); - topic_graph = mp_participant->create_topic(is_lww_mode(sync_mode_wire) ? "LWW_GRAPH_ANSWER" : "GRAPH_ANSWER", graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node = mp_participant->create_topic(family.node_topic_name, dsrgraphType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge = mp_participant->create_topic(family.edge_topic_name, dsrEdgeType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_node_att = mp_participant->create_topic(family.node_attr_topic_name, dsrNodeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_edge_att = mp_participant->create_topic(family.edge_attr_topic_name, dsrEdgeAttrType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph_request = mp_participant->create_topic(family.graph_request_topic_name, graphrequestType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); + topic_graph = mp_participant->create_topic(family.graph_answer_topic_name, graphRequestAnswerType.get_type_name(), eprosima::fastdds::dds::TOPIC_QOS_DEFAULT); return std::make_tuple(true, mp_participant); } From 2efaa394fcad70db1299298964141810ef1faa2d Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Wed, 22 Apr 2026 21:23:26 +0200 Subject: [PATCH 19/38] refactor: align sync backends and lww runtime paths --- api/dsr_api.cpp | 9 +- api/dsr_crdt_sync_engine.cpp | 111 ++++++++++++++++---- api/dsr_lww_sync_engine.cpp | 112 ++++++++++++++++++--- api/include/dsr/api/dsr_api.h | 93 ++++++++++++----- api/include/dsr/api/dsr_crdt_sync_engine.h | 2 + api/include/dsr/api/dsr_lww_sync_engine.h | 4 + api/include/dsr/api/dsr_sync_engine.h | 21 ++++ core/include/dsr/core/traits.h | 8 +- core/rtps/dsrparticipant.cpp | 6 +- python-wrapper/python_api.cpp | 20 +++- 10 files changed, 325 insertions(+), 61 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 8fe91e06..e35b0eff 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -1029,9 +1029,14 @@ std::map DSRGraph::getCopy() const ///// CORE ////////////////////////////////////////////////////////////////////////////// -const CRDTNode* DSRGraph::get_node_ptr_(uint64_t id) const +bool DSRGraph::with_node_attrs_(uint64_t id, const SyncEngine::NodeAttrsVisitor& visitor) const { - return crdt_engine().get_node_ptr(id); + return engine_->with_node_attrs(id, visitor); +} + +bool DSRGraph::with_node_view_(uint64_t id, const SyncEngine::NodeViewVisitor& visitor) const +{ + return engine_->with_node_view(id, visitor); } std::optional DSRGraph::get_node_level(const Node &n) diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 17a3c85c..29bc6bf6 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -26,6 +26,40 @@ bool protocol_version_matches( "local:", DSR::DSR_PROTOCOL_VERSION); return false; } + +class CRDTNodeAttrsView final : public SyncEngine::NodeAttrsView +{ +public: + explicit CRDTNodeAttrsView(const std::map>& attrs) + : attrs_(attrs) {} + + const Attribute* find(const std::string& name) const override + { + if (auto it = attrs_.find(name); it != attrs_.end() && !it->second.empty()) { + return &it->second.read_reg(); + } + return nullptr; + } + +private: + const std::map>& attrs_; +}; + +class CRDTNodeView final : public SyncEngine::NodeView +{ +public: + explicit CRDTNodeView(const CRDTNode& node) + : node_(node), attrs_(node.attrs()) {} + + uint64_t id() const override { return node_.id(); } + const std::string& type() const override { return node_.type(); } + const std::string& name() const override { return node_.name(); } + const SyncEngine::NodeAttrsView& attrs() const override { return attrs_; } + +private: + const CRDTNode& node_; + CRDTNodeAttrsView attrs_; +}; } CRDTSyncEngine::CRDTSyncEngine(SyncEngineHost& host) @@ -70,6 +104,26 @@ std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const s return {}; } +bool CRDTSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + CRDTNodeAttrsView attrs(node->attrs()); + visitor(attrs); + return true; + } + return false; +} + +bool CRDTSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + CRDTNodeView view(*node); + visitor(view); + return true; + } + return false; +} + bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const { if (const auto* node = get_node_ptr(from); node != nullptr) { @@ -114,8 +168,13 @@ size_t CRDTSyncEngine::size() const std::map CRDTSyncEngine::snapshot() const { + const auto log_level = host_.get_log_level(); std::map out; for (const auto& [id, reg] : nodes_) { + if (reg.empty()) { + DSR_LOG_WARNING_L(log_level, "[CRDT] snapshot skipping empty node register", id); + continue; + } out.emplace(id, Node(reg.read_reg())); } return out; @@ -342,6 +401,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR uint64_t id = node.id(); host_.update_maps_node_insert(Node(node)); auto delta = nodes_[id].write(std::move(node)); + nodes_[id].join(mvreg(delta)); return {true, crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta))}; } return {false, {}}; @@ -361,6 +421,7 @@ std::tuple> CRDTSyncEngine::update_node_ra auto& attr_reg = iter.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); + attr_reg.join(mvreg(delta)); atts_deltas.vec.emplace_back( crdt_node_attr_to_msg(host_.local_agent_id(), node.id(), node.id(), k, std::move(delta))); } @@ -399,6 +460,7 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) deleted_edges.emplace_back(v.second.read_reg()); } auto delta = nodes_[id].reset(); + nodes_.erase(id); MvregNodeMsg delta_remove = crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta)); { std::vector> incoming; @@ -455,6 +517,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 auto& attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); + attr_reg.join(mvreg(delta)); atts_deltas.vec.emplace_back( crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type(), k, std::move(delta))); } @@ -475,7 +538,9 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 } else { std::string att_type = attrs.type(); - auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs)); + auto& edge_reg = node.fano()[{to, attrs.type()}]; + auto delta = edge_reg.write(std::move(attrs)); + edge_reg.join(mvreg(delta)); host_.update_maps_edge_insert(from, to, att_type); return {true, crdt_edge_to_msg(host_.local_agent_id(), from, to, std::move(att_type), std::move(delta)), {}}; } @@ -962,22 +1027,25 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) std::optional nd = (it != nodes_.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; id = k; - if (!host_.is_node_deleted(k)) { - if (it == nodes_.end()) { - it = nodes_.emplace(k, mvreg{}).first; - } - it->second.join(std::move(mv)); - if (mv_empty or it->second.empty()) { - std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; - host_.update_maps_node_delete(k, nd_user); - updates.emplace_back(false, k, "", std::nullopt, std::nullopt); - delete_unprocessed_deltas(); - } else { - const auto& reg = it->second.read_reg(); - host_.update_maps_node_insert(Node(reg)); - updates.emplace_back(true, k, reg.type(), nd, reg); - consume_unprocessed_deltas(); - } + if (host_.is_node_deleted(k)) { + nodes_.erase(k); + delete_unprocessed_deltas(); + continue; + } + if (it == nodes_.end()) { + it = nodes_.emplace(k, mvreg{}).first; + } + it->second.join(std::move(mv)); + if (mv_empty or it->second.empty()) { + std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; + host_.update_maps_node_delete(k, nd_user); + updates.emplace_back(false, k, "", std::nullopt, std::nullopt); + delete_unprocessed_deltas(); + } else { + const auto& reg = it->second.read_reg(); + host_.update_maps_node_insert(Node(reg)); + updates.emplace_back(true, k, reg.type(), nd, reg); + consume_unprocessed_deltas(); } } } @@ -1007,13 +1075,22 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } } } + + std::erase_if(nodes_, [](const auto& item) { + return item.second.empty(); + }); } std::map CRDTSyncEngine::export_mvreg_map() const { CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::export_mvreg_map"); + const auto log_level = host_.get_log_level(); std::map m; for (const auto& kv : nodes_) { + if (kv.second.empty()) { + DSR_LOG_WARNING_L(log_level, "[CRDT] export skipping empty node register", kv.first); + continue; + } MvregNodeMsg msg; msg.dk = kv.second; msg.id = kv.first; diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 00968b0e..1cd378d1 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -9,6 +9,63 @@ using DSR::LWW::edge_key; using DSR::LWW::is_newer; using DSR::LWW::version_of; +namespace { +template +std::vector collect_changed_attr_names(const AttrMap& before, const AttrMap& after) +{ + std::vector changed; + changed.reserve(std::max(before.size(), after.size())); + + for (const auto& [name, after_attr] : after) { + const auto before_it = before.find(name); + if (before_it == before.end() || !(before_it->second.value == after_attr.value)) { + changed.emplace_back(name); + } + } + for (const auto& [name, _] : before) { + if (!after.contains(name)) { + changed.emplace_back(name); + } + } + + return changed; +} + +class LWWNodeAttrsView final : public SyncEngine::NodeAttrsView +{ +public: + explicit LWWNodeAttrsView(const std::map& attrs) + : attrs_(attrs) {} + + const Attribute* find(const std::string& name) const override + { + if (auto it = attrs_.find(name); it != attrs_.end()) { + return &it->second.value; + } + return nullptr; + } + +private: + const std::map& attrs_; +}; + +class LWWNodeView final : public SyncEngine::NodeView +{ +public: + explicit LWWNodeView(const LWW::NodeState& node) + : node_(node), attrs_(node.attrs) {} + + uint64_t id() const override { return node_.id; } + const std::string& type() const override { return node_.type; } + const std::string& name() const override { return node_.name; } + const SyncEngine::NodeAttrsView& attrs() const override { return attrs_; } + +private: + const LWW::NodeState& node_; + LWWNodeAttrsView attrs_; +}; +} + LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, uint64_t tombstone_window_ms) : host_(host), tombstone_window_ms_(tombstone_window_ms) @@ -115,11 +172,34 @@ std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const st return {}; } +bool LWWSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + LWWNodeAttrsView attrs(node->attrs); + visitor(attrs); + return true; + } + return false; +} + +bool LWWSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) const +{ + if (const auto* node = get_node_ptr(id); node != nullptr) { + LWWNodeView view(*node); + visitor(view); + return true; + } + return false; +} + bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const { if (!nodes_.contains(from)) { return false; } + if (auto it = from_idx_.find(from); it == from_idx_.end()) { + return true; + } return LWW::for_each_edge_from(edges_, from_idx_, from, visitor); } @@ -196,14 +276,7 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) it->second.agent_id = host_.local_agent_id(); std::map next_attrs = LWW::to_attr_state_map(node.attrs(), version); - for (const auto& [name, _] : node.attrs()) { - effect.changed_attributes.emplace_back(name); - } - for (const auto& [name, _] : it->second.attrs) { - if (!next_attrs.contains(name)) { - effect.changed_attributes.emplace_back(name); - } - } + effect.changed_attributes = collect_changed_attr_names(it->second.attrs, next_attrs); it->second.attrs = std::move(next_attrs); host_.update_maps_node_delete(node.id(), old_node); @@ -263,11 +336,17 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) } auto key = edge_key(edge.from(), edge.to(), edge.type()); - edges_[key] = LWW::to_edge_state(edge, version, host_.local_agent_id()); - idx_insert(key); // idempotent for updates - for (const auto& [name, _] : edge.attrs()) { - effect.changed_attributes.emplace_back(name); + auto next_state = LWW::to_edge_state(edge, version, host_.local_agent_id()); + if (const auto old_it = edges_.find(key); old_it != edges_.end()) { + effect.changed_attributes = collect_changed_attr_names(old_it->second.attrs, next_state.attrs); + } else { + effect.changed_attributes.reserve(next_state.attrs.size()); + for (const auto& [name, _] : next_state.attrs) { + effect.changed_attributes.emplace_back(name); + } } + edges_[key] = std::move(next_state); + idx_insert(key); // idempotent for updates edge_tombstones_.erase(key); host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); effect.applied = true; @@ -540,3 +619,12 @@ std::optional LWWSyncEngine::export_edge_delta(uint64_t from, uint64 } return {}; } + +const LWW::NodeState* LWWSyncEngine::get_node_ptr(uint64_t id) const +{ + auto it = nodes_.find(id); + if (it != nodes_.end()) { + return &it->second; + } + return nullptr; +} diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index f0b48190..b31eef45 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -173,6 +173,7 @@ namespace DSR const auto &av = [&]() -> const DSR::Attribute& { if constexpr (node_or_edge) return value->second; + else if constexpr (lww_node_or_edge) return value->value; else return value->second.read_reg(); }(); @@ -209,6 +210,44 @@ namespace DSR } } + template + inline std::optional get_attrib_by_name(const Attribute &av) + requires(is_attr_name) { + using name_type = std::remove_cv_t>>>; + + if constexpr (std::is_same_v< name_type, float>) + return av.fl(); + else if constexpr (std::is_same_v< name_type, double>) + return av.dob(); + else if constexpr (std::is_same_v< name_type, std::string>) + return std::cref(av.str()); + else if constexpr (std::is_same_v< name_type, std::int32_t>) + return av.dec(); + else if constexpr (std::is_same_v< name_type, std::uint32_t>) + return av.uint(); + else if constexpr (std::is_same_v< name_type, std::uint64_t>) + return av.uint64(); + else if constexpr (std::is_same_v< name_type, bool>) + return av.bl(); + else if constexpr (std::is_same_v< name_type, std::vector>) + return std::cref(av.float_vec()); + else if constexpr (std::is_same_v< name_type, std::vector>) + return std::cref(av.byte_vec()); + else if constexpr (std::is_same_v< name_type, std::vector>) + return std::cref(av.u64_vec()); + else if constexpr (std::is_same_v< name_type, std::array>) + return std::cref(av.vec2()); + else if constexpr (std::is_same_v< name_type, std::array>) + return std::cref(av.vec3()); + else if constexpr (std::is_same_v< name_type, std::array>) + return std::cref(av.vec4()); + else if constexpr (std::is_same_v< name_type, std::array>) + return std::cref(av.vec6()); + else { + []() { static_assert(flag, "Unreachable"); }(); + } + } + template inline std::optional>> get_attrib_by_name(uint64_t id) @@ -216,17 +255,20 @@ namespace DSR { using ret_type = std::remove_cvref_t>; std::shared_lock lock(_mutex); - if (const auto* n = get_node_ptr_(id); n != nullptr) { - auto tmp = get_attrib_by_name(*n); - if (tmp.has_value()) - { - if constexpr(is_reference_wrapper::value) { - return ret_type{tmp.value().get()}; - } else { - return tmp; + std::optional out; + with_node_attrs_(id, [&](const SyncEngine::NodeAttrsView& attrs) { + if (const auto* attr = attrs.find(name::attr_name.data()); attr != nullptr) { + auto tmp = get_attrib_by_name(*attr); + if (tmp.has_value()) { + if constexpr(is_reference_wrapper::value) { + out = tmp.value().get(); + } else { + out = tmp; + } } } - } + }); + if (out.has_value()) return out; return {}; } @@ -259,23 +301,27 @@ namespace DSR { using ret_type = std::tuple>> ...>; std::shared_lock lock(_mutex); - if (const auto* node = get_node_ptr_(id); node != nullptr) - { + std::optional out; + with_node_view_(id, [&](const SyncEngine::NodeView& node_view) { + const auto& attrs_view = node_view.attrs(); auto get_by_name = [&](n* dummy) -> std::optional>> { - auto tmp = get_attrib_by_name(*node); - if (tmp.has_value()) - { - if constexpr(is_reference_wrapper::value) { - return tmp.value().get(); - } else { - return tmp; + if (const auto* attr = attrs_view.find(n::attr_name.data()); attr != nullptr) { + auto tmp = get_attrib_by_name(*attr); + if (tmp.has_value()) + { + if constexpr(is_reference_wrapper::value) { + return tmp.value().get(); + } else { + return tmp; + } } - } else return {}; + } + return {}; }; - - return ret_type(std::move(get_by_name(static_cast(nullptr))) ...); - } + out = ret_type(std::move(get_by_name(static_cast(nullptr))) ...); + }); + if (out.has_value()) return *out; constexpr auto return_nullopt = [](n* dummy) { return std::optional>>{}; }; return ret_type( return_nullopt(static_cast(nullptr)) ...); } @@ -658,7 +704,8 @@ namespace DSR ////////////////////////////////////////////////////////////////////////// // Non-blocking graph operations ////////////////////////////////////////////////////////////////////////// - const CRDTNode* get_node_ptr_(uint64_t id) const; + bool with_node_attrs_(uint64_t id, const SyncEngine::NodeAttrsVisitor& visitor) const; + bool with_node_view_(uint64_t id, const SyncEngine::NodeViewVisitor& visitor) const; void publish_node_message(const NodeDeltaMessage &message); void publish_node_attr_batch(const NodeAttrDeltaBatchMessage &message); void publish_edge_message(const EdgeDeltaMessage &message); diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index 20efe2e1..bcce62bc 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -27,6 +27,8 @@ class CRDTSyncEngine final : public SyncEngine std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + bool with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const override; + bool with_node_view(uint64_t id, const NodeViewVisitor& visitor) const override; bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const override; bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const override; void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const override; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index a6ebc584..fcee3908 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -30,6 +30,8 @@ class LWWSyncEngine final : public SyncEngine std::optional get_node(uint64_t id) const override; std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const override; + bool with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const override; + bool with_node_view(uint64_t id, const NodeViewVisitor& visitor) const override; bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const override; bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const override; void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const override; @@ -64,6 +66,8 @@ class LWWSyncEngine final : public SyncEngine using ToIndex = LWW::ToIndex; using TypeIndex = LWW::TypeIndex; + const LWW::NodeState* get_node_ptr(uint64_t id) const; + uint64_t current_time_ms() const; uint64_t next_timestamp(); void prune_tombstones(uint64_t now); diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h index ca95ed3a..470c8805 100644 --- a/api/include/dsr/api/dsr_sync_engine.h +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -92,9 +92,28 @@ class SyncEngineHost class SyncEngine { public: + class NodeAttrsView + { + public: + virtual ~NodeAttrsView() = default; + virtual const Attribute* find(const std::string& name) const = 0; + }; + + class NodeView + { + public: + virtual ~NodeView() = default; + virtual uint64_t id() const = 0; + virtual const std::string& type() const = 0; + virtual const std::string& name() const = 0; + virtual const NodeAttrsView& attrs() const = 0; + }; + using OutgoingEdgeVisitor = std::function; using IncomingEdgeVisitor = std::function; using TypedEdgeVisitor = std::function; + using NodeAttrsVisitor = std::function; + using NodeViewVisitor = std::function; virtual ~SyncEngine() = default; @@ -103,6 +122,8 @@ class SyncEngine virtual std::optional get_node(uint64_t id) const = 0; virtual std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const = 0; + virtual bool with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const = 0; + virtual bool with_node_view(uint64_t id, const NodeViewVisitor& visitor) const = 0; virtual bool for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const = 0; virtual bool for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const = 0; virtual void for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const = 0; diff --git a/core/include/dsr/core/traits.h b/core/include/dsr/core/traits.h index b1766fd6..877f0026 100644 --- a/core/include/dsr/core/traits.h +++ b/core/include/dsr/core/traits.h @@ -16,6 +16,10 @@ namespace DSR { class Edge; class CRDTNode; class CRDTEdge; + namespace LWW { + class NodeState; + class EdgeState; + }; }; @@ -48,11 +52,13 @@ concept allowed_types = one_of::value; template -concept any_node_or_edge = one_of::value;; +concept any_node_or_edge = one_of::value;; template concept node_or_edge = one_of::value;; +template +concept lww_node_or_edge = one_of::value; template concept crdt_node_or_edge = one_of::value;; diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 6cf2f92a..0c046cd9 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -206,9 +206,9 @@ eprosima::fastdds::dds::DomainParticipant *DSRParticipant::getParticipant() void DSRParticipant::remove_participant_and_entities() { - if (!cleanup_enabled_) { - return; - } + //if (!cleanup_enabled_) { + // return; + //} if (mp_participant != nullptr) { diff --git a/python-wrapper/python_api.cpp b/python-wrapper/python_api.cpp index c0e7f6c4..90d110f9 100644 --- a/python-wrapper/python_api.cpp +++ b/python-wrapper/python_api.cpp @@ -152,6 +152,11 @@ PYBIND11_MAKE_OPAQUE(std::map) PYBIND11_MODULE(pydsr, m) { + py::enum_(m, "SyncMode") + .value("CRDT", SyncMode::CRDT) + .value("LWW", SyncMode::LWW) + .export_values(); + py::bind_map, Edge>>(m, "MapStringEdge"); py::bind_dsr_map>(m, "MapStringAttribute"); @@ -575,12 +580,21 @@ PYBIND11_MODULE(pydsr, m) { py::class_(m, "DSRGraph") .def(py::init([&](int root, const std::string &name, int id, const std::string &dsr_input_file = "", - bool all_same_host = true, int8_t domain_id = 0) -> std::unique_ptr { + bool all_same_host = true, int8_t domain_id = 0, + SyncMode sync_mode = SyncMode::CRDT) -> std::unique_ptr { local_agent_id = id; - auto g = std::make_unique(root, name, id, dsr_input_file, all_same_host, domain_id, SignalMode::Queue); + GraphSettings settings; + settings.agent_id = id; + settings.graph_name = name; + settings.input_file = dsr_input_file; + settings.same_host = all_same_host; + settings.domain_id = domain_id; + settings.signal_mode = SignalMode::Queue; + settings.sync_mode = sync_mode; + auto g = std::make_unique(settings); return g; }), "root"_a, "name"_a, "id"_a, "dsr_input_file"_a = "", - "all_same_host"_a = true, "domain_id"_a=0, py::call_guard()) + "all_same_host"_a = true, "domain_id"_a=0, "sync_mode"_a = SyncMode::CRDT, py::call_guard()) .def("get_agent_id", &DSRGraph::get_agent_id, "get agent_id") .def("get_agent_name", &DSRGraph::get_agent_name, "get agent_id") .def("get_node", [](DSRGraph &self, uint64_t id) -> std::optional { From 93ad63aaa4e5c814a134be1217705158c1d58edb Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 23 Apr 2026 12:50:26 +0200 Subject: [PATCH 20/38] refactor: changes in tests and benchmarks to support backend selection --- benchmarks/benchmark_main.cpp | 54 +++++++++++ benchmarks/core/benchmark_config.h | 21 ++++ benchmarks/core/metrics_collector.h | 1 + benchmarks/core/report_generator.h | 8 ++ benchmarks/fixtures/multi_agent_fixture.h | 22 +++-- benchmarks/python/bench_baseline_graph.py | 33 ++++--- benchmarks/python/bench_graph_operations.py | 48 +++++----- benchmarks/python/bench_signals.py | 46 +++++---- benchmarks/python/bench_utils.py | 17 ++++ benchmarks/report.py | 76 +++++++++++++-- benchmarks/run_benchmarks.py | 96 ++++++++++++++++--- python-wrapper/test/PythonAPITests.py | 67 +++++++------ tests/graph/attribute_operations.cpp | 17 +++- tests/graph/convenience_operations.cpp | 11 ++- tests/graph/edge_operations.cpp | 7 +- tests/graph/graph_operations.cpp | 5 +- tests/graph/node_operations.cpp | 12 ++- tests/synchronization/graph_signals.cpp | 33 +++++-- .../synchronization/graph_synchronization.cpp | 15 +-- tests/utils.h | 29 ++++++ 20 files changed, 472 insertions(+), 146 deletions(-) diff --git a/benchmarks/benchmark_main.cpp b/benchmarks/benchmark_main.cpp index 7321fccf..4d6cf397 100644 --- a/benchmarks/benchmark_main.cpp +++ b/benchmarks/benchmark_main.cpp @@ -5,8 +5,12 @@ #include #include #include +#include "core/benchmark_config.h" +#include #include +#include #include +#include // Custom Qt message handler to filter debug output during benchmarks static bool g_verbose = false; @@ -31,6 +35,47 @@ bool shouldPrintBenchmarkPreamble(int argc, char* argv[]) { && !hasCliFlag(argc, argv, "--list-listeners"); } +std::optional getenv_string(const char* name) { + if (const char* value = std::getenv(name); value != nullptr && *value != '\0') { + return std::string(value); + } + return std::nullopt; +} + +template +void load_env_value(const char* name, T& target) { + if (const auto value = getenv_string(name); value.has_value()) { + if constexpr (std::is_same_v) { + target = static_cast(std::stoul(*value)); + } else if constexpr (std::is_same_v) { + target = std::chrono::milliseconds(std::stoull(*value)); + } else if constexpr (std::is_same_v) { + target = std::chrono::seconds(std::stoull(*value)); + } else { + target = *value; + } + } +} + +void configureBenchmarkDefaultsFromEnv() { + using namespace DSR::Benchmark; + + auto& config = default_config(); + + if (const auto sync_mode = getenv_string("BENCH_SYNC_MODE"); sync_mode.has_value()) { + config.sync_mode = parse_sync_mode(*sync_mode); + } + + load_env_value("BENCH_WARMUP_ITERATIONS", config.warmup_iterations); + load_env_value("BENCH_MEASUREMENT_ITERATIONS", config.measurement_iterations); + load_env_value("BENCH_SYNC_WAIT_MS", config.sync_wait_time); + load_env_value("BENCH_MAX_CONVERGENCE_TIMEOUT_S", config.max_convergence_timeout); + load_env_value("BENCH_DEFAULT_AGENT_COUNT", config.default_agent_count); + load_env_value("BENCH_MAX_AGENT_COUNT", config.max_agent_count); + load_env_value("BENCH_CONCURRENT_WRITER_THREADS", config.concurrent_writer_threads); + load_env_value("BENCH_RESULTS_DIRECTORY", config.results_directory); +} + } // namespace void benchmarkMessageHandler(QtMsgType type, const QMessageLogContext& context, const QString& msg) { @@ -82,6 +127,7 @@ int main(int argc, char* argv[]) { // Initialize Qt (required for signals/slots) QCoreApplication app(argc, argv); + configureBenchmarkDefaultsFromEnv(); // Initialize Catch2 Catch::Session session; @@ -98,6 +144,14 @@ int main(int argc, char* argv[]) { std::cout << "=================================\n"; std::cout << " DSR Benchmarking Suite\n"; std::cout << "=================================\n\n"; + std::cout << "Benchmark config:\n"; + std::cout << " sync_mode = " << DSR::Benchmark::sync_mode_name(DSR::Benchmark::default_config().sync_mode) << "\n"; + std::cout << " warmup = " << DSR::Benchmark::default_config().warmup_iterations << "\n"; + std::cout << " measurements = " << DSR::Benchmark::default_config().measurement_iterations << "\n"; + std::cout << " sync_wait_ms = " << DSR::Benchmark::default_config().sync_wait_time.count() << "\n"; + std::cout << " max_conv_s = " << DSR::Benchmark::default_config().max_convergence_timeout.count() << "\n"; + std::cout << " agent_count = " << DSR::Benchmark::default_config().default_agent_count << "\n"; + std::cout << " writer_threads = " << DSR::Benchmark::default_config().concurrent_writer_threads << "\n\n"; std::cout << "Available benchmark categories:\n"; std::cout << " [BASELINE] - Curated low-noise regression baseline\n"; std::cout << " [EXTENDED] - Slower supplementary baseline coverage\n"; diff --git a/benchmarks/core/benchmark_config.h b/benchmarks/core/benchmark_config.h index 0734131e..766588e4 100644 --- a/benchmarks/core/benchmark_config.h +++ b/benchmarks/core/benchmark_config.h @@ -4,6 +4,7 @@ #include #include #include +#include namespace DSR::Benchmark { @@ -32,8 +33,28 @@ struct BenchmarkConfig { bool export_json = true; bool export_csv = true; bool verbose = false; + DSR::SyncMode sync_mode = DSR::SyncMode::CRDT; }; +inline const char* sync_mode_name(DSR::SyncMode mode) { + switch (mode) { + case DSR::SyncMode::CRDT: return "crdt"; + case DSR::SyncMode::LWW: return "lww"; + } + return "unknown"; +} + +inline DSR::SyncMode parse_sync_mode(const std::string& value) { + if (value == "lww" || value == "LWW") { + return DSR::SyncMode::LWW; + } + return DSR::SyncMode::CRDT; +} + +inline std::string sync_mode_suffix(DSR::SyncMode mode) { + return std::string("_") + sync_mode_name(mode); +} + // Default configuration singleton inline BenchmarkConfig& default_config() { static BenchmarkConfig config; diff --git a/benchmarks/core/metrics_collector.h b/benchmarks/core/metrics_collector.h index cf08f604..27bb6f9d 100644 --- a/benchmarks/core/metrics_collector.h +++ b/benchmarks/core/metrics_collector.h @@ -214,6 +214,7 @@ class MetricsCollector { result.total_duration = duration; result.metrics = metrics_; result.metadata = metadata_; + result.metadata.try_emplace("sync_mode", sync_mode_name(default_config().sync_mode)); return result; } diff --git a/benchmarks/core/report_generator.h b/benchmarks/core/report_generator.h index 6831f2ab..3b50c3a8 100644 --- a/benchmarks/core/report_generator.h +++ b/benchmarks/core/report_generator.h @@ -7,6 +7,7 @@ #include #include #include "metrics_collector.h" +#include "benchmark_config.h" namespace DSR::Benchmark { @@ -178,6 +179,13 @@ class ReportGenerator { "_" + sanitize_filename(result.timestamp); } + const auto suffix = sync_mode_suffix(default_config().sync_mode); + if (!suffix.empty() && name.size() >= suffix.size()) { + if (name.substr(name.size() - suffix.size()) != suffix) { + name += suffix; + } + } + // Remove extension if present if (name.size() > extension.size() && name.substr(name.size() - extension.size()) == extension) { diff --git a/benchmarks/fixtures/multi_agent_fixture.h b/benchmarks/fixtures/multi_agent_fixture.h index 46e9f327..86d77eaa 100644 --- a/benchmarks/fixtures/multi_agent_fixture.h +++ b/benchmarks/fixtures/multi_agent_fixture.h @@ -87,10 +87,13 @@ class MultiAgentFixture { try { agent->graph = std::make_unique( - agent->name, - agent->id, - config_file, - true + GraphSettings{ + .agent_id = agent->id, + .graph_name = agent->name, + .input_file = config_file, + .same_host = true, + .sync_mode = config_.sync_mode + } ); agents_.push_back(std::move(agent)); } catch (const std::exception& e) { @@ -111,10 +114,13 @@ class MultiAgentFixture { try { // No config file - agent receives graph from DDS agent->graph = std::make_unique( - agent->name, - agent->id, - std::string{}, - true + GraphSettings{ + .agent_id = agent->id, + .graph_name = agent->name, + .input_file = std::string{}, + .same_host = true, + .sync_mode = config_.sync_mode + } ); agents_.push_back(std::move(agent)); } catch (const std::exception& e) { diff --git a/benchmarks/python/bench_baseline_graph.py b/benchmarks/python/bench_baseline_graph.py index 7a8166ce..f0b84fe7 100644 --- a/benchmarks/python/bench_baseline_graph.py +++ b/benchmarks/python/bench_baseline_graph.py @@ -13,7 +13,7 @@ sys.path.insert(0, os.path.dirname(__file__)) -from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file +from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file, sync_modes, create_graph try: import pydsr @@ -106,25 +106,28 @@ def main(): print("=" * 60) print() - collector = MetricsCollector("python_baseline_graph") - collector.metadata["profile"] = "baseline" - - config_file = make_temp_config_file() - graph = pydsr.DSRGraph(0, "python_baseline_graph", 84, config_file) - time.sleep(0.3) - - benchmark_fixed_graph(graph, collector) - - del graph - os.unlink(config_file) - results_dir = os.environ.get( "BENCH_RESULTS_DIR", os.path.join(os.path.dirname(__file__), "..", "results"), ) os.makedirs(results_dir, exist_ok=True) - collector.export_json(os.path.join(results_dir, "python_baseline_graph.json")) - collector.export_csv(os.path.join(results_dir, "python_baseline_graph.csv")) + + for sync_label, sync_mode in sync_modes(pydsr): + collector = MetricsCollector(f"python_baseline_graph_{sync_label}") + collector.metadata["profile"] = "baseline" + collector.metadata["sync_mode"] = sync_label + + config_file = make_temp_config_file() + graph = create_graph(pydsr, f"python_baseline_graph_{sync_label}", 84, config_file, sync_mode) + time.sleep(0.3) + + benchmark_fixed_graph(graph, collector) + + del graph + os.unlink(config_file) + + collector.export_json(os.path.join(results_dir, f"python_baseline_graph_{sync_label}.json")) + collector.export_csv(os.path.join(results_dir, f"python_baseline_graph_{sync_label}.csv")) print(f"\nResults exported to {results_dir}") diff --git a/benchmarks/python/bench_graph_operations.py b/benchmarks/python/bench_graph_operations.py index 4e3412b8..05946f0a 100644 --- a/benchmarks/python/bench_graph_operations.py +++ b/benchmarks/python/bench_graph_operations.py @@ -17,7 +17,7 @@ sys.path.insert(0, os.path.dirname(__file__)) -from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file, warmup +from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file, warmup, sync_modes, create_graph try: import pydsr @@ -246,34 +246,36 @@ def main(): print("=" * 60) print() - collector = MetricsCollector("graph_operations") - - # Create graph - config_file = make_temp_config_file() - graph = pydsr.DSRGraph(0, "bench_graph_ops", 42, config_file) - time.sleep(0.5) - - print("--- Node Operations ---") - benchmark_node_operations(graph, collector) - - print("\n--- Edge Operations ---") - benchmark_edge_operations(graph, collector) - - print("\n--- Query Operations ---") - benchmark_query_operations(graph, collector) - - # Cleanup - del graph - os.unlink(config_file) - # Export results_dir = os.environ.get( "BENCH_RESULTS_DIR", os.path.join(os.path.dirname(__file__), "..", "results"), ) os.makedirs(results_dir, exist_ok=True) - collector.export_json(os.path.join(results_dir, "python_graph_operations.json")) - collector.export_csv(os.path.join(results_dir, "python_graph_operations.csv")) + + for sync_label, sync_mode in sync_modes(pydsr): + print(f"--- Backend: {sync_label} ---") + collector = MetricsCollector(f"graph_operations_{sync_label}") + collector.metadata["sync_mode"] = sync_label + + config_file = make_temp_config_file() + graph = create_graph(pydsr, f"bench_graph_ops_{sync_label}", 42, config_file, sync_mode) + time.sleep(0.5) + + print("--- Node Operations ---") + benchmark_node_operations(graph, collector) + + print("\n--- Edge Operations ---") + benchmark_edge_operations(graph, collector) + + print("\n--- Query Operations ---") + benchmark_query_operations(graph, collector) + + del graph + os.unlink(config_file) + + collector.export_json(os.path.join(results_dir, f"python_graph_operations_{sync_label}.json")) + collector.export_csv(os.path.join(results_dir, f"python_graph_operations_{sync_label}.csv")) print(f"\nResults exported to {results_dir}") diff --git a/benchmarks/python/bench_signals.py b/benchmarks/python/bench_signals.py index 0249787c..144c5900 100644 --- a/benchmarks/python/bench_signals.py +++ b/benchmarks/python/bench_signals.py @@ -17,7 +17,7 @@ sys.path.insert(0, os.path.dirname(__file__)) -from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file +from bench_utils import LatencyTracker, MetricsCollector, make_temp_config_file, sync_modes, create_graph try: import pydsr @@ -158,32 +158,36 @@ def main(): print("=" * 60) print() - collector = MetricsCollector("signals") - - config_file = make_temp_config_file() - graph = pydsr.DSRGraph(0, "bench_signals", 42, config_file) - time.sleep(0.5) - - print("--- Signal Callback Latency ---") - benchmark_signal_callback_latency(graph, collector) - - print("\n--- Signal Throughput ---") - benchmark_signal_throughput(graph, collector) - - print("\n--- Multiple Handlers Impact ---") - benchmark_multiple_handlers(graph, collector) - - del graph - os.unlink(config_file) - # Export results_dir = os.environ.get( "BENCH_RESULTS_DIR", os.path.join(os.path.dirname(__file__), "..", "results"), ) os.makedirs(results_dir, exist_ok=True) - collector.export_json(os.path.join(results_dir, "python_signals.json")) - collector.export_csv(os.path.join(results_dir, "python_signals.csv")) + + for sync_label, sync_mode in sync_modes(pydsr): + print(f"--- Backend: {sync_label} ---") + collector = MetricsCollector(f"signals_{sync_label}") + collector.metadata["sync_mode"] = sync_label + + config_file = make_temp_config_file() + graph = create_graph(pydsr, f"bench_signals_{sync_label}", 42, config_file, sync_mode) + time.sleep(0.5) + + print("--- Signal Callback Latency ---") + benchmark_signal_callback_latency(graph, collector) + + print("\n--- Signal Throughput ---") + benchmark_signal_throughput(graph, collector) + + print("\n--- Multiple Handlers Impact ---") + benchmark_multiple_handlers(graph, collector) + + del graph + os.unlink(config_file) + + collector.export_json(os.path.join(results_dir, f"python_signals_{sync_label}.json")) + collector.export_csv(os.path.join(results_dir, f"python_signals_{sync_label}.csv")) print(f"\nResults exported to {results_dir}") diff --git a/benchmarks/python/bench_utils.py b/benchmarks/python/bench_utils.py index c2f60f4c..b9d260e4 100644 --- a/benchmarks/python/bench_utils.py +++ b/benchmarks/python/bench_utils.py @@ -239,6 +239,23 @@ def make_temp_config_file() -> str: return path +def sync_modes(pydsr_module): + requested = os.environ.get("BENCH_SYNC_MODE", "both").lower() + modes = { + "crdt": [("crdt", pydsr_module.SyncMode.CRDT)], + "lww": [("lww", pydsr_module.SyncMode.LWW)], + "both": [ + ("crdt", pydsr_module.SyncMode.CRDT), + ("lww", pydsr_module.SyncMode.LWW), + ], + } + return modes.get(requested, modes["both"]) + + +def create_graph(pydsr_module, name: str, agent_id: int, config_file: str, sync_mode): + return pydsr_module.DSRGraph(0, name, agent_id, config_file, True, 0, sync_mode) + + def warmup(func: Callable, iterations: int = 10): """Run warmup iterations.""" for _ in range(iterations): diff --git a/benchmarks/report.py b/benchmarks/report.py index fda994f0..7271cdae 100644 --- a/benchmarks/report.py +++ b/benchmarks/report.py @@ -5,6 +5,7 @@ Single run: python report.py # latest run python report.py --run 20260314T153000 + python report.py --run 20260314T153000 --report-name lww_vs_crdt Compare two runs: python report.py --run 20260314T153000 --baseline 20260313T090000 @@ -95,13 +96,63 @@ def resolve_run_dir(run_id: str, results_root: str) -> str: raise FileNotFoundError(f"Run directory not found for id '{run_id}'") +def sanitize_report_name(name: str) -> str: + """Return a filesystem-safe report basename without an html extension.""" + cleaned = [] + for ch in name.strip(): + if ch.isalnum() or ch in ("-", "_", "."): + cleaned.append(ch) + elif ch.isspace(): + cleaned.append("_") + basename = "".join(cleaned).strip("._") + if basename.lower().endswith(".html"): + basename = basename[:-5] + if not basename: + raise ValueError("--report-name must contain at least one letter, number, dash, underscore, or dot") + return basename + + +def resolve_output_path(run_dir: str, output: Optional[str], report_name: Optional[str]) -> str: + if output and report_name: + raise ValueError("--output and --report-name are mutually exclusive") + if output: + return output + if report_name: + return os.path.join(run_dir, f"{sanitize_report_name(report_name)}.html") + return os.path.join(run_dir, "report.html") + + _UNIT_TO_NS = {"ns": 1, "us": 1_000, "µs": 1_000, "ms": 1_000_000, "s": 1_000_000_000} +SYNC_MODE_SUFFIXES = ("_crdt", "_lww") + + def _to_ns(value: float, unit: str) -> float: return value * _UNIT_TO_NS.get(unit.strip(), 1) +def comparison_benchmark_name(bench: dict) -> str: + """Return a stable benchmark identity for cross-sync-mode comparisons.""" + name = bench.get("benchmark_name", bench.get("_source_file", "")) + metadata = bench.get("metadata", {}) or {} + sync_mode = str(metadata.get("sync_mode", "")).strip().lower() + suffixes = [f"_{sync_mode}"] if sync_mode else [] + suffixes.extend(s for s in SYNC_MODE_SUFFIXES if s not in suffixes) + for suffix in suffixes: + if suffix and name.endswith(suffix): + return name[:-len(suffix)] + return name + + +def metric_tag_suffix(tags: dict) -> str: + """Build a deterministic suffix for tags that identify repeated metrics.""" + preferred = ("graph_size", "num_threads", "threads", "agents", "scale_factor", "num_handlers") + keys = [k for k in preferred if k in tags] + keys.extend(sorted(k for k in tags if k not in preferred and k != "scale_dim")) + return "_".join(f"{k}={tags[k]}" for k in keys) + + def infer_profile(bench: dict, metric: Optional[dict] = None) -> str: metadata = bench.get("metadata", {}) or {} meta_profile = str(metadata.get("profile", "")).strip().lower() @@ -134,6 +185,7 @@ def flatten_metrics(bench_files: list) -> tuple[list, list]: latency_keys: set = set() # (bench_name, metric_name) pairs with real latency data for bench in bench_files: bench_name = bench.get("benchmark_name", bench["_source_file"]) + bench_key = comparison_benchmark_name(bench) lang = bench.get("_lang", "python") for m in bench.get("metrics", []): add = m.get("additional", {}) @@ -146,13 +198,13 @@ def flatten_metrics(bench_files: list) -> tuple[list, list]: # differentiates them (e.g. graph_size) so each row is unique. metric_name = m["name"] if tags: - tag_suffix = "_".join(f"{k}={v}" for k, v in tags.items() - if k in ("graph_size", "num_threads", "threads", "scale_factor")) + tag_suffix = metric_tag_suffix(tags) if tag_suffix: metric_name = f"{metric_name}@{tag_suffix}" entry = { "benchmark": bench_name, + "benchmark_key": bench_key, "metric": metric_name, "lang": lang, "profile": profile, @@ -173,7 +225,7 @@ def flatten_metrics(bench_files: list) -> tuple[list, list]: "has_percentiles": True, }) latency.append(entry) - latency_keys.add((bench_name, metric_name)) + latency_keys.add((bench_key, metric_name)) elif category == "throughput": entry.update({ "ops_per_sec": m["value"], @@ -184,7 +236,7 @@ def flatten_metrics(bench_files: list) -> tuple[list, list]: elif category == "scalability" and unit in _UNIT_TO_NS: # Only promote scalability entries that have no proper latency # counterpart — avoids duplicates and preserves percentile data. - if (bench_name, metric_name) in latency_keys: + if (bench_key, metric_name) in latency_keys: continue mean_ns = _to_ns(m["value"], unit) entry.update({ @@ -1307,7 +1359,7 @@ def generate_html( // Deduplicate for chart (first-seen per key) const seenChart = new Set(), chartItems = []; for (const m of langLat) {{ - const key = m.benchmark + '/' + m.metric; + const key = (m.benchmark_key || m.benchmark) + '/' + m.metric; const b = bLatMap[key]; if (b && !seenChart.has(key)) {{ seenChart.add(key); @@ -1329,7 +1381,7 @@ def generate_html( ` : ''; const latRows = langLat.map(m => {{ - const b = bLatMap[m.benchmark+'/'+m.metric]; + const b = bLatMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; if (!b) return `${{m.benchmark}}${{m.metric}}no baseline`; const pct = ((m.mean_ns - b.mean_ns) / b.mean_ns) * 100; const p99pct = (m.has_percentiles && b.has_percentiles && b.p99_ns) ? ((m.p99_ns - b.p99_ns) / b.p99_ns) * 100 : null; @@ -1344,7 +1396,7 @@ def generate_html( }}).join(''); const thrRows = langThr.map(m => {{ - const b = bThrMap[m.benchmark+'/'+m.metric]; + const b = bThrMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; if (!b) return `${{m.benchmark}}${{m.metric}}no baseline`; const pct = ((m.ops_per_sec - b.ops_per_sec) / b.ops_per_sec) * 100; return ` @@ -1395,8 +1447,8 @@ def generate_html( const el = document.getElementById('tab-compare'); if (!el || !COMPARING) return; - const bLatMap = Object.fromEntries(B_LAT.map(m => [m.benchmark+'/'+m.metric, m])); - const bThrMap = Object.fromEntries(B_THR.map(m => [m.benchmark+'/'+m.metric, m])); + const bLatMap = Object.fromEntries(B_LAT.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); + const bThrMap = Object.fromEntries(B_THR.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); const pySection = buildLangSection('python', LAT, bLatMap, THR, bThrMap); const cppSection = buildLangSection('cpp', LAT, bLatMap, THR, bThrMap); @@ -1463,6 +1515,7 @@ def main(): parser.add_argument("--baseline", "-b", help="Run ID to compare against") parser.add_argument("--results-root", default=DEFAULT_RESULTS_ROOT) parser.add_argument("--output", "-o", help="Output HTML file (default: /report.html)") + parser.add_argument("--report-name", help="Named HTML report in the run directory, e.g. lww_vs_crdt -> lww_vs_crdt.html") parser.add_argument("--list", action="store_true", help="List available runs") args = parser.parse_args() @@ -1506,7 +1559,10 @@ def main(): baseline_files = load_run_metrics(b_dir) print(f"Baseline: {len(baseline_files)} file(s) from run '{baseline_info.get('id', b_dir)}'") - output_path = args.output or os.path.join(run_dir, "report.html") + try: + output_path = resolve_output_path(run_dir, args.output, args.report_name) + except ValueError as e: + parser.error(str(e)) generate_html(run_info, bench_files, output_path, baseline_info, baseline_files) diff --git a/benchmarks/run_benchmarks.py b/benchmarks/run_benchmarks.py index 34ffbf16..6f3a7aaa 100644 --- a/benchmarks/run_benchmarks.py +++ b/benchmarks/run_benchmarks.py @@ -46,6 +46,15 @@ DEFAULT_STABILITY_WARN_PCT = 5.0 +def parse_sync_mode_selection(value: str) -> list[str]: + mapping = { + "crdt": ["crdt"], + "lww": ["lww"], + "both": ["crdt", "lww"], + } + return mapping[value] + + # ── Index helpers (mirrors python/run_all.py) ────────────────────────────────── def load_runs() -> list: @@ -454,12 +463,13 @@ def _build_cpp_cmd(binary: str, catch2_filter: Optional[str], verbose: bool, def _run_cpp_once(binary: str, cpp_cwd: str, catch2_filter: Optional[str], - verbose: bool, priority: Optional[int], taskset: Optional[str]) -> tuple[bool, float]: + verbose: bool, priority: Optional[int], taskset: Optional[str], + extra_env: Optional[dict[str, str]] = None) -> tuple[bool, float]: # Catch2 v3 has no single-spec "run everything including hidden". # Handle the sentinel by running visible tests then hidden tests in the same cwd. if catch2_filter == ALL_CPP_FILTER: - ok1, dur1 = _run_cpp_once(binary, cpp_cwd, None, verbose, priority, taskset) - ok2, dur2 = _run_cpp_once(binary, cpp_cwd, "[.]", verbose, priority, taskset) + ok1, dur1 = _run_cpp_once(binary, cpp_cwd, None, verbose, priority, taskset, extra_env) + ok2, dur2 = _run_cpp_once(binary, cpp_cwd, "[.]", verbose, priority, taskset, extra_env) return ok1 and ok2, dur1 + dur2 os.makedirs(cpp_cwd, exist_ok=True) @@ -468,7 +478,7 @@ def _run_cpp_once(binary: str, cpp_cwd: str, catch2_filter: Optional[str], wsl_cwd = win_to_wsl(cpp_cwd) cmd_str = _build_cpp_cmd(binary, catch2_filter, verbose, priority, taskset) bash_cmd = f"cd {wsl_cwd} && {cmd_str}" - result = subprocess.run(["wsl", "-e", "bash", "-c", bash_cmd]) + result = subprocess.run(["wsl", "-e", "bash", "-c", bash_cmd], env={**os.environ, **(extra_env or {})}) else: cmd = [] if taskset: @@ -480,14 +490,16 @@ def _run_cpp_once(binary: str, cpp_cwd: str, catch2_filter: Optional[str], cmd.append(catch2_filter) if verbose: cmd.append("--verbose") - result = subprocess.run(cmd, cwd=cpp_cwd) + result = subprocess.run(cmd, cwd=cpp_cwd, env={**os.environ, **(extra_env or {})}) duration = time.time() - start return result.returncode == 0, duration def run_cpp(binary: str, run_dir: str, catch2_filter: Optional[str], verbose: bool, repeat: int = 1, priority: Optional[int] = None, taskset: Optional[str] = None, - stability_warn_pct: Optional[float] = DEFAULT_STABILITY_WARN_PCT): + stability_warn_pct: Optional[float] = DEFAULT_STABILITY_WARN_PCT, + sync_modes: Optional[list[str]] = None, + bench_env: Optional[dict[str, str]] = None): """ Run dsr_benchmarks 'repeat' times. If repeat > 1, each invocation writes to a separate cpp_N/ subdirectory; results are then median-merged into @@ -505,6 +517,9 @@ def run_cpp(binary: str, run_dir: str, catch2_filter: Optional[str], verbose: bo print(f"Priority: nice {priority:+d}") if taskset: print(f"CPU affinity: {taskset}") + sync_modes = sync_modes or ["crdt"] + bench_env = bench_env or {} + print(f"Sync modes: {', '.join(sync_modes)}") print("=" * 70) total_start = time.time() @@ -515,16 +530,28 @@ def run_cpp(binary: str, run_dir: str, catch2_filter: Optional[str], verbose: bo # Single run — original behaviour cpp_cwd = os.path.join(run_dir, "cpp") print(f"Output : {cpp_cwd}/results/") - ok, dur = _run_cpp_once(binary, cpp_cwd, catch2_filter, verbose, priority, taskset) - all_ok = ok + for sync_mode in sync_modes: + print(f" -> sync_mode={sync_mode}") + ok, _dur = _run_cpp_once( + binary, cpp_cwd, catch2_filter, verbose, priority, taskset, + {**bench_env, "BENCH_SYNC_MODE": sync_mode} + ) + all_ok = all_ok and ok else: # Multiple runs → median merge run_cwds = [] for r in range(1, repeat + 1): cpp_cwd = os.path.join(run_dir, f"cpp_{r}") print(f"\n--- Run {r}/{repeat} → {cpp_cwd}/results/ ---") - ok, dur = _run_cpp_once(binary, cpp_cwd, catch2_filter, verbose, priority, taskset) - if not ok: + run_ok = True + for sync_mode in sync_modes: + print(f" -> sync_mode={sync_mode}") + ok, _dur = _run_cpp_once( + binary, cpp_cwd, catch2_filter, verbose, priority, taskset, + {**bench_env, "BENCH_SYNC_MODE": sync_mode} + ) + run_ok = run_ok and ok + if not run_ok: print(f" Warning: run {r} exited non-zero") all_ok = False run_cwds.append(cpp_cwd) @@ -542,7 +569,8 @@ def run_cpp(binary: str, run_dir: str, catch2_filter: Optional[str], verbose: bo # ── Run Python suite ────────────────────────────────────────────────────────── -def run_python(run_dir: str, label: Optional[str], baseline: bool = False): +def run_python(run_dir: str, label: Optional[str], baseline: bool = False, + sync_mode: str = "both"): """ Delegate to python/run_all.py passing BENCH_RESULTS_DIR so Python files land directly in / (not a subdirectory). @@ -552,7 +580,7 @@ def run_python(run_dir: str, label: Optional[str], baseline: bool = False): print(f"Output : {run_dir}/") print("=" * 70) - env = {**os.environ, "BENCH_RESULTS_DIR": run_dir} + env = {**os.environ, "BENCH_RESULTS_DIR": run_dir, "BENCH_SYNC_MODE": sync_mode} cmd = [sys.executable, os.path.join(PYTHON_DIR, "run_all.py"), "--direct"] if baseline: cmd.append("--baseline") @@ -685,6 +713,23 @@ def cmd_run(args): elif args.baseline and not effective_cpp_filter: effective_cpp_filter = BASELINE_CPP_FILTER + cpp_sync_modes = parse_sync_mode_selection(args.cpp_sync_mode) + cpp_bench_env: dict[str, str] = {} + if args.warmup_iterations is not None: + cpp_bench_env["BENCH_WARMUP_ITERATIONS"] = str(args.warmup_iterations) + if args.measurement_iterations is not None: + cpp_bench_env["BENCH_MEASUREMENT_ITERATIONS"] = str(args.measurement_iterations) + if args.sync_wait_ms is not None: + cpp_bench_env["BENCH_SYNC_WAIT_MS"] = str(args.sync_wait_ms) + if args.max_convergence_timeout_s is not None: + cpp_bench_env["BENCH_MAX_CONVERGENCE_TIMEOUT_S"] = str(args.max_convergence_timeout_s) + if args.default_agent_count is not None: + cpp_bench_env["BENCH_DEFAULT_AGENT_COUNT"] = str(args.default_agent_count) + if args.max_agent_count is not None: + cpp_bench_env["BENCH_MAX_AGENT_COUNT"] = str(args.max_agent_count) + if args.writer_threads is not None: + cpp_bench_env["BENCH_CONCURRENT_WRITER_THREADS"] = str(args.writer_threads) + # Optionally build C++ if args.build: if not build_cpp(): @@ -709,6 +754,8 @@ def cmd_run(args): binary, run_dir, effective_cpp_filter, args.verbose, repeat=args.repeat, priority=args.priority, taskset=args.taskset, stability_warn_pct=args.stability_warn_pct, + sync_modes=cpp_sync_modes, + bench_env=cpp_bench_env, ) results["cpp"] = {"ok": ok, "duration_sec": dur, "stability": stability} suites_run.append("cpp") @@ -719,7 +766,10 @@ def cmd_run(args): # Python suite if not args.cpp_only: - ok, dur = run_python(run_dir, args.label, baseline=args.baseline) + ok, dur = run_python( + run_dir, args.label, baseline=args.baseline, + sync_mode=args.python_sync_mode, + ) results["python"] = {"ok": ok, "duration_sec": dur} suites_run.append("python") @@ -748,6 +798,8 @@ def cmd_run(args): "git_hash": git_hash, "platform": platform.platform(), "python": sys.version.split()[0], + "cpp_sync_mode": args.cpp_sync_mode, + "python_sync_mode": args.python_sync_mode, } cpp_stability = results.get("cpp", {}).get("stability") @@ -817,6 +869,10 @@ def main(): help=f"Path to dsr_benchmarks binary (default: {os.path.join(BUILD_DIR, 'dsr_benchmarks')})") parser.add_argument("--cpp-filter", metavar="FILTER", help='Catch2 test filter, e.g. "[LATENCY]" or "[THROUGHPUT]"') + parser.add_argument("--cpp-sync-mode", choices=["crdt", "lww", "both"], default="crdt", + help="Backend for C++ benchmarks (default: crdt)") + parser.add_argument("--python-sync-mode", choices=["crdt", "lww", "both"], default="both", + help="Backend selection for Python benchmarks (default: both)") parser.add_argument("--build", action="store_true", help="Build C++ benchmarks before running") parser.add_argument("--cpp-only", action="store_true", help="Skip Python suite") @@ -847,6 +903,20 @@ def main(): parser.add_argument("--stability-warn-pct", type=float, default=DEFAULT_STABILITY_WARN_PCT, metavar="PCT", help="Warn when repeated C++ metrics exceed this spread percentage") + parser.add_argument("--warmup-iterations", type=int, metavar="N", + help="Override C++ benchmark warmup iterations") + parser.add_argument("--measurement-iterations", type=int, metavar="N", + help="Override C++ benchmark measurement iterations") + parser.add_argument("--sync-wait-ms", type=int, metavar="MS", + help="Override C++ benchmark sync wait time in milliseconds") + parser.add_argument("--max-convergence-timeout-s", type=int, metavar="S", + help="Override C++ benchmark convergence timeout in seconds") + parser.add_argument("--default-agent-count", type=int, metavar="N", + help="Override C++ benchmark default agent count") + parser.add_argument("--max-agent-count", type=int, metavar="N", + help="Override C++ benchmark max agent count") + parser.add_argument("--writer-threads", type=int, metavar="N", + help="Override C++ benchmark concurrent writer thread count") args = parser.parse_args() diff --git a/python-wrapper/test/PythonAPITests.py b/python-wrapper/test/PythonAPITests.py index 090f0ae5..2b2a16d2 100644 --- a/python-wrapper/test/PythonAPITests.py +++ b/python-wrapper/test/PythonAPITests.py @@ -6,6 +6,28 @@ ETC_DIR = "../etc/" +NativeDSRGraph = DSRGraph +CURRENT_SYNC_MODE = SyncMode.CRDT + + +def DSRGraph(*args, **kwargs): + kwargs.setdefault("sync_mode", CURRENT_SYNC_MODE) + return NativeDSRGraph(*args, **kwargs) + + +SYNC_MODES = [("crdt", SyncMode.CRDT), ("lww", SyncMode.LWW)] + + +def make_graph(sync_mode): + return DSRGraph( + int(0), + "Prueba", + int(12), + os.path.join(ETC_DIR, "autonomyLab_objects.simscene.json"), + True, + 0, + sync_mode, + ) class TestAttribute(unittest.TestCase): @@ -147,30 +169,27 @@ def test_edge(self): class TestDSRGraph(unittest.TestCase): + SYNC_MODE = SyncMode.CRDT @classmethod def tearDownClass(cls): # time.sleep(0.5) pass + def setUp(self): + global CURRENT_SYNC_MODE + CURRENT_SYNC_MODE = self.SYNC_MODE + + def tearDown(self): + global CURRENT_SYNC_MODE + CURRENT_SYNC_MODE = SyncMode.CRDT + def test_create_graph(self): - a = DSRGraph( - int(0), - "Prueba", - int(12), - os.path.join(ETC_DIR, "autonomyLab_objects.simscene.json"), - True, - ) + a = make_graph(self.SYNC_MODE) self.assertIsNotNone(a) def test_get_node(self): - g = DSRGraph( - int(0), - "Prueba", - int(12), - os.path.join(ETC_DIR, "autonomyLab_objects.simscene.json"), - True, - ) + g = make_graph(self.SYNC_MODE) node = g.get_node(1) self.assertIsNotNone(node) node = g.get_node("root") @@ -181,13 +200,7 @@ def test_get_node(self): self.assertIsNone(node) def test_delete_node(self): - g = DSRGraph( - int(0), - "Prueba", - int(12), - os.path.join(ETC_DIR, "autonomyLab_objects.simscene.json"), - True, - ) + g = make_graph(self.SYNC_MODE) node = g.get_node(1) self.assertIsNotNone(node) res = g.delete_node(1) @@ -196,13 +209,7 @@ def test_delete_node(self): self.assertIsNone(node) def test_update_node(self): - g = DSRGraph( - int(0), - "Prueba", - int(12), - os.path.join(ETC_DIR, "autonomyLab_objects.simscene.json"), - True, - ) + g = make_graph(self.SYNC_MODE) world = g.get_node("root") world.attrs["color"].value = "red" result = g.update_node(world) @@ -555,6 +562,10 @@ def test_get_euler_xyz_angles(self): self.assertIsNotNone(angles) +class TestDSRGraphLWW(TestDSRGraph): + SYNC_MODE = SyncMode.LWW + + class Singleton(type): _instances = {} diff --git a/tests/graph/attribute_operations.cpp b/tests/graph/attribute_operations.cpp index 1a626968..6fc7354f 100644 --- a/tests/graph/attribute_operations.cpp +++ b/tests/graph/attribute_operations.cpp @@ -5,6 +5,7 @@ #include #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "dsr/core/types/type_checking/dsr_edge_type.h" #include "dsr/core/types/type_checking/dsr_node_type.h" @@ -32,9 +33,11 @@ REGISTER_TYPE(att_no_reference, vec6, false) TEST_CASE("Attributes operations (Compile time type-checked)", "[ATTRIBUTES]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Insert attribute (node) and insert node in G") { @@ -104,9 +107,11 @@ TEST_CASE("Attributes operations (Compile time type-checked)", "[ATTRIBUTES]") { } TEST_CASE("Attributes operations II (Runtime time type-checked)", "[RUNTIME ATTRIBUTES]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Insert an attribute") { std::optional n = G.get_node(100); @@ -182,9 +187,11 @@ TEST_CASE("Attributes operations II (Runtime time type-checked)", "[RUNTIME ATTR } TEST_CASE("Other attribute operations and checks", "[ATTRIBUTES]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Get attribute timestamp") { std::optional n = G.get_node(100); @@ -295,9 +302,11 @@ TEST_CASE("Other attribute operations and checks", "[ATTRIBUTES]") { } } TEST_CASE("Native types in attributes", "[ATTRIBUTES]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Insert a string attribute") { std::optional n = G.get_node(100); diff --git a/tests/graph/convenience_operations.cpp b/tests/graph/convenience_operations.cpp index 020798f0..fc29bda1 100644 --- a/tests/graph/convenience_operations.cpp +++ b/tests/graph/convenience_operations.cpp @@ -4,6 +4,7 @@ #include #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "dsr/core/types/type_checking/dsr_node_type.h" using namespace DSR; @@ -12,9 +13,11 @@ using namespace DSR; TEST_CASE("Maps operations", "[CONVENIENCE METHODS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Get id from a name and a name from an id") { @@ -94,9 +97,11 @@ TEST_CASE("Maps operations", "[CONVENIENCE METHODS]") { TEST_CASE("Convenience methods", "[CONVENIENCE METHODS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Get node level") { @@ -144,4 +149,4 @@ TEST_CASE("Convenience methods", "[CONVENIENCE METHODS]") { REQUIRE(n2.has_value()); REQUIRE(n2.value() == n.value()); } -} \ No newline at end of file +} diff --git a/tests/graph/edge_operations.cpp b/tests/graph/edge_operations.cpp index 61da9959..156ba135 100644 --- a/tests/graph/edge_operations.cpp +++ b/tests/graph/edge_operations.cpp @@ -3,6 +3,7 @@ // #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "dsr/core/types/type_checking/dsr_edge_type.h" #include "dsr/core/types/user_types.h" @@ -17,9 +18,11 @@ using namespace DSR; TEST_CASE("Graph edge operations", "[EDGE]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_empty_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Get an edge that does not exists by id") { std::optional e_id = G.get_edge(random_number(), random_number(), random_string()); @@ -169,4 +172,4 @@ TEST_CASE("Edge creation", REQUIRE_NOTHROW(e.type("in")); REQUIRE_THROWS(e.type("invalidtype")); } -} \ No newline at end of file +} diff --git a/tests/graph/graph_operations.cpp b/tests/graph/graph_operations.cpp index 68ba0c8c..b8445656 100644 --- a/tests/graph/graph_operations.cpp +++ b/tests/graph/graph_operations.cpp @@ -8,6 +8,7 @@ #include #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "dsr/core/types/type_checking/dsr_edge_type.h" #include "dsr/core/types/type_checking/dsr_node_type.h" @@ -37,9 +38,11 @@ REGISTER_TYPE(att_no_reference, vec6, false) SCENARIO( "Node insertions, updates and removals", "[NODE]" ) { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_edge_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); GIVEN("A new Node") { diff --git a/tests/graph/node_operations.cpp b/tests/graph/node_operations.cpp index 0edec07d..43023a38 100644 --- a/tests/graph/node_operations.cpp +++ b/tests/graph/node_operations.cpp @@ -4,6 +4,7 @@ #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "dsr/core/types/user_types.h" #include "dsr/core/types/type_checking/dsr_edge_type.h" @@ -17,10 +18,11 @@ using namespace DSR; TEST_CASE("Graph node operations", "[NODE]") { - + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_empty_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Try to get a node that does not exists by a id") { std::optional n_id = G.get_node(random_number()); @@ -157,9 +159,11 @@ TEST_CASE("Graph node operations", "[NODE]") { TEST_CASE("Insert node with specific id", "[NODE]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = make_empty_config_file(); - DSRGraph G(random_string(10), rand() % 1200, filename); + DSRGraph G(make_test_graph_settings(random_string(10), rand() % 1200, filename, true, 0, SignalMode::QT, sync_mode)); SECTION("Insert a node with a specific id") { auto node_name = random_string(); @@ -228,4 +232,4 @@ TEST_CASE("Node creation", REQUIRE_NOTHROW(n.type("testtype")); REQUIRE_THROWS(n.type("invalidtype")); } -} \ No newline at end of file +} diff --git a/tests/synchronization/graph_signals.cpp b/tests/synchronization/graph_signals.cpp index 676d73f5..dcdaf67d 100644 --- a/tests/synchronization/graph_signals.cpp +++ b/tests/synchronization/graph_signals.cpp @@ -5,6 +5,7 @@ #include #include "catch2/catch_test_macros.hpp" +#include "catch2/generators/catch_generators.hpp" #include "catch2/internal/catch_test_registry.hpp" using namespace DSR; @@ -52,11 +53,13 @@ struct QTestApplication: public QCoreApplication { }; TEST_CASE("Insert a node without attributes and edges", "[GRAPH][SIGNALS]"){ + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); bool update_node_signal_recv = false; QObject::connect(&G, &DSRGraph::update_node_signal, &app, @@ -159,11 +162,13 @@ static const auto new_edge_ = [](uint64_t to, const std::map(node_name); std::optional r = G.insert_node(n); @@ -250,11 +255,13 @@ TEST_CASE("Insert a node with attributes and edges", "[GRAPH][SIGNALS]"){ TEST_CASE("Update a node, add and remove attributes", "[GRAPH][SIGNALS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); n.attrs({new_attribute_(), new_attribute_(), new_attribute_()}); @@ -343,11 +350,13 @@ TEST_CASE("Update a node, add and remove attributes", "[GRAPH][SIGNALS]") { } TEST_CASE("Insert and edge", "[GRAPH][SIGNALS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); const std::optional r = G.insert_node(n); @@ -435,11 +444,13 @@ TEST_CASE("Insert and edge", "[GRAPH][SIGNALS]") { } TEST_CASE("Update an edge, add and remove attributes", "[GRAPH][SIGNALS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); const std::optional r = G.insert_node(n); @@ -542,11 +553,13 @@ TEST_CASE("Update an edge, add and remove attributes", "[GRAPH][SIGNALS]") { } TEST_CASE("delete a node", "[GRAPH][SIGNALS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); const std::optional r = G.insert_node(n); @@ -648,11 +661,13 @@ TEST_CASE("delete a node", "[GRAPH][SIGNALS]") { } TEST_CASE("delete an edge", "[GRAPH][SIGNALS]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto ctx = make_empty_config_file(); auto id1 = rand() % 1000; int argc = 0; QTestApplication app(argc, nullptr); // need this to trigger signals - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); const std::optional r = G.insert_node(n); @@ -858,4 +873,6 @@ TEST_CASE("RT api signals", "[GRAPH][SIGNALS]") { TEST_CASE("Graph synchronization signals", "[GRAPH][SIGNALS]") { -} \ No newline at end of file + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); +} diff --git a/tests/synchronization/graph_synchronization.cpp b/tests/synchronization/graph_synchronization.cpp index 2e71954c..ab113999 100644 --- a/tests/synchronization/graph_synchronization.cpp +++ b/tests/synchronization/graph_synchronization.cpp @@ -39,14 +39,15 @@ class DSRGraphTestAccess } TEST_CASE("Connect and receive the graph from other agent", "[SYNCHRONIZATION][GRAPH]"){ - + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + CAPTURE(sync_mode_label(sync_mode)); auto filename = GENERATE(make_edge_config_file, make_empty_config_file); auto ctx = filename(); auto id1 = rand() % 1000; auto id2 = id1 + 1; - DSRGraph G(random_string(10), id1, ctx); - DSRGraph G2(random_string(11), id2); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); + DSRGraph G2(make_test_graph_settings(random_string(11), id2, std::string{}, true, 0, SignalMode::QT, sync_mode)); std::this_thread::sleep_for(200ms); REQUIRE(G2.size() == G.size()); @@ -54,13 +55,15 @@ TEST_CASE("Connect and receive the graph from other agent", "[SYNCHRONIZATION][G TEST_CASE("Same-process agents discover each other and exchange updates", "[SYNCHRONIZATION][GRAPH][REGRESSION][DDS]") { - const auto same_host = GENERATE(true, false); + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + const auto same_host = (sync_mode == SyncMode::LWW) ? true : GENERATE(true, false); + CAPTURE(sync_mode_label(sync_mode), same_host); auto ctx = make_edge_config_file(); auto id1 = static_cast(rand() % 1000 + 1000); auto id2 = id1 + 1; - DSRGraph loader(random_string(10), id1, ctx, same_host); - DSRGraph follower(random_string(11), id2, std::string{}, same_host); + DSRGraph loader(make_test_graph_settings(random_string(10), id1, ctx, same_host, 0, SignalMode::QT, sync_mode)); + DSRGraph follower(make_test_graph_settings(random_string(11), id2, std::string{}, same_host, 0, SignalMode::QT, sync_mode)); auto wait_until = [](auto&& predicate, std::chrono::milliseconds timeout = 2000ms) { diff --git a/tests/utils.h b/tests/utils.h index 88b2bb71..1e58c695 100644 --- a/tests/utils.h +++ b/tests/utils.h @@ -282,3 +282,32 @@ inline auto make_edge_config_file() -> std::string { return filename; } + +inline auto sync_mode_label(DSR::SyncMode mode) -> const char* +{ + switch (mode) { + case DSR::SyncMode::CRDT: return "CRDT"; + case DSR::SyncMode::LWW: return "LWW"; + } + return "UNKNOWN"; +} + +inline auto make_test_graph_settings( + std::string graph_name, + uint32_t agent_id, + const std::string& input_file = std::string(), + bool same_host = true, + int8_t domain_id = 0, + DSR::SignalMode signal_mode = DSR::SignalMode::QT, + DSR::SyncMode sync_mode = DSR::SyncMode::CRDT) -> DSR::GraphSettings +{ + DSR::GraphSettings settings; + settings.agent_id = agent_id; + settings.graph_name = std::move(graph_name); + settings.input_file = input_file; + settings.same_host = same_host; + settings.domain_id = domain_id; + settings.signal_mode = signal_mode; + settings.sync_mode = sync_mode; + return settings; +} From 8d51ee6b253daa355edbba93518b75311310bf14 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 23 Apr 2026 13:35:06 +0200 Subject: [PATCH 21/38] refactor: small things --- api/dsr_api.cpp | 100 +++++++------- api/dsr_crdt_sync_engine.cpp | 7 + api/dsr_lww_sync_engine.cpp | 159 ++++++++++++++-------- api/dsr_rt_api.cpp | 196 --------------------------- api/include/dsr/api/dsr_api.h | 49 +++---- core/include/dsr/core/id_generator.h | 4 +- tests/graph/rt_timestamp.cpp | 6 +- 7 files changed, 189 insertions(+), 332 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index e35b0eff..b1abd4f1 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -161,7 +161,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : auto participant_init_result = [&]() { CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init participant"); return dsrparticipant.init(agent_id, agent_name, settings.same_host, - ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph, + ParticipantChangeFn(this, [&](DSR::DSRGraph *graph, eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) { @@ -295,26 +295,6 @@ void DSRGraph::reset() to_edges.clear(); } -CRDTSyncEngine& DSRGraph::crdt_engine() -{ - return static_cast(*engine_); -} - -const CRDTSyncEngine& DSRGraph::crdt_engine() const -{ - return static_cast(*engine_); -} - -LWWSyncEngine& DSRGraph::lww_engine() -{ - return static_cast(*engine_); -} - -const LWWSyncEngine& DSRGraph::lww_engine() const -{ - return static_cast(*engine_); -} - void DSRGraph::publish_node_message(const NodeDeltaMessage& message) { std::visit([this](const auto& payload) { @@ -352,10 +332,10 @@ void DSRGraph::publish_full_graph_message(FullGraphMessage&& message, int32_t se } template -DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal) +DSRGraph::NewMessageFn DSRGraph::make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal) { auto name = "node_subscription_thread"; - return NewMessageFunctor(this, [this, channel, name, showReceived = log_level, clear_deleted_signal] + return NewMessageFn(this, [this, channel, name, showReceived = log_level, clear_deleted_signal] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); @@ -396,10 +376,10 @@ DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor_impl(const } template -DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor_impl(const char* channel) +DSRGraph::NewMessageFn DSRGraph::make_edge_subscription_functor_impl(const char* channel) { auto name = "edge_subscription_thread"; - return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] + return NewMessageFn(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); @@ -430,10 +410,10 @@ DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor_impl(const } template -DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor_impl(const char* channel) +DSRGraph::NewMessageFn DSRGraph::make_edge_attrs_subscription_functor_impl(const char* channel) { auto name = "edge_attrs_subscription_thread"; - return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] + return NewMessageFn(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); @@ -469,10 +449,10 @@ DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor_impl( } template -DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor_impl(const char* channel) +DSRGraph::NewMessageFn DSRGraph::make_node_attrs_subscription_functor_impl(const char* channel) { auto name = "node_attrs_subscription_thread"; - return NewMessageFunctor(this, [this, channel, name, showReceived = log_level] + return NewMessageFn(this, [this, channel, name, showReceived = log_level] (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); @@ -508,9 +488,9 @@ DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor_impl( } template -DSRGraph::NewMessageFunctor DSRGraph::make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated) +DSRGraph::NewMessageFn DSRGraph::make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated) { - return NewMessageFunctor(this, [this, channel, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + return NewMessageFn(this, [this, channel, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); @@ -548,7 +528,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_fullgraph_request_functor_impl(const }); } -DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor() +DSRGraph::NewMessageFn DSRGraph::make_node_subscription_functor() { if (sync_mode == SyncMode::LWW) { return make_node_subscription_functor_impl("LWW_NODE"); @@ -556,7 +536,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_node_subscription_functor() return make_node_subscription_functor_impl("DSR_NODE", true); } -DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor() +DSRGraph::NewMessageFn DSRGraph::make_edge_subscription_functor() { if (sync_mode == SyncMode::LWW) { return make_edge_subscription_functor_impl("LWW_EDGE"); @@ -564,7 +544,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_edge_subscription_functor() return make_edge_subscription_functor_impl("DSR_EDGE"); } -DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor() +DSRGraph::NewMessageFn DSRGraph::make_edge_attrs_subscription_functor() { if (sync_mode == SyncMode::LWW) { return make_edge_attrs_subscription_functor_impl("LWW_EDGE_ATTS"); @@ -572,7 +552,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_edge_attrs_subscription_functor() return make_edge_attrs_subscription_functor_impl("DSR_EDGE_ATTS"); } -DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor() +DSRGraph::NewMessageFn DSRGraph::make_node_attrs_subscription_functor() { if (sync_mode == SyncMode::LWW) { return make_node_attrs_subscription_functor_impl("LWW_NODE_ATTS"); @@ -580,7 +560,7 @@ DSRGraph::NewMessageFunctor DSRGraph::make_node_attrs_subscription_functor() return make_node_attrs_subscription_functor_impl("DSR_NODE_ATTS"); } -DSRGraph::NewMessageFunctor DSRGraph::make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) +DSRGraph::NewMessageFn DSRGraph::make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) { if (sync_mode == SyncMode::LWW) { return make_fullgraph_request_functor_impl("LWW_GRAPH_ANSWER", sync, repeated); @@ -616,9 +596,9 @@ template std::optional DSRGraph::insert_node(No &&node) requires (std::is_same_v, DSR::Node>) { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node"); NodeMutationEffect effect; { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node local"); std::unique_lock lock(_mutex); std::shared_lock lck_cache(_mutex_cache_maps); uint64_t new_node_id = generator.generate(); @@ -635,7 +615,9 @@ std::optional DSRGraph::insert_node(No &&node) { if (effect.node_delta.has_value()) { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node publish deltas"); publish_node_message(*effect.node_delta); + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node emit signals"); DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); for (const auto &[k, v]: node.fano()) @@ -655,6 +637,7 @@ template std::optional DSRGraph::insert_node_with_id(No &&node) requires (std::is_same_v, DSR::Node>) { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_with_id"); NodeMutationEffect effect; { std::unique_lock lock(_mutex); @@ -675,7 +658,9 @@ std::optional DSRGraph::insert_node_with_id(No &&node) { if (effect.node_delta.has_value()) { + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_with_id send deltas"); publish_node_message(*effect.node_delta); + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_with_id emit signals"); DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); for (const auto &[k, v]: node.fano()) @@ -720,12 +705,14 @@ requires (std::is_same_v, DSR::Node>) } } if (!copy) { + CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node send deltas"); if (effect.node_delta.has_value()) { publish_node_message(*effect.node_delta); } if (effect.node_attr_batch.has_value()) { publish_node_attr_batch(*effect.node_attr_batch); } + CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node emit signals"); if (effect.node_delta.has_value() || effect.node_attr_batch.has_value()) { DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); @@ -772,17 +759,21 @@ bool DSRGraph::delete_node(uint64_t id) } if (!copy) { - DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); - emitter.del_node_signal(id, SignalInfo{ agent_id }); - if (effect.deleted_node) { - emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); - } + CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node(id) send deltas"); if (effect.node_delta.has_value()) { publish_node_message(*effect.node_delta); } for (const auto &delta : effect.edge_deltas) { publish_edge_message(delta); } + CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node(id) emit signals"); + DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); + emitter.del_node_signal(id, SignalInfo{ agent_id }); + + if (effect.deleted_node) { + emitter.deleted_node_signal(*effect.deleted_node, SignalInfo{agent_id}); + } + for (auto &edge : effect.deleted_edges) { emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id }); emitter.deleted_edge_signal(edge, SignalInfo{ agent_id }); @@ -810,15 +801,17 @@ requires (std::is_same_v, DSR::Edge>) } } if (!copy) { - DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); - emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); - + CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge sned deltas"); if (effect.edge_delta.has_value()) { publish_edge_message(*effect.edge_delta); } if (effect.edge_attr_batch.has_value()) { publish_edge_attr_batch(*effect.edge_attr_batch); } + CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge emit signals"); + DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); + emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); + if (!effect.changed_attributes.empty()) { emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), effect.changed_attributes, SignalInfo{ agent_id }); } @@ -835,6 +828,7 @@ template bool DSRGraph::insert_or_assign_edge(const DSR::Edge& bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_edge(from, to, key)"); EdgeMutationEffect effect; { std::unique_lock lock(_mutex); @@ -845,20 +839,24 @@ bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key) return false; } if (!copy) { + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_edge(from, to, key) send deltas"); + if (effect.edge_delta.has_value()) { + publish_edge_message(*effect.edge_delta); + } + + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_edge(from, to, key) emit signals"); DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key); emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id }); if (effect.deleted_edge.has_value()) { emitter.deleted_edge_signal(*effect.deleted_edge, SignalInfo{ agent_id }); } - if (effect.edge_delta.has_value()) { - publish_edge_message(*effect.edge_delta); - } } return true; } bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::delete_edge(from_str, to_str, key)"); std::optional id_from = get_id_from_name(from); std::optional id_to = get_id_from_name(to); if (!id_from.has_value() || !id_to.has_value()) { @@ -931,6 +929,7 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector DSRGraph::get_edge(const std::string &from, const std::string &to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(from_str, to_str, key)"); std::shared_lock lock(_mutex); std::optional id_from = get_id_from_name(from); std::optional id_to = get_id_from_name(to); @@ -943,12 +942,14 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional DSRGraph::get_edge(uint64_t from, uint64_t to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(from, to, key)"); std::shared_lock lock(_mutex); return engine_->get_edge(from, to, key); } std::optional DSRGraph::get_edge(const Node &n, const std::string &to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(Node, to_str, key)"); std::optional id_to = get_id_from_name(to); if (id_to.has_value()) { @@ -960,6 +961,7 @@ std::optional DSRGraph::get_edge(const Node &n, const std::string &to, con std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::string &key) { + CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(Node, to, key)"); auto it = n.fano().find({to, key}); if (it != n.fano().end()) return it->second; return {}; @@ -1445,7 +1447,7 @@ void DSRGraph::fullgraph_server_thread() } } }; - dsrpub_graph_request_call = NewMessageFunctor(this, lambda_graph_request); + dsrpub_graph_request_call = NewMessageFn(this, lambda_graph_request); auto [res, sub, reader] = dsrsub_graph_request.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id(), dsrpub_graph_request_call, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getGraphRequestTopic()->get_name(), {sub, reader}); diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 29bc6bf6..b31283d2 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -619,6 +619,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) std::string current_type; auto delete_unprocessed_deltas = [&](){ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node delete unprocessed deltas"); unprocessed_delta_node_att_.erase(id); decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); while (!node_handle.empty()) @@ -633,6 +634,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) }; auto consume_unprocessed_deltas = [&]() { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node consume unprocessed deltas"); decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); while (!node_handle_node_att.empty()) { @@ -768,6 +770,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) std::optional deleted_edge; auto delete_unprocessed_deltas = [&](){ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge delete unprocessed deltas"); unprocessed_delta_edge_att_.erase(std::tuple{from, to, type}); std::erase_if(unprocessed_delta_edge_to_, [&](auto &it){ return std::get<0>(it.second) == from || std::get<0>(it.second) == to;}); @@ -776,6 +779,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) }; auto consume_unprocessed_deltas = [&](){ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge consume unprocessed deltas"); auto att_key = std::tuple{from, to, type}; decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { @@ -948,6 +952,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) uint64_t id{0}, timestamp{0}; uint32_t agent_id_ch{0}; auto delete_unprocessed_deltas = [&](){ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph delete unprocessed deltas"); unprocessed_delta_node_att_.erase(id); decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); while (!node_handle.empty()) @@ -960,6 +965,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; auto consume_unprocessed_deltas = [&](){ + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph consume unprocessed deltas"); decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); while (!node_handle_node_att.empty()) { @@ -1019,6 +1025,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph crdt"); for (auto &[k, val] : full_graph.m) { auto mv = std::move(val.dk); bool mv_empty = mv.empty(); diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 1cd378d1..24d41800 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -1,4 +1,5 @@ #include "dsr/api/dsr_lww_sync_engine.h" +#include "dsr/core/profiling.h" #include "dsr/core/types/lww_io.h" #include "dsr/core/types/lww_merge.h" @@ -93,6 +94,7 @@ SyncBackendInfo LWWSyncEngine::backend_info() const std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::clone"); return std::make_unique(host, *this); } @@ -121,6 +123,7 @@ uint64_t LWWSyncEngine::next_timestamp() void LWWSyncEngine::prune_tombstones(uint64_t now) { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::prune_tombstones"); std::erase_if(node_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); std::erase_if(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); } @@ -137,6 +140,7 @@ void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std:: void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::erase_related_edges"); std::unordered_set to_erase; if (auto it = from_idx_.find(node_id); it != from_idx_.end()) { to_erase.insert(it->second.begin(), it->second.end()); @@ -159,6 +163,7 @@ void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint6 std::optional LWWSyncEngine::get_node(uint64_t id) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_node"); auto it = nodes_.find(id); if (it == nodes_.end()) return {}; return LWW::to_user_node(it->second, edges_, from_idx_); @@ -166,6 +171,7 @@ std::optional LWWSyncEngine::get_node(uint64_t id) const std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_edge"); if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end()) { return LWW::to_user_edge(it->second); } @@ -194,6 +200,7 @@ bool LWWSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_from"); if (!nodes_.contains(from)) { return false; } @@ -205,11 +212,13 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_to"); return LWW::for_each_edge_to(edges_, to_idx_, to, visitor); } void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_of_type"); LWW::for_each_edge_of_type(edges_, type_idx_, type, visitor); } @@ -220,6 +229,7 @@ size_t LWWSyncEngine::size() const std::map LWWSyncEngine::snapshot() const { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::snapshot"); std::map out; for (const auto& [id, _] : nodes_) { out.emplace(id, *get_node(id)); @@ -229,6 +239,7 @@ std::map LWWSyncEngine::snapshot() const NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::insert_node_local"); auto now = next_timestamp(); prune_tombstones(now); @@ -256,6 +267,7 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::update_node_local"); auto now = next_timestamp(); prune_tombstones(now); @@ -288,6 +300,7 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::delete_node_local"); auto now = next_timestamp(); prune_tombstones(now); @@ -321,6 +334,7 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::insert_or_assign_edge_local"); auto now = next_timestamp(); prune_tombstones(now); @@ -356,6 +370,7 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, const std::string& type) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::delete_edge_local"); auto now = next_timestamp(); prune_tombstones(now); @@ -385,6 +400,7 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::apply_remote_node_delta"); auto* payload = std::get_if(&delta); if (payload == nullptr) { return; @@ -400,6 +416,7 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) } if (payload->deleted) { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_delta delete"); std::optional deleted_node; std::vector deleted_edges; if (auto it = nodes_.find(payload->id); it != nodes_.end()) { @@ -415,18 +432,22 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) NodeState state = LWW::to_node_state(*payload); - auto maybe_old = get_node(payload->id); - if (maybe_old.has_value()) { - host_.update_maps_node_delete(payload->id, maybe_old); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_delta upsert"); + auto maybe_old = get_node(payload->id); + if (maybe_old.has_value()) { + host_.update_maps_node_delete(payload->id, maybe_old); + } + nodes_[payload->id] = std::move(state); + node_tombstones_.erase(payload->id); + host_.update_maps_node_insert(*get_node(payload->id)); } - nodes_[payload->id] = std::move(state); - node_tombstones_.erase(payload->id); - host_.update_maps_node_insert(*get_node(payload->id)); host_.on_remote_node_updated(payload->id, payload->type, payload->agent_id); } void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::apply_remote_edge_delta"); auto* payload = std::get_if(&delta); if (payload == nullptr) { return; @@ -446,6 +467,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) auto key = edge_key(payload->from, payload->to, payload->type); if (payload->deleted) { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_delta delete"); std::optional deleted_edge; if (auto it = edges_.find(key); it != edges_.end()) { deleted_edge = LWW::to_user_edge(it->second); @@ -458,16 +480,20 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) return; } - EdgeState state = LWW::to_edge_state(*payload); - edges_[key] = std::move(state); - idx_insert(key); - edge_tombstones_.erase(key); - host_.update_maps_edge_insert(payload->from, payload->to, payload->type); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_delta upsert"); + EdgeState state = LWW::to_edge_state(*payload); + edges_[key] = std::move(state); + idx_insert(key); + edge_tombstones_.erase(key); + host_.update_maps_edge_insert(payload->from, payload->to, payload->type); + } host_.on_remote_edge_updated(payload->from, payload->to, payload->type, payload->agent_id); } void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::apply_remote_node_attr_batch"); auto* payload = std::get_if(&batch); if (payload == nullptr) { return; @@ -480,36 +506,43 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat uint32_t agent_id{0}; }; std::unordered_map changes; - for (const auto& item : payload->vec) { - auto it = nodes_.find(item.node_id); - if (it == nodes_.end()) { - continue; - } - auto version = version_of(item.timestamp, item.agent_id); - auto attr_it = it->second.attrs.find(item.attr_name); - if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { - continue; - } - if (item.deleted) { - it->second.attrs.erase(item.attr_name); - } else { - it->second.attrs[item.attr_name] = AttrState{item.value, version}; - } - auto& change = changes[item.node_id]; - if (change.type.empty()) { - change.type = it->second.type; + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_attr_batch merge"); + for (const auto& item : payload->vec) { + auto it = nodes_.find(item.node_id); + if (it == nodes_.end()) { + continue; + } + auto version = version_of(item.timestamp, item.agent_id); + auto attr_it = it->second.attrs.find(item.attr_name); + if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { + continue; + } + if (item.deleted) { + it->second.attrs.erase(item.attr_name); + } else { + it->second.attrs[item.attr_name] = AttrState{item.value, version}; + } + auto& change = changes[item.node_id]; + if (change.type.empty()) { + change.type = it->second.type; + } + change.agent_id = item.agent_id; + change.attrs.push_back(item.attr_name); } - change.agent_id = item.agent_id; - change.attrs.push_back(item.attr_name); } - for (const auto& [id, change] : changes) { - host_.on_remote_node_attrs_updated(id, change.type, change.attrs, change.agent_id); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_attr_batch emit"); + for (const auto& [id, change] : changes) { + host_.on_remote_node_attrs_updated(id, change.type, change.attrs, change.agent_id); + } } } void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::apply_remote_edge_attr_batch"); auto* payload = std::get_if(&batch); if (payload == nullptr) { return; @@ -521,49 +554,63 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat uint32_t agent_id{0}; }; std::map changes; - for (const auto& item : payload->vec) { - auto it = edges_.find(edge_key(item.from, item.to, item.type)); - if (it == edges_.end()) { - continue; - } - auto version = version_of(item.timestamp, item.agent_id); - auto attr_it = it->second.attrs.find(item.attr_name); - if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { - continue; - } - if (item.deleted) { - it->second.attrs.erase(item.attr_name); - } else { - it->second.attrs[item.attr_name] = AttrState{item.value, version}; + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); + for (const auto& item : payload->vec) { + auto it = edges_.find(edge_key(item.from, item.to, item.type)); + if (it == edges_.end()) { + continue; + } + auto version = version_of(item.timestamp, item.agent_id); + auto attr_it = it->second.attrs.find(item.attr_name); + if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { + continue; + } + if (item.deleted) { + it->second.attrs.erase(item.attr_name); + } else { + it->second.attrs[item.attr_name] = AttrState{item.value, version}; + } + auto& change = changes[edge_key(item.from, item.to, item.type)]; + change.agent_id = item.agent_id; + change.attrs.push_back(item.attr_name); } - auto& change = changes[edge_key(item.from, item.to, item.type)]; - change.agent_id = item.agent_id; - change.attrs.push_back(item.attr_name); } - for (const auto& [key, change] : changes) { - host_.on_remote_edge_attrs_updated(std::get<0>(key), std::get<1>(key), std::get<2>(key), change.attrs, change.agent_id); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch emit"); + for (const auto& [key, change] : changes) { + host_.on_remote_edge_attrs_updated(std::get<0>(key), std::get<1>(key), std::get<2>(key), change.attrs, change.agent_id); + } } } void LWWSyncEngine::import_full_graph(FullGraphMessage&& full_graph) { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::import_full_graph"); auto* payload = std::get_if(&full_graph); if (payload == nullptr) { return; } tombstone_window_ms_ = payload->tombstone_window_ms == 0 ? tombstone_window_ms_ : payload->tombstone_window_ms; - for (const auto& node : payload->nodes) { - apply_remote_node_delta(NodeDeltaMessage{node}); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::import_full_graph nodes"); + for (const auto& node : payload->nodes) { + apply_remote_node_delta(NodeDeltaMessage{node}); + } } - for (const auto& edge : payload->edges) { - apply_remote_edge_delta(EdgeDeltaMessage{edge}); + { + CORTEX_PROFILE_ZONE_N("LWWSyncEngine::import_full_graph edges"); + for (const auto& edge : payload->edges) { + apply_remote_edge_delta(EdgeDeltaMessage{edge}); + } } } FullGraphMessage LWWSyncEngine::export_full_graph() const { + CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::export_full_graph"); LWWGraphSnapshot snapshot; snapshot.id = static_cast(host_.local_agent_id()); snapshot.protocol_version = DSR_PROTOCOL_VERSION; diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index 3c876cdb..0c7c3c87 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -367,203 +367,7 @@ std::optional> RT_API::get_covariance_matrix(uint64_ void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, const std::vector &trans, const std::vector &rot_euler, std::optional timestamp) { CORTEX_PROFILE_ZONE_N("RT_API::insert_or_assign_edge_RT(copy)"); -<<<<<<< HEAD insert_or_assign_edge_RT_impl(n, to, trans, rot_euler, std::nullopt, timestamp); -======= - bool r1 = false; - bool r2 = false; - bool no_send = true; - - std::optional node1_insert; - std::optional node1_update; - std::optional node2; - std::optional to_n_mut; - std::optional to_n_id; - std::optional to_n_type; - { - std::unique_lock lock(G->_mutex); - if (const auto* to_n = G->crdt_engine().get_node_ptr(to); to_n != nullptr) - { - to_n_id = to_n->id(); - to_n_type = to_n->type(); - CRDTEdge e; - if (HISTORY_SIZE <= 0) - { - e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); - CRDTAttribute tr(trans, get_unix_timestamp(), 0); - CRDTAttribute rot(rot_euler, get_unix_timestamp(), 0); - - auto [it, new_el] = e.attrs().emplace("rt_rotation_euler_xyz", mvreg ()); - it->second.write(std::move(rot)); - auto [it2, new_el2] = e.attrs().emplace("rt_translation", mvreg ()); - it2->second.write(std::move(tr)); - } else { - - e = G->crdt_engine().get_crdt_edge(n.id(), to, "RT").value_or(CRDTEdge()); - e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); - auto head_o = G->get_attrib_by_name(e); - std::optional> tstamps_o = G->get_attrib_by_name(e); - std::optional> tr_pack_o = G->get_attrib_by_name(e); - std::optional> rot_pack_o = G->get_attrib_by_name(e); - auto time_stamps = tstamps_o.value_or(std::vector(HISTORY_SIZE, 0)); - auto tr_pack = tr_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); - auto rot_pack = rot_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); - - if (time_stamps.size() < BLOCK_SIZE * HISTORY_SIZE) time_stamps.resize(HISTORY_SIZE); - if (tr_pack.size() < BLOCK_SIZE * HISTORY_SIZE) tr_pack.resize(BLOCK_SIZE * HISTORY_SIZE); - if (rot_pack.size() < BLOCK_SIZE * HISTORY_SIZE) rot_pack.resize(BLOCK_SIZE * HISTORY_SIZE); - - bool update_index = true; - auto timestamp_index = 0; - if (!head_o.has_value()) { - timestamp_index = 0; - } else { - timestamp_index = (int)(head_o.value_or(0)/BLOCK_SIZE) % HISTORY_SIZE; - } - int index = timestamp_index * BLOCK_SIZE; - - auto timestamp_v = (timestamp.has_value()) ? *timestamp : static_cast( - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()).count()); - - - - if (timestamp_v < time_stamps[prev(timestamp_index, HISTORY_SIZE)]) { - std::vector diffs; - std::transform(time_stamps.begin(), time_stamps.end(), std::back_inserter(diffs), - [t = *timestamp](auto &val) { - return ((int64_t)t - (int64_t)val > 0) ? ((int64_t)t - (int64_t)val) : std::numeric_limits::min(); - }); - - auto pos = (((std::min_element(diffs.begin(), diffs.end())) - diffs.begin())) % HISTORY_SIZE; - - // too old to insert it - if (pos == timestamp_index && timestamp_v < time_stamps[pos]) {return;} - if (pos > timestamp_index) { - update_index = false; - } - - time_stamps.erase(time_stamps.begin() + timestamp_index); - tr_pack.erase(tr_pack.begin() + index, tr_pack.begin() + index + 3); - rot_pack.erase(rot_pack.begin() + index, rot_pack.begin() + index + 3); - - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE, trans[0]); - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 1, trans[1]); - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 2, trans[2]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE, rot_euler[0]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 1, rot_euler[1]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 2, rot_euler[2]); - time_stamps.insert(time_stamps.begin() + pos, *timestamp); - - } else { - - tr_pack[index] = trans[0]; - tr_pack[index + 1] = trans[1]; - tr_pack[index + 2] = trans[2]; - rot_pack[index] = rot_euler[0]; - rot_pack[index + 1] = rot_euler[1]; - rot_pack[index + 2] = rot_euler[2]; - time_stamps[timestamp_index] = timestamp_v; - } - - CRDTAttribute tr(std::move(tr_pack), get_unix_timestamp(), 0); - CRDTAttribute rot(std::move(rot_pack), get_unix_timestamp(), 0); - CRDTAttribute head_index(index+3, get_unix_timestamp(), 0); - CRDTAttribute timestamps(std::move(time_stamps), get_unix_timestamp(), 0); - - auto [it, new_el] = e.attrs().insert_or_assign("rt_rotation_euler_xyz", mvreg ()); - it->second.write(std::move(rot)); - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_translation", mvreg ()); - it->second.write(std::move(tr)); - if (update_index) { - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_head_index", mvreg ()); - it->second.write(std::move(head_index)); - } - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_timestamps", mvreg ()); - it->second.write(std::move(timestamps)); - } - - const auto ensure_mutable_to_n = [&]() -> CRDTNode& { - if (!to_n_mut.has_value()) to_n_mut = *to_n; - return to_n_mut.value(); - }; - - if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) - { - if ( x.value() != n.id()) - { - no_send = !G->modify_attrib_local(ensure_mutable_to_n(), n.id()); - } - } - else - { - no_send = !G->add_attrib_local(ensure_mutable_to_n(), n.id()); - } - - if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) - { - if (x.value() != G->get_node_level(n).value() + 1) - { - no_send = !G->modify_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); - } - } - else - { - no_send = !G->add_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); - } - - //Check if RT edge exist. - if (!n.fano().contains({to, "RT"})) - { - //Create -> insert edge, update to-node attrs - std::tie(r1, node1_insert, std::ignore) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); - - } - else - { - //Update -> update edge attrs, update to-node attrs - std::tie(r1, std::ignore, node1_update) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); - - } - if (!r1) - { - throw std::runtime_error( - "Could not insert Node " + std::to_string(n.id()) + " in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - if (!r2 and !no_send) - { - throw std::runtime_error( - "Could not insert Node " + std::to_string(to_n_id.value()) + " in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - } else - throw std::runtime_error( - "Destination node " + std::to_string(to) + " not found in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - if (!G->copy) - { - if (node1_insert.has_value()) - { - G->dsrpub_edge.write(node1_insert.value()); - - } - if (node1_update.has_value()) G->dsrpub_edge_attrs.write(node1_update.value()); - - if (!no_send and node2.has_value()) G->dsrpub_node_attrs.write(node2.value()); - - G->emitter.update_edge_attr_signal(n.id(), to, "RT" ,{"rt_rotation_euler_xyz", "rt_translation"}, SignalInfo{ G->agent_id }); - G->emitter.update_edge_signal(n.id(), to, "RT", SignalInfo{ G->agent_id }); - if (!no_send) - { - G->emitter.update_node_signal(to_n_id.value(), to_n_type.value(), SignalInfo{ G->agent_id }); - G->emitter.update_node_attr_signal(to_n_id.value(), {"level", "parent"}, SignalInfo{ G->agent_id }); - } - } ->>>>>>> 5ae1438 (refactor: reduce legacy crdt graph wrappers) } void RT_API::insert_or_assign_edge_RT(Node &n, uint64_t to, std::vector &&trans, std::vector &&rot_euler, std::optional timestamp) diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index b31eef45..a1bef738 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -695,11 +695,6 @@ namespace DSR void on_remote_node_attrs_updated(uint64_t id, const std::string& type, const std::vector& attrs, uint32_t agent_id) override; void on_remote_edge_attrs_updated(uint64_t from, uint64_t to, const std::string& type, const std::vector& attrs, uint32_t agent_id) override; - CRDTSyncEngine& crdt_engine(); - const CRDTSyncEngine& crdt_engine() const; - LWWSyncEngine& lww_engine(); - const LWWSyncEngine& lww_engine() const; - ////////////////////////////////////////////////////////////////////////// // Non-blocking graph operations @@ -718,49 +713,49 @@ namespace DSR ThreadPool tp, tp_delta_attr; //Custom function for each rtps topic - class NewMessageFunctor { + class NewMessageFn { public: DSRGraph *graph{}; std::function f; - NewMessageFunctor(DSRGraph *graph_, + NewMessageFn(DSRGraph *graph_, std::function f_) : graph(graph_), f(std::move(f_)) {} - NewMessageFunctor() = default; + NewMessageFn() = default; void operator()(eprosima::fastdds::dds::DataReader* reader) const { f(reader, graph); }; }; - NewMessageFunctor make_node_subscription_functor(); - NewMessageFunctor make_edge_subscription_functor(); - NewMessageFunctor make_edge_attrs_subscription_functor(); - NewMessageFunctor make_node_attrs_subscription_functor(); - NewMessageFunctor make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + NewMessageFn make_node_subscription_functor(); + NewMessageFn make_edge_subscription_functor(); + NewMessageFn make_edge_attrs_subscription_functor(); + NewMessageFn make_node_attrs_subscription_functor(); + NewMessageFn make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); template - NewMessageFunctor make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal = false); + NewMessageFn make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal = false); template - NewMessageFunctor make_edge_subscription_functor_impl(const char* channel); + NewMessageFn make_edge_subscription_functor_impl(const char* channel); template - NewMessageFunctor make_edge_attrs_subscription_functor_impl(const char* channel); + NewMessageFn make_edge_attrs_subscription_functor_impl(const char* channel); template - NewMessageFunctor make_node_attrs_subscription_functor_impl(const char* channel); + NewMessageFn make_node_attrs_subscription_functor_impl(const char* channel); template - NewMessageFunctor make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated); + NewMessageFn make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated); //Custom function for each rtps topic - class ParticipantChangeFunctor { + class ParticipantChangeFn { public: DSRGraph *graph{}; std::function f; - ParticipantChangeFunctor(DSRGraph *graph_, + ParticipantChangeFn(DSRGraph *graph_, std::function f_) : graph(graph_), f(std::move(f_)) {} - ParticipantChangeFunctor() = default; + ParticipantChangeFn() = default; void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) const @@ -791,27 +786,27 @@ namespace DSR DSRPublisher dsrpub_node; DSRSubscriber dsrsub_node; - NewMessageFunctor dsrpub_call_node; + NewMessageFn dsrpub_call_node; DSRPublisher dsrpub_edge; DSRSubscriber dsrsub_edge; - NewMessageFunctor dsrpub_call_edge; + NewMessageFn dsrpub_call_edge; DSRPublisher dsrpub_node_attrs; DSRSubscriber dsrsub_node_attrs; - NewMessageFunctor dsrpub_call_node_attrs; + NewMessageFn dsrpub_call_node_attrs; DSRPublisher dsrpub_edge_attrs; DSRSubscriber dsrsub_edge_attrs; - NewMessageFunctor dsrpub_call_edge_attrs; + NewMessageFn dsrpub_call_edge_attrs; DSRSubscriber dsrsub_graph_request; DSRPublisher dsrpub_graph_request; - NewMessageFunctor dsrpub_graph_request_call; + NewMessageFn dsrpub_graph_request_call; DSRSubscriber dsrsub_request_answer; DSRPublisher dsrpub_request_answer; - NewMessageFunctor dsrpub_request_answer_call; + NewMessageFn dsrpub_request_answer_call; Q_OBJECT signals: diff --git a/core/include/dsr/core/id_generator.h b/core/include/dsr/core/id_generator.h index ae81c8ed..543d97aa 100644 --- a/core/include/dsr/core/id_generator.h +++ b/core/include/dsr/core/id_generator.h @@ -10,7 +10,7 @@ * as it is not intended to be used on architectures that do not support * unsigned 64-bits numbers. * - * Each timestamp represent a 10 milliseconds periods since 2021-01-01 00:00:00 GTM. + * Each timestamp represent a 10 milliseconds periods since 2026-04-23 00:00:00 GTM. * The counter is used to differentiate between ids generated in the same timestamp. * The id allows to generate unique ids in a distributed environment as long as the id * is unique. @@ -57,7 +57,7 @@ class id_generator throw std::logic_error("agent_id must be between 0 and 4095"); } - start_time = 1609459200000000000; // epoch of 2021-01-01 00:00:00 GMT in nanoseconds + start_time = 1776902400000000000; // epoch of 2026-04-23 00:00:00 GMT in nanoseconds elapsed_time = 0; agent_id = agent_id_; counter = 0; diff --git a/tests/graph/rt_timestamp.cpp b/tests/graph/rt_timestamp.cpp index 60bf3677..bad5b774 100644 --- a/tests/graph/rt_timestamp.cpp +++ b/tests/graph/rt_timestamp.cpp @@ -3,6 +3,7 @@ #include "../utils.h" #include "catch2/catch_test_macros.hpp" +#include #include #include @@ -13,10 +14,11 @@ using namespace DSR; //TODO: add REQUIRES, I'm checking manually TEST_CASE("RT api timestamp", "[GRAPH][RT]") { + const auto sync_mode = GENERATE(SyncMode::CRDT, SyncMode::LWW); + INFO("sync_mode=" << sync_mode_label(sync_mode)); auto ctx = make_edge_config_file(); auto id1 = rand() % 1000; - int argc = 0; - DSRGraph G(random_string(10), id1, ctx); + DSRGraph G(make_test_graph_settings(random_string(10), id1, ctx, true, 0, SignalMode::QT, sync_mode)); auto node_name = random_string(); auto n = Node::create(node_name); G.add_attrib_local(n, 0); From 84f73bff16c657bb3d3d58a7a3f84f62e6e00085 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 23 Apr 2026 13:45:00 +0200 Subject: [PATCH 22/38] refactor: unify lww and crdt apis --- api/dsr_crdt_sync_engine.cpp | 38 +++++----- core/include/dsr/core/types/crdt_io.h | 35 +++++++++ core/include/dsr/core/types/user_types.h | 90 ------------------------ 3 files changed, 54 insertions(+), 109 deletions(-) diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index b31283d2..7b554b6b 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -91,7 +91,7 @@ std::unique_ptr CRDTSyncEngine::clone(SyncEngineHost& host) const std::optional CRDTSyncEngine::get_node(uint64_t id) const { if (const auto* node = get_node_ptr(id); node != nullptr) { - return Node(*node); + return to_user_node(*node); } return {}; } @@ -99,7 +99,7 @@ std::optional CRDTSyncEngine::get_node(uint64_t id) const std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { - return Edge(std::move(edge.value())); + return to_user_edge(*edge); } return {}; } @@ -129,7 +129,7 @@ bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor if (const auto* node = get_node_ptr(from); node != nullptr) { for (const auto& [key, edge_reg] : node->fano()) { if (!edge_reg.empty()) { - Edge edge(edge_reg.read_reg()); + Edge edge = to_user_edge(edge_reg.read_reg()); visitor(key.first, key.second, edge); } } @@ -144,7 +144,7 @@ bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vi host_.for_each_incoming_edge(to, [&](uint64_t from, const std::string& type) { found = true; if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { - Edge out(std::move(*edge)); + Edge out = to_user_edge(*edge); visitor(from, type, out); } }); @@ -155,7 +155,7 @@ void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedE { host_.for_each_edge_of_type_cache(type, [&](uint64_t from, uint64_t to) { if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { - Edge out(std::move(*edge)); + Edge out = to_user_edge(*edge); visitor(from, to, out); } }); @@ -175,7 +175,7 @@ std::map CRDTSyncEngine::snapshot() const DSR_LOG_WARNING_L(log_level, "[CRDT] snapshot skipping empty node register", id); continue; } - out.emplace(id, Node(reg.read_reg())); + out.emplace(id, to_user_node(reg.read_reg())); } return out; } @@ -219,7 +219,7 @@ NodeMutationEffect CRDTSyncEngine::delete_node_local(uint64_t id) effect.id = id; effect.deleted_edges = std::move(deleted_edges); if (node.has_value()) { - effect.deleted_node = Node(*node); + effect.deleted_node = to_user_node(*node); } if (delta_node.has_value()) { effect.node_delta = NodeDeltaMessage{*delta_node}; @@ -399,7 +399,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR } uint64_t id = node.id(); - host_.update_maps_node_insert(Node(node)); + host_.update_maps_node_insert(to_user_node(node)); auto delta = nodes_[id].write(std::move(node)); nodes_[id].join(mvreg(delta)); return {true, crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta))}; @@ -457,7 +457,7 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) std::vector delta_vec; for (const auto& v : node.fano()) { - deleted_edges.emplace_back(v.second.read_reg()); + deleted_edges.emplace_back(to_user_edge(v.second.read_reg())); } auto delta = nodes_[id].reset(); nodes_.erase(id); @@ -471,7 +471,7 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) { if (!nodes_.contains(from)) continue; auto& visited_node = nodes_.at(from).read_reg(); - deleted_edges.emplace_back(visited_node.fano().at({id, type}).read_reg()); + deleted_edges.emplace_back(to_user_edge(visited_node.fano().at({id, type}).read_reg())); auto delta_fano = visited_node.fano().at({id, type}).reset(); delta_vec.emplace_back(crdt_edge_to_msg(host_.local_agent_id(), from, id, type, std::move(delta_fano))); visited_node.fano().erase({id, type}); @@ -479,7 +479,7 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) } } - host_.update_maps_node_delete(id, std::make_optional(Node(node))); + host_.update_maps_node_delete(id, std::make_optional(to_user_node(node))); return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; } @@ -707,13 +707,13 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) }); } std::optional deleted_node_user = maybe_deleted_node.has_value() - ? std::make_optional(Node(*maybe_deleted_node)) : std::nullopt; + ? std::make_optional(to_user_node(*maybe_deleted_node)) : std::nullopt; host_.update_maps_node_delete(id, deleted_node_user); delete_unprocessed_deltas(); } else { const auto& reg = nodes_.at(id).read_reg(); current_type = reg.type(); - host_.update_maps_node_insert(Node(reg)); + host_.update_maps_node_insert(to_user_node(reg)); consume_unprocessed_deltas(); } signal = !d_empty; @@ -735,11 +735,11 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) } } else { std::optional deleted_node_user = maybe_deleted_node.has_value() - ? std::make_optional(Node(*maybe_deleted_node)) : std::nullopt; + ? std::make_optional(to_user_node(*maybe_deleted_node)) : std::nullopt; std::vector deleted_edges_user; if (maybe_deleted_node.has_value()) { for (const auto& [key, mvreg_edge] : maybe_deleted_node->fano()) { - deleted_edges_user.emplace_back(mvreg_edge.read_reg()); + deleted_edges_user.emplace_back(to_user_edge(mvreg_edge.read_reg())); } } host_.on_remote_node_deleted(id, deleted_node_user, deleted_edges_user, mvreg.agent_id); @@ -1044,13 +1044,13 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } it->second.join(std::move(mv)); if (mv_empty or it->second.empty()) { - std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; + std::optional nd_user = nd.has_value() ? std::make_optional(to_user_node(*nd)) : std::nullopt; host_.update_maps_node_delete(k, nd_user); updates.emplace_back(false, k, "", std::nullopt, std::nullopt); delete_unprocessed_deltas(); } else { const auto& reg = it->second.read_reg(); - host_.update_maps_node_insert(Node(reg)); + host_.update_maps_node_insert(to_user_node(reg)); updates.emplace_back(true, k, reg.type(), nd, reg); consume_unprocessed_deltas(); } @@ -1067,7 +1067,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) for (const auto &[k, v] : nd->fano()) { if (!iter.contains(k)) { std::optional del_edge = (v.dk.ds.size() > 0) - ? std::make_optional(Edge(v.read_reg())) : std::nullopt; + ? std::make_optional(to_user_edge(v.read_reg())) : std::nullopt; host_.on_remote_edge_deleted(node_id, k.first, k.second, del_edge, agent_id_ch); } } @@ -1077,7 +1077,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } } } else { - std::optional nd_user = nd.has_value() ? std::make_optional(Node(*nd)) : std::nullopt; + std::optional nd_user = nd.has_value() ? std::make_optional(to_user_node(*nd)) : std::nullopt; host_.on_remote_node_deleted(node_id, nd_user, {}, agent_id_ch); } } diff --git a/core/include/dsr/core/types/crdt_io.h b/core/include/dsr/core/types/crdt_io.h index db48e2b2..edb23fff 100644 --- a/core/include/dsr/core/types/crdt_io.h +++ b/core/include/dsr/core/types/crdt_io.h @@ -101,6 +101,41 @@ inline CRDTEdge user_edge_to_crdt(const Edge& edge) return crdt_edge; } +inline Edge to_user_edge(const CRDTEdge& edge) +{ + Edge out(edge.to(), edge.from(), edge.type(), {}, edge.agent_id()); + auto& attrs = out.attrs(); + for (const auto& [name, attr] : edge.attrs()) { + if (!attr.empty()) { + attrs.emplace(name, attr.read_reg()); + } + } + return out; +} + +inline Node to_user_node(const CRDTNode& node) +{ + Node out(node.agent_id(), node.type()); + out.id(node.id()); + out.name(node.name()); + + auto& attrs = out.attrs(); + for (const auto& [name, attr] : node.attrs()) { + if (!attr.empty()) { + attrs.emplace(name, attr.read_reg()); + } + } + + auto& fano = out.fano(); + for (const auto& [key, edge] : node.fano()) { + if (!edge.empty()) { + fano.emplace(key, to_user_edge(edge.read_reg())); + } + } + + return out; +} + inline CRDTNode user_node_to_crdt(Node&& node) { CRDTNode crdt_node; diff --git a/core/include/dsr/core/types/user_types.h b/core/include/dsr/core/types/user_types.h index fcf1c689..5324ae80 100644 --- a/core/include/dsr/core/types/user_types.h +++ b/core/include/dsr/core/types/user_types.h @@ -9,7 +9,6 @@ #include #include "type_checking/type_checker.h" #include "common_types.h" -#include "crdt_types.h" #include @@ -75,45 +74,6 @@ namespace DSR { return Edge(from, to, std::string(edge_type::attr_name.data()), 0, attrs); } - explicit Edge (const CRDTEdge& edge) - { - m_agent_id = edge.agent_id(); - m_from = edge.from(); - m_to = edge.to(); - m_type = edge.type(); - for (const auto &[k,v] : edge.attrs()) { - assert(!v.dk.ds.empty()); - m_attrs.emplace(k, v.dk.ds.begin()->second); - } - - } - - explicit Edge (CRDTEdge&& edge) - { - m_agent_id = edge.agent_id(); - m_from = edge.from(); - m_to = edge.to(); - m_type = edge.type(); - for (auto &[k,v] : edge.attrs()) { - assert(!v.dk.ds.empty()); - m_attrs.emplace(k, std::move(v.dk.ds.begin()->second)); - } - - } - - Edge& operator= (const CRDTEdge& attr) - { - m_agent_id = attr.agent_id(); - m_from = attr.from(); - m_to = attr.to(); - m_type = attr.type(); - for (const auto &[k,v] : attr.attrs()) { - assert(!v.dk.ds.empty()); - m_attrs.emplace(k, v.dk.ds.begin()->second); - } - return *this; - } - [[nodiscard]] uint64_t to() const; [[nodiscard]] uint64_t from() const; @@ -256,56 +216,6 @@ namespace DSR { return Node( std::string(node_type::attr_name.data()), 0, attrs, fano, name); } - explicit Node (const CRDTNode& node) - { - m_agent_id = node.agent_id(); - m_id = node.id(); - m_name = node.name(); - m_type = node.type(); - for (const auto &[k,v] : node.attrs()) { - if (v.dk.ds.empty()) continue; // guard: skip attrs with empty delta-set (partial network update) - m_attrs.emplace(k, v.dk.ds.begin()->second); - } - for (const auto &[k,v] : node.fano()) { - if (v.dk.ds.empty()) continue; // guard: skip edges with empty delta-set - m_fano.emplace(k, v.dk.ds.begin()->second); - } - } - - explicit Node (CRDTNode&& node) - { - m_agent_id = node.agent_id(); - m_id = node.id(); - m_name = node.name(); - m_type = node.type(); - for (auto &[k,v] : node.attrs()) { - if (v.dk.ds.empty()) continue; // guard: skip attrs with empty delta-set - m_attrs.emplace(k, std::move(v.dk.ds.begin()->second)); - } - for (auto &[k,v] : node.fano()) { - if (v.dk.ds.empty()) continue; // guard: skip edges with empty delta-set - m_fano.emplace(k, std::move(v.dk.ds.begin()->second)); - } - } - - Node& operator= (const CRDTNode& node ) - { - m_agent_id = node.agent_id(); - m_id = node.id(); - m_name = node.name(); - m_type = node.type(); - for (const auto &[k,v] : node.attrs()) { - if (v.dk.ds.empty()) continue; // guard: skip attrs with empty delta-set - m_attrs.emplace(k, v.dk.ds.begin()->second); - } - for (const auto &[k,v] : node.fano()) { - if (v.dk.ds.empty()) continue; // guard: skip edges with empty delta-set - m_fano.emplace(k, v.dk.ds.begin()->second); - } - - return *this; - } - [[nodiscard]] uint64_t id() const; [[nodiscard]] const std::string &type() const; From 5ce3c4fdc133ce644eecbf899b2a99f426c5c0a0 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 23 Apr 2026 22:19:31 +0200 Subject: [PATCH 23/38] refactor: tests and benchmarks --- benchmarks/CMakeLists.txt | 3 +- .../consistency/conflict_rate_bench.cpp | 90 +----- .../consistency/convergence_time_bench.cpp | 111 +++---- benchmarks/latency/crdt_join_bench.cpp | 50 +-- .../latency/delta_propagation_bench.cpp | 24 +- benchmarks/latency/type_conversion_bench.cpp | 259 ++++++++++++++++ benchmarks/report.py | 160 ++++++++-- benchmarks/run_benchmarks.py | 6 +- .../scalability/agent_scaling_bench.cpp | 65 +--- .../scalability/graph_size_impact_bench.cpp | 82 +++++ .../scalability/multi_agent_sync_bench.cpp | 286 ------------------ .../scalability/thread_scaling_bench.cpp | 108 +------ .../throughput/concurrent_writers_bench.cpp | 8 +- benchmarks/throughput/query_ops_bench.cpp | 131 -------- tests/synchronization/graph_signals.cpp | 4 +- .../synchronization/graph_synchronization.cpp | 4 + tests/synchronization/lww_sync_engine.cpp | 13 +- 17 files changed, 607 insertions(+), 797 deletions(-) create mode 100644 benchmarks/latency/type_conversion_bench.cpp delete mode 100644 benchmarks/scalability/multi_agent_sync_bench.cpp delete mode 100644 benchmarks/throughput/query_ops_bench.cpp diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index a72bfd77..ac73d385 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -34,15 +34,14 @@ set(BENCHMARK_SOURCES latency/delta_propagation_bench.cpp latency/signal_latency_bench.cpp latency/crdt_join_bench.cpp + latency/type_conversion_bench.cpp # Throughput benchmarks throughput/single_agent_ops_bench.cpp throughput/concurrent_writers_bench.cpp throughput/single_agent_ops_with_latency_bench.cpp - throughput/query_ops_bench.cpp # Scalability benchmarks - scalability/multi_agent_sync_bench.cpp scalability/graph_size_impact_bench.cpp scalability/thread_scaling_bench.cpp scalability/graph_size_scaling_bench.cpp diff --git a/benchmarks/consistency/conflict_rate_bench.cpp b/benchmarks/consistency/conflict_rate_bench.cpp index fd76cb70..7f825be6 100644 --- a/benchmarks/consistency/conflict_rate_bench.cpp +++ b/benchmarks/consistency/conflict_rate_bench.cpp @@ -13,7 +13,7 @@ using namespace DSR; using namespace DSR::Benchmark; -TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][CONFLICT][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("conflict_rate"); @@ -34,7 +34,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ fixture.wait_for_sync(); REQUIRE(fixture.verify_convergence()); - constexpr int NUM_ROUNDS = 50; + constexpr int NUM_ROUNDS = 20; constexpr int UPDATES_PER_AGENT = 10; constexpr size_t NUM_AGENTS = 4; @@ -76,7 +76,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ } // Wait for convergence - fixture.wait_for_sync(std::chrono::milliseconds(500)); + fixture.wait_for_sync(std::chrono::milliseconds(200)); // Check if all agents converged to the same value std::set final_values; @@ -111,79 +111,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ INFO("Total updates: " << total_updates.load()); // Verify final convergence - fixture.wait_for_sync(std::chrono::milliseconds(1000)); - CHECK(fixture.verify_convergence()); - } - - SECTION("Concurrent node creations - potential ID conflicts") { - // This tests CRDT behavior when multiple agents create nodes - MultiAgentFixture fixture; - auto config_file = generator.generate_empty_graph(); - REQUIRE(fixture.create_agents(4, config_file)); - fixture.wait_for_sync(); - - constexpr int NODES_PER_AGENT = 100; - constexpr size_t NUM_AGENTS = 4; - - std::atomic total_created{0}; - std::atomic creation_failures{0}; - - std::barrier sync_point(NUM_AGENTS); - std::vector threads; - threads.reserve(NUM_AGENTS); - - for (size_t agent_idx = 0; agent_idx < NUM_AGENTS; ++agent_idx) { - threads.emplace_back([&, agent_idx]() { - auto* agent = fixture.get_agent(agent_idx); - sync_point.arrive_and_wait(); - - for (int i = 0; i < NODES_PER_AGENT; ++i) { - // Each agent uses unique IDs in its range - uint64_t node_id = 8500000 + agent_idx * 10000 + i; - auto node = GraphGenerator::create_test_node( - node_id, agent->get_agent_id(), - "agent" + std::to_string(agent_idx) + "_node" + std::to_string(i)); - - auto result = agent->insert_node(node); - if (result.has_value()) { - total_created.fetch_add(1, std::memory_order_relaxed); - } else { - creation_failures.fetch_add(1, std::memory_order_relaxed); - } - } - }); - } - - for (auto& t : threads) { - t.join(); - } - - // Wait for convergence - fixture.wait_for_sync(std::chrono::milliseconds(2000)); - - // Verify all agents have the same nodes - auto* agent_0 = fixture.get_agent(0); - size_t expected_node_count = agent_0->get_nodes().size(); - - bool all_match = true; - for (size_t i = 1; i < NUM_AGENTS; ++i) { - auto* agent = fixture.get_agent(i); - if (agent->get_nodes().size() != expected_node_count) { - all_match = false; - } - } - - collector.record_consistency("node_creation_success_rate", - static_cast(total_created.load()) / - static_cast(NODES_PER_AGENT * NUM_AGENTS) * 100.0, "%"); - - collector.record_consistency("final_convergence", - all_match ? 100.0 : 0.0, "%"); - - INFO("Created: " << total_created.load() << "/" << NODES_PER_AGENT * NUM_AGENTS); - INFO("Failures: " << creation_failures.load()); - INFO("All agents converged: " << (all_match ? "yes" : "no")); - + fixture.wait_for_sync(std::chrono::milliseconds(500)); CHECK(fixture.verify_convergence()); } @@ -210,7 +138,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ REQUIRE(fixture.verify_convergence()); uint64_t conflicts = 0; - constexpr int NUM_ROUNDS = 50; + constexpr int NUM_ROUNDS = 20; for (int round = 0; round < NUM_ROUNDS; ++round) { // Both agents try to create the same edge simultaneously @@ -225,7 +153,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ ta.join(); tb.join(); - fixture.wait_for_sync(std::chrono::milliseconds(200)); + fixture.wait_for_sync(std::chrono::milliseconds(100)); // Check both agents see the edge auto edge_on_a = agent_a->get_edge(node1_id, node2_id, "test_edge"); @@ -237,7 +165,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ // Delete edge for next round agent_a->delete_edge(node1_id, node2_id, "test_edge"); - fixture.wait_for_sync(std::chrono::milliseconds(100)); + fixture.wait_for_sync(std::chrono::milliseconds(50)); } double conflict_rate = static_cast(conflicts) / @@ -254,7 +182,7 @@ TEST_CASE("Conflict rate benchmarks", "[CONSISTENCY][conflict][.multi][PROFILE][ reporter.export_all(result, "conflict_rate"); } -TEST_CASE("CRDT eventual consistency verification", "[CONSISTENCY][eventual][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("CRDT eventual consistency verification", "[CONSISTENCY][EVENTUAL][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("eventual_consistency"); @@ -286,7 +214,7 @@ TEST_CASE("CRDT eventual consistency verification", "[CONSISTENCY][eventual][.mu // Insert node auto node = GraphGenerator::create_test_node( base_id + i, agent->get_agent_id()); - agent->insert_node(node); + agent->insert_node_with_id(node); } else if (op == 1) { // Update existing node auto node = agent->get_node(base_id + (i % (std::max(1, i / 2)))); diff --git a/benchmarks/consistency/convergence_time_bench.cpp b/benchmarks/consistency/convergence_time_bench.cpp index fa777846..bfa2d210 100644 --- a/benchmarks/consistency/convergence_time_bench.cpp +++ b/benchmarks/consistency/convergence_time_bench.cpp @@ -13,7 +13,7 @@ using namespace DSR; using namespace DSR::Benchmark; -TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("convergence_time"); @@ -28,39 +28,40 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO REQUIRE(agent_a != nullptr); REQUIRE(agent_b != nullptr); - LatencyTracker tracker(100); + constexpr int ITERATIONS = 50; + constexpr uint64_t TIMEOUT_NS = 5'000'000'000ULL; // 5 s in ns + LatencyTracker tracker(ITERATIONS); - for (int i = 0; i < 100; ++i) { + for (int i = 0; i < ITERATIONS; ++i) { auto node = GraphGenerator::create_test_node( 0, agent_a->get_agent_id(), "conv_node_" + std::to_string(i)); - uint64_t start = get_unix_timestamp(); + uint64_t start = bench_now(); auto result = agent_a->insert_node(node); if (!result.has_value()) continue; uint64_t node_id = result.value(); - // Poll until agent B sees the node + bool converged = false; auto poll_start = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - poll_start < std::chrono::seconds(5)) { fixture.process_events(1); - auto b_node = agent_b->get_node(node_id); - if (b_node.has_value()) { - uint64_t conv_time = get_unix_timestamp() - start; - tracker.record(conv_time); + if (agent_b->get_node(node_id).has_value()) { + converged = true; break; } } + + tracker.record(converged ? bench_now() - start : TIMEOUT_NS); } auto stats = tracker.stats(); collector.record_latency_stats("single_node_convergence", stats); collector.record_consistency("convergence_success_rate", - (static_cast(tracker.count()) / 100.0) * 100, "%"); + (static_cast(tracker.count()) / ITERATIONS) * 100, "%"); INFO("Single node convergence - Mean: " << stats.mean_us() << " us, " << "P99: " << stats.p99_us() << " us"); - INFO("Success rate: " << tracker.count() << "/100"); } SECTION("Batch convergence time") { @@ -72,43 +73,35 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO auto* agent_a = fixture.get_agent(0); auto* agent_b = fixture.get_agent(1); - LatencyTracker tracker(20); + constexpr int BATCHES = 10; + constexpr uint64_t TIMEOUT_NS = 10'000'000'000ULL; + LatencyTracker tracker(BATCHES); - for (int batch = 0; batch < 20; ++batch) { - // Insert batch of 10 nodes and capture actual IDs + for (int batch = 0; batch < BATCHES; ++batch) { std::vector node_ids; node_ids.reserve(10); - uint64_t start = get_unix_timestamp(); + uint64_t start = bench_now(); for (int i = 0; i < 10; ++i) { - auto node = GraphGenerator::create_test_node( - 0, agent_a->get_agent_id()); + auto node = GraphGenerator::create_test_node(0, agent_a->get_agent_id()); auto result = agent_a->insert_node(node); - if (result.has_value()) { - node_ids.push_back(result.value()); - } + if (result.has_value()) node_ids.push_back(result.value()); } - // Wait for all nodes to converge + bool converged = false; auto poll_start = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - poll_start < std::chrono::seconds(10)) { fixture.process_events(1); - bool all_converged = true; + bool all = true; for (auto id : node_ids) { - if (!agent_b->get_node(id).has_value()) { - all_converged = false; - break; - } - } - - if (all_converged) { - uint64_t conv_time = get_unix_timestamp() - start; - tracker.record(conv_time); - break; + if (!agent_b->get_node(id).has_value()) { all = false; break; } } + if (all) { converged = true; break; } } + + tracker.record(converged ? bench_now() - start : TIMEOUT_NS); } auto stats = tracker.stats(); @@ -123,23 +116,22 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO REQUIRE(fixture.create_agents(4, config_file)); fixture.wait_for_sync(); - LatencyTracker tracker(50); + constexpr int ROUNDS = 30; + constexpr uint64_t TIMEOUT_NS = 15'000'000'000ULL; + LatencyTracker tracker(ROUNDS); - // Each agent creates nodes concurrently - for (int round = 0; round < 50; ++round) { + for (int round = 0; round < ROUNDS; ++round) { std::vector all_node_ids; std::mutex ids_mutex; - uint64_t start = get_unix_timestamp(); + uint64_t start = bench_now(); - // Each agent creates 5 nodes in parallel std::vector threads; for (size_t agent_idx = 0; agent_idx < 4; ++agent_idx) { threads.emplace_back([&, agent_idx]() { auto* agent = fixture.get_agent(agent_idx); for (int i = 0; i < 5; ++i) { - auto node = GraphGenerator::create_test_node( - 0, agent->get_agent_id()); + auto node = GraphGenerator::create_test_node(0, agent->get_agent_id()); auto result = agent->insert_node(node); if (result.has_value()) { std::lock_guard lock(ids_mutex); @@ -150,28 +142,22 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO } for (auto& t : threads) t.join(); - // Wait for all agents to see all nodes + bool converged = false; auto poll_start = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - poll_start < std::chrono::seconds(15)) { fixture.process_events(5); - bool all_converged = true; - for (size_t agent_idx = 0; agent_idx < 4 && all_converged; ++agent_idx) { + bool all = true; + for (size_t agent_idx = 0; agent_idx < 4 && all; ++agent_idx) { auto* agent = fixture.get_agent(agent_idx); for (auto id : all_node_ids) { - if (!agent->get_node(id).has_value()) { - all_converged = false; - break; - } + if (!agent->get_node(id).has_value()) { all = false; break; } } } - - if (all_converged) { - uint64_t conv_time = get_unix_timestamp() - start; - tracker.record(conv_time); - break; - } + if (all) { converged = true; break; } } + + tracker.record(converged ? bench_now() - start : TIMEOUT_NS); } auto stats = tracker.stats(); @@ -180,8 +166,7 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO INFO("Concurrent convergence (4 agents) - Mean: " << stats.mean_ms() << " ms, " << "P99: " << stats.p99_ms() << " ms"); - // Check against timeout - CHECK(stats.p99_ms() < 1000); // Should converge within 1 second p99 + CHECK(stats.p99_ms() < 1000); } auto result = collector.finalize(); @@ -189,7 +174,7 @@ TEST_CASE("Convergence time benchmarks", "[CONSISTENCY][convergence][.multi][PRO reporter.export_all(result, "convergence_time"); } -TEST_CASE("Attribute convergence", "[CONSISTENCY][convergence][attributes][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Attribute convergence", "[CONSISTENCY][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("attribute_convergence"); @@ -201,7 +186,6 @@ TEST_CASE("Attribute convergence", "[CONSISTENCY][convergence][attributes][.mult auto* agent_a = fixture.get_agent(0); auto* agent_b = fixture.get_agent(1); - // Create shared test node and capture actual ID auto test_node = GraphGenerator::create_test_node( 0, agent_a->get_agent_id(), "attr_conv_test"); auto insert_result = agent_a->insert_node(test_node); @@ -212,19 +196,21 @@ TEST_CASE("Attribute convergence", "[CONSISTENCY][convergence][attributes][.mult REQUIRE(fixture.verify_convergence()); SECTION("Attribute update convergence") { - LatencyTracker tracker(100); + constexpr int ITERATIONS = 50; + constexpr uint64_t TIMEOUT_NS = 5'000'000'000ULL; + LatencyTracker tracker(ITERATIONS); - for (int i = 0; i < 100; ++i) { + for (int i = 0; i < ITERATIONS; ++i) { auto node = agent_a->get_node(shared_node_id); REQUIRE(node.has_value()); int32_t new_value = 1000 + i; agent_a->add_or_modify_attrib_local(*node, new_value); - uint64_t start = get_unix_timestamp(); + uint64_t start = bench_now(); agent_a->update_node(*node); - // Wait for attribute to converge + bool converged = false; auto poll_start = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - poll_start < std::chrono::seconds(5)) { fixture.process_events(1); @@ -233,12 +219,13 @@ TEST_CASE("Attribute convergence", "[CONSISTENCY][convergence][attributes][.mult if (b_node.has_value()) { auto attr = agent_b->get_attrib_by_name(*b_node); if (attr.has_value() && attr.value() == new_value) { - uint64_t conv_time = get_unix_timestamp() - start; - tracker.record(conv_time); + converged = true; break; } } } + + tracker.record(converged ? bench_now() - start : TIMEOUT_NS); } auto stats = tracker.stats(); diff --git a/benchmarks/latency/crdt_join_bench.cpp b/benchmarks/latency/crdt_join_bench.cpp index 8d7e6fc1..28bedaca 100644 --- a/benchmarks/latency/crdt_join_bench.cpp +++ b/benchmarks/latency/crdt_join_bench.cpp @@ -20,7 +20,8 @@ static DSR::CRDTAttribute make_test_attribute(uint32_t agent_id, int32_t value) // All four mvreg operations in a single TEST_CASE so they export together // to one JSON file. -TEST_CASE("CRDT mvreg operations", "[CRDT][mvreg][BASELINE]") { +TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { + if (strcmp(sync_mode_name(default_config().sync_mode),"lww")) return; MetricsCollector collector("crdt_mvreg"); collector.add_metadata("profile", "baseline"); @@ -34,6 +35,7 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][mvreg][BASELINE]") { bench.run("mvreg_write", [&] { auto attr = make_test_attribute(100, i++); auto delta = reg.write(attr); + ankerl::nanobench::doNotOptimizeAway(attr); ankerl::nanobench::doNotOptimizeAway(delta); }); collector.record_latency_stats("mvreg_write", nb_to_stats(bench)); @@ -106,7 +108,8 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][mvreg][BASELINE]") { reporter.export_all(result, "crdt_mvreg"); } -TEST_CASE("CRDT dot_context operations", "[CRDT][dot_context][BASELINE]") { +TEST_CASE("CRDT dot_context operations", "[CRDT][DOT_CONTEXT][BASELINE]") { + if (strcmp(sync_mode_name(default_config().sync_mode),"lww")) return; MetricsCollector collector("crdt_dot_context"); collector.add_metadata("profile", "baseline"); @@ -172,46 +175,3 @@ TEST_CASE("CRDT dot_context operations", "[CRDT][dot_context][BASELINE]") { ReportGenerator reporter("results"); reporter.export_all(result, "crdt_dot_context"); } - -// Catch2 BENCHMARK macros — kept hidden; run with [!benchmark] to activate. -TEST_CASE("CRDT micro-benchmarks (Catch2 BENCHMARK)", "[.][crdt][!benchmark]") { - - BENCHMARK("mvreg write") { - mvreg reg; - reg.id = 100; - auto attr = make_test_attribute(100, 42); - return reg.write(attr); - }; - - BENCHMARK("mvreg join") { - mvreg reg; - reg.id = 100; - auto attr1 = make_test_attribute(100, 1); - auto delta = reg.write(attr1); - - mvreg delta_reg; - delta_reg.id = 200; - delta_reg.join(std::move(delta)); - auto attr2 = make_test_attribute(200, 2); - delta = delta_reg.write(attr2); - - reg.join(std::move(delta)); - return reg.read_reg(); - }; - - BENCHMARK("dot_context makedot") { - dot_context ctx; - return ctx.makedot(100); - }; - - BENCHMARK("dot_context join") { - dot_context ctx1; - dot_context ctx2; - for (int i = 0; i < 10; ++i) { - ctx1.makedot(100); - ctx2.makedot(200); - } - ctx1.join(ctx2); - return ctx1.cc.size(); - }; -} diff --git a/benchmarks/latency/delta_propagation_bench.cpp b/benchmarks/latency/delta_propagation_bench.cpp index b301352c..233dd018 100644 --- a/benchmarks/latency/delta_propagation_bench.cpp +++ b/benchmarks/latency/delta_propagation_bench.cpp @@ -13,8 +13,8 @@ using namespace DSR; using namespace DSR::Benchmark; // Multi-agent tests require working DDS synchronization -// Skip these by default - run with "[delta]" tag explicitly to test -TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][PROFILE][MULTIAGENT]") { +// Skip these by default - run with "[DELTA]" tag explicitly to test +TEST_CASE("Delta propagation latency between agents", "[LATENCY][DELTA][PROFILE][MULTIAGENT]") { // Setup MultiAgentFixture fixture; GraphGenerator generator; @@ -42,7 +42,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ QObject::connect(agent_b, &DSR::DSRGraph::update_node_signal, agent_b, [&](uint64_t id, const std::string& type, DSR::SignalInfo) { if (id == expected_node_id.load(std::memory_order_acquire)) { - receive_time.store(get_unix_timestamp()); + receive_time.store(bench_now()); received.store(true); } }, Qt::DirectConnection); @@ -63,7 +63,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ expected_node_id, agent_a->get_agent_id(), "bench_node_" + std::to_string(i)); - uint64_t send_time = get_unix_timestamp(); + uint64_t send_time = bench_now(); auto ins_result = agent_a->insert_node(node); REQUIRE(ins_result.has_value()); expected_node_id.store(ins_result.value(), std::memory_order_release); @@ -121,7 +121,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ [&](uint64_t from, uint64_t to, const std::string& type, DSR::SignalInfo) { if (from == expected_from.load(std::memory_order_acquire) && to == expected_to.load(std::memory_order_acquire)) { - receive_time.store(get_unix_timestamp()); + receive_time.store(bench_now()); received.store(true); } }, Qt::DirectConnection); @@ -143,7 +143,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ auto edge = GraphGenerator::create_test_edge( expected_from, expected_to, agent_a->get_agent_id()); - uint64_t send_time = get_unix_timestamp(); + uint64_t send_time = bench_now(); agent_a->insert_or_assign_edge(edge); // Wait for signal with timeout @@ -191,7 +191,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ QObject::connect(agent_b, &DSR::DSRGraph::update_node_attr_signal, agent_b, [&](uint64_t id, const std::vector& att_names, DSR::SignalInfo) { if (id == *insert_result) { - receive_time.store(get_unix_timestamp()); + receive_time.store(bench_now()); received.store(true); } }, Qt::DirectConnection); @@ -215,7 +215,7 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ agent_a->add_or_modify_attrib_local(*node, static_cast(1000 + i)); - uint64_t send_time = get_unix_timestamp(); + uint64_t send_time = bench_now(); agent_a->update_node(*node); // Wait for signal with timeout @@ -246,11 +246,11 @@ TEST_CASE("Delta propagation latency between agents", "[LATENCY][delta][.multi][ reporter.export_all(result, "delta_propagation"); } -TEST_CASE("Delta propagation with varying agent counts", "[LATENCY][delta][scalability][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Delta propagation with varying agent counts", "[LATENCY][DELTA][scalability][PROFILE][MULTIAGENT]") { MetricsCollector collector("delta_propagation_scaling"); GraphGenerator generator; - for (uint32_t num_agents : {2, 4, 8}) { + for (uint32_t num_agents : {2, 4}) { SECTION("With " + std::to_string(num_agents) + " agents") { MultiAgentFixture fixture; auto config_file = generator.generate_empty_graph(); @@ -282,7 +282,7 @@ TEST_CASE("Delta propagation with varying agent counts", "[LATENCY][delta][scala QObject::connect(receiver, &DSR::DSRGraph::update_node_signal, receiver, [&, idx = i - 1](uint64_t id, const std::string& type, DSR::SignalInfo) { if (id == current_expected_id.load()) { - receive_times[idx].store(get_unix_timestamp()); + receive_times[idx].store(bench_now()); received_count.fetch_add(1); } }, Qt::DirectConnection); @@ -297,7 +297,7 @@ TEST_CASE("Delta propagation with varying agent counts", "[LATENCY][delta][scala 0, sender->get_agent_id(), "scale_node_" + std::to_string(i)); - uint64_t send_time = get_unix_timestamp(); + uint64_t send_time = bench_now(); auto result = sender->insert_node(node); REQUIRE(result.has_value()); current_expected_id.store(result.value()); diff --git a/benchmarks/latency/type_conversion_bench.cpp b/benchmarks/latency/type_conversion_bench.cpp new file mode 100644 index 00000000..35117836 --- /dev/null +++ b/benchmarks/latency/type_conversion_bench.cpp @@ -0,0 +1,259 @@ +#include + +#include +#include +#include +#include +#include + +#include "../core/nanobench_adapter.h" +#include "../core/metrics_collector.h" +#include "../core/report_generator.h" +#include "../fixtures/graph_generator.h" + +using namespace DSR; +using namespace DSR::Benchmark; + +// ── Helpers ────────────────────────────────────────────────────────────────── + +static Attribute make_attr(int32_t v) { + return Attribute(v, 0, 1); +} + +static Node make_node(uint32_t n_attrs, uint32_t n_edges) { + GraphGenerator::register_test_types(); + Node node; + node.id(1000); + node.name("conv_test_node"); + node.type("test_node"); + node.agent_id(1); + + auto& attrs = node.attrs(); + for (uint32_t i = 0; i < n_attrs; ++i) { + switch (i % 5) { + case 0: attrs.emplace("attr_int_" + std::to_string(i), Attribute(static_cast(i), 0, 1)); break; + case 1: attrs.emplace("attr_float_" + std::to_string(i), Attribute(static_cast(i) * 0.1f, 0, 1)); break; + case 2: attrs.emplace("attr_bool_" + std::to_string(i), Attribute(static_cast(i % 2), 0, 1)); break; + case 3: attrs.emplace("attr_str_" + std::to_string(i), Attribute(std::string("val_" + std::to_string(i)), 0, 1)); break; + case 4: attrs.emplace("attr_u64_" + std::to_string(i), Attribute(static_cast(i * 1000), 0, 1)); break; + } + } + + auto& fano = node.fano(); + for (uint32_t e = 0; e < n_edges; ++e) { + uint64_t dst = 2000 + e; + Edge edge(dst, 1000, "test_edge", {}, 1); + auto& eattrs = edge.attrs(); + eattrs.emplace("weight", Attribute(static_cast(e) * 0.5f, 0, 1)); + fano.emplace(std::make_pair(dst, std::string("test_edge")), std::move(edge)); + } + + return node; +} + +static Edge make_edge(uint32_t n_attrs) { + GraphGenerator::register_test_types(); + Edge edge(2000, 1000, "test_edge", {}, 1); + auto& attrs = edge.attrs(); + for (uint32_t i = 0; i < n_attrs; ++i) { + attrs.emplace("ea_" + std::to_string(i), Attribute(static_cast(i), 0, 1)); + } + return edge; +} + +// ── CRDT node/edge conversions ──────────────────────────────────────────────── + +TEST_CASE("CRDT type conversion latency", "[LATENCY][CONVERSION][BASELINE]") { + MetricsCollector collector("crdt_type_conversion"); + collector.add_metadata("profile", "baseline"); + + for (auto [n_attrs, n_edges, label] : std::initializer_list>{ + {0, 0, "bare"}, + {5, 0, "light"}, + {20, 0, "heavy_attrs"}, + {5, 5, "light_with_edges"}, + {20, 20, "heavy"}, + }) + { + Node node = make_node(n_attrs, n_edges); + + { + auto bench = make_latency_bench(); + bench.run(std::string("user_node_to_crdt_") + label, [&] { + auto crdt = user_node_to_crdt(node); + ankerl::nanobench::doNotOptimizeAway(crdt); + }); + collector.record_latency_stats("user_node_to_crdt", + nb_to_stats(bench), {{"config", label}}); + } + + { + CRDTNode crdt_node = user_node_to_crdt(node); + + auto bench = make_latency_bench(); + bench.run(std::string("crdt_node_to_user_") + label, [&] { + auto out = to_user_node(crdt_node); + ankerl::nanobench::doNotOptimizeAway(out); + }); + collector.record_latency_stats("crdt_node_to_user", + nb_to_stats(bench), {{"config", label}}); + } + + Edge edge = make_edge(n_attrs); + + { + auto bench = make_latency_bench(); + bench.run(std::string("user_edge_to_crdt_") + label, [&] { + auto crdt = user_edge_to_crdt(edge); + ankerl::nanobench::doNotOptimizeAway(crdt); + }); + collector.record_latency_stats("user_edge_to_crdt", + nb_to_stats(bench), {{"config", label}}); + } + + { + CRDTEdge crdt_edge = user_edge_to_crdt(edge); + + auto bench = make_latency_bench(); + bench.run(std::string("crdt_edge_to_user_") + label, [&] { + auto out = to_user_edge(crdt_edge); + ankerl::nanobench::doNotOptimizeAway(out); + }); + collector.record_latency_stats("crdt_edge_to_user", + nb_to_stats(bench), {{"config", label}}); + } + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "crdt_type_conversion"); +} + +// ── LWW node/edge conversions ───────────────────────────────────────────────── + +TEST_CASE("LWW type conversion latency", "[LATENCY][CONVERSION][BASELINE]") { + MetricsCollector collector("lww_type_conversion"); + collector.add_metadata("profile", "baseline"); + + const LWW::Version ver{12345678ULL, 1}; + + for (auto [n_attrs, n_edges, label] : std::initializer_list>{ + {0, 0, "bare"}, + {5, 0, "light"}, + {20, 0, "heavy_attrs"}, + {5, 5, "light_with_edges"}, + {20, 20, "heavy"}, + }) + { + Node node = make_node(n_attrs, n_edges); + + { + auto bench = make_latency_bench(); + bench.run(std::string("to_node_state_") + label, [&] { + auto state = LWW::to_node_state(node, ver, 1); + ankerl::nanobench::doNotOptimizeAway(state); + }); + collector.record_latency_stats("to_node_state", + nb_to_stats(bench), {{"config", label}}); + } + + { + LWW::NodeState state = LWW::to_node_state(node, ver, 1); + + // Build a FromIndex with the node's outgoing edges. + LWW::FromIndex from_idx; + std::vector edge_states; + edge_states.reserve(n_edges); + for (const auto& [key, edge] : node.fano()) { + Edge e(key.first, node.id(), key.second, edge.attrs(), 1); + edge_states.push_back(LWW::to_edge_state(e, ver, 1)); + } + for (const auto& es : edge_states) { + from_idx[es.from].insert(&es); + } + + auto bench = make_latency_bench(); + bench.run(std::string("lww_node_to_user_") + label, [&] { + auto out = LWW::to_user_node(state, from_idx); + ankerl::nanobench::doNotOptimizeAway(out); + }); + collector.record_latency_stats("lww_node_to_user", + nb_to_stats(bench), {{"config", label}}); + } + + Edge edge = make_edge(n_attrs); + + { + auto bench = make_latency_bench(); + bench.run(std::string("to_edge_state_") + label, [&] { + auto state = LWW::to_edge_state(edge, ver, 1); + ankerl::nanobench::doNotOptimizeAway(state); + }); + collector.record_latency_stats("to_edge_state", + nb_to_stats(bench), {{"config", label}}); + } + + { + LWW::EdgeState state = LWW::to_edge_state(edge, ver, 1); + + auto bench = make_latency_bench(); + bench.run(std::string("lww_edge_to_user_") + label, [&] { + auto out = LWW::to_user_edge(state); + ankerl::nanobench::doNotOptimizeAway(out); + }); + collector.record_latency_stats("lww_edge_to_user", + nb_to_stats(bench), {{"config", label}}); + } + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "lww_type_conversion"); +} + +// ── Wire message serialization ──────────────────────────────────────────────── + +TEST_CASE("Wire message conversion latency", "[LATENCY][CONVERSION][BASELINE]") { + MetricsCollector collector("wire_conversion"); + collector.add_metadata("profile", "baseline"); + + const LWW::Version ver{12345678ULL, 1}; + + for (auto [n_attrs, label] : std::initializer_list>{ + {0, "bare"}, + {5, "light"}, + {20, "heavy"}, + }) + { + Node node = make_node(n_attrs, 0); + Edge edge = make_edge(n_attrs); + + { + LWW::NodeState state = LWW::to_node_state(node, ver, 1); + + auto bench = make_latency_bench(); + bench.run(std::string("lww_node_to_msg_") + label, [&] { + auto msg = LWW::to_node_msg(state); + ankerl::nanobench::doNotOptimizeAway(msg); + }); + collector.record_latency_stats("lww_node_to_msg", + nb_to_stats(bench), {{"config", label}}); + } + + { + LWW::EdgeState state = LWW::to_edge_state(edge, ver, 1); + + auto bench = make_latency_bench(); + bench.run(std::string("lww_edge_to_msg_") + label, [&] { + auto msg = LWW::to_edge_msg(state); + ankerl::nanobench::doNotOptimizeAway(msg); + }); + collector.record_latency_stats("lww_edge_to_msg", + nb_to_stats(bench), {{"config", label}}); + } + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "wire_conversion"); +} diff --git a/benchmarks/report.py b/benchmarks/report.py index 7271cdae..af719683 100644 --- a/benchmarks/report.py +++ b/benchmarks/report.py @@ -179,9 +179,9 @@ def infer_profile(bench: dict, metric: Optional[dict] = None) -> str: return "other" -def flatten_metrics(bench_files: list) -> tuple[list, list]: - """Return (latency_metrics, throughput_metrics) as flat lists.""" - latency, throughput = [], [] +def flatten_metrics(bench_files: list) -> tuple[list, list, list]: + """Return (latency_metrics, throughput_metrics, other_metrics) as flat lists.""" + latency, throughput, other = [], [], [] latency_keys: set = set() # (bench_name, metric_name) pairs with real latency data for bench in bench_files: bench_name = bench.get("benchmark_name", bench["_source_file"]) @@ -250,7 +250,13 @@ def flatten_metrics(bench_files: list) -> tuple[list, list]: "has_percentiles": False, }) latency.append(entry) - return latency, throughput + else: + entry.update({ + "category": category or "other", + "tags": tags, + }) + other.append(entry) + return latency, throughput, other # ── Scalability flattening ──────────────────────────────────────────────────── @@ -361,8 +367,10 @@ def generate_html( baseline_info: Optional[dict] = None, baseline_files: Optional[list] = None, ): - latency, throughput = flatten_metrics(bench_files) - b_latency, b_throughput = (flatten_metrics(baseline_files) if baseline_files else ([], [])) + latency, throughput, other = flatten_metrics(bench_files) + b_latency, b_throughput, b_other = ( + flatten_metrics(baseline_files) if baseline_files else ([], [], []) + ) scl_rows = flatten_scalability(bench_files) eff_rows = compute_efficiency(scl_rows) @@ -377,8 +385,10 @@ def generate_html( latency_json = json.dumps(latency) throughput_json = json.dumps(throughput) + other_json = json.dumps(other) b_latency_json = json.dumps(b_latency) b_throughput_json = json.dumps(b_throughput) + b_other_json = json.dumps(b_other) run_info_json = json.dumps(run_info) b_info_json = json.dumps(baseline_info or {}) scl_json = json.dumps(scl_rows) @@ -572,6 +582,7 @@ def generate_html( + {compare_tab} @@ -667,6 +678,30 @@ def generate_html( + +
+
+
+ + +
+ + + +
+
+
+

Non-Time Metrics

+
+
+
+
+
@@ -719,8 +754,10 @@ def generate_html( // ── Data ───────────────────────────────────────────────────────────────────── const LAT = {latency_json}; const THR = {throughput_json}; +const OTH = {other_json}; const B_LAT = {b_latency_json}; const B_THR = {b_throughput_json}; +const B_OTH = {b_other_json}; const RUN_INFO = {run_info_json}; const B_INFO = {b_info_json}; const SUMMARY = {summary_json}; @@ -745,6 +782,11 @@ def generate_html( if (v >= 1e3) return (v/1e3).toFixed(2) + ' K ops/s'; return v.toFixed(1) + ' ops/s'; }} +function fmtValue(v, unit) {{ + if (typeof v !== 'number') return String(v) + (unit ? ' ' + unit : ''); + if (unit === '%') return v.toFixed(2).replace(/[.]?0+$/, '') + '%'; + return v.toLocaleString(undefined, {{ maximumFractionDigits: 3 }}) + (unit ? ' ' + unit : ''); +}} function deltaClass(pct, higherIsBetter) {{ if (Math.abs(pct) < 1) return 'delta-neutral'; return (pct > 0) === higherIsBetter ? 'delta-good' : 'delta-bad'; @@ -812,11 +854,11 @@ def generate_html( // ── Overview ────────────────────────────────────────────────────────────────── function renderOverview() {{ // Stat cards - const total = LAT.length + THR.length; - const benchNames = [...new Set([...LAT.map(m=>m.benchmark), ...THR.map(m=>m.benchmark)])]; + const total = LAT.length + THR.length + OTH.length; + const benchNames = [...new Set([...LAT.map(m=>m.benchmark), ...THR.map(m=>m.benchmark), ...OTH.map(m=>m.benchmark)])]; const avgMean = LAT.length ? LAT.reduce((s,m)=>s+m.mean_ns,0)/LAT.length : 0; - const baselineCount = new Set([...LAT.filter(m=>m.profile==='baseline').map(m=>m.benchmark), ...THR.filter(m=>m.profile==='baseline').map(m=>m.benchmark)]).size; - const extendedCount = new Set([...LAT.filter(m=>m.profile==='extended').map(m=>m.benchmark), ...THR.filter(m=>m.profile==='extended').map(m=>m.benchmark)]).size; + const baselineCount = new Set([...LAT.filter(m=>m.profile==='baseline').map(m=>m.benchmark), ...THR.filter(m=>m.profile==='baseline').map(m=>m.benchmark), ...OTH.filter(m=>m.profile==='baseline').map(m=>m.benchmark)]).size; + const extendedCount = new Set([...LAT.filter(m=>m.profile==='extended').map(m=>m.benchmark), ...THR.filter(m=>m.profile==='extended').map(m=>m.benchmark), ...OTH.filter(m=>m.profile==='extended').map(m=>m.benchmark)]).size; document.getElementById('stat-cards').innerHTML = `
${{benchNames.length}}
Benchmark Suites
${{total}}
Total Metrics
@@ -881,13 +923,14 @@ def generate_html( }} // ── Lang filter state ───────────────────────────────────────────────────────── -const langFilter = {{ lat: '', thr: '' }}; +const langFilter = {{ lat: '', thr: '', oth: '' }}; function setLangFilter(tab, lang, btn) {{ langFilter[tab] = lang; btn.closest('.lang-toggle').querySelectorAll('button').forEach(b => b.classList.remove('active')); btn.classList.add('active'); if (tab === 'lat') renderLatency(); - else renderThroughput(); + else if (tab === 'thr') renderThroughput(); + else renderOther(); }} function langBadge(lang) {{ return `${{lang}}`; @@ -1056,6 +1099,50 @@ def generate_html( document.getElementById('thr-detail-sections').innerHTML = grouped || '

No data

'; }} +function renderOther() {{ + let data = OTH; + const benchF = document.getElementById('oth-filter').value; + const profileF = document.getElementById('oth-profile-filter').value; + if (benchF) data = data.filter(m => m.benchmark === benchF); + if (profileF) data = data.filter(m => m.profile === profileF); + if (langFilter.oth) data = data.filter(m => m.lang === langFilter.oth); + const bMap = COMPARING ? Object.fromEntries(B_OTH.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])) : {{}}; + + const renderRows = rows => rows.map(m => {{ + const b = bMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; + const deltaCell = b && typeof m.value === 'number' && typeof b.value === 'number' && b.value !== 0 + ? fmtDelta(((m.value - b.value) / b.value) * 100, true) + : ''; + const tagText = m.tags && Object.keys(m.tags).length ? JSON.stringify(m.tags) : ''; + return ` + ${{langBadge(m.lang)}} + ${{m.category}} + ${{m.benchmark}} ${{profileBadge(m.profile)}} + ${{m.metric}} + ${{fmtValue(m.value, m.unit)}}${{deltaCell ? ' ' + deltaCell : ''}} + ${{b ? fmtValue(b.value, b.unit) : ''}} + ${{tagText}} + `; + }}).join(''); + + const grouped = ['baseline', 'extended', 'other'].map(profile => {{ + const rows = data.filter(m => m.profile === profile); + if (!rows.length) return ''; + return ` +
+ ${{profileLabel(profile)}} ${{profileBadge(profile)}} + ${{rows.length}} metric(s) +
+ + + + + ${{renderRows(rows) || ''}} +
LangCategoryBenchmarkMetricValueBaselineTags
No data
`; + }}).join(''); + document.getElementById('oth-detail-sections').innerHTML = grouped || '

No non-time metrics

'; +}} + // ── Scalability Tab ─────────────────────────────────────────────────────────── let sclThrChart = null, sclLatChart = null, sclEffChart = null; @@ -1348,10 +1435,11 @@ def generate_html( }} }} -function buildLangSection(lang, lat, bLatMap, thr, bThrMap) {{ +function buildLangSection(lang, lat, bLatMap, thr, bThrMap, oth, bOthMap) {{ const langLat = lat.filter(m => m.lang === lang); const langThr = thr.filter(m => m.lang === lang); - if (!langLat.length && !langThr.length) return {{ html: '', items: [] }}; + const langOth = oth.filter(m => m.lang === lang); + if (!langLat.length && !langThr.length && !langOth.length) return {{ html: '', items: [] }}; const badgeCls = lang === 'cpp' ? 'badge-cpp' : 'badge-python'; const langLabel = lang === 'cpp' ? 'C++' : 'Python'; @@ -1432,13 +1520,42 @@ def generate_html(
` : ''; + const othRows = langOth.map(m => {{ + const b = bOthMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; + const deltaCell = b && typeof m.value === 'number' && typeof b.value === 'number' && b.value !== 0 + ? fmtDelta(((m.value - b.value) / b.value) * 100, true) + : ''; + if (!b) return `${{m.category}}${{m.benchmark}}${{m.metric}}no baseline`; + return ` + ${{m.category}} + ${{m.benchmark}} + ${{m.metric}} + ${{fmtValue(b.value, b.unit)}} + ${{fmtValue(m.value, m.unit)}} + ${{deltaCell}} + `; + }}).join(''); + + const othSection = langOth.length ? ` +
+

Other Metrics Comparison

+ + + + + + ${{othRows}} +
CategoryBenchmarkMetricBaselineCurrentΔ
+
` : ''; + const html = `
${{langLabel}}
${{chartSection}} ${{latSection}} - ${{thrSection}}`; + ${{thrSection}} + ${{othSection}}`; return {{ html, items: chartItems }}; }} @@ -1449,9 +1566,10 @@ def generate_html( const bLatMap = Object.fromEntries(B_LAT.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); const bThrMap = Object.fromEntries(B_THR.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); + const bOthMap = Object.fromEntries(B_OTH.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); - const pySection = buildLangSection('python', LAT, bLatMap, THR, bThrMap); - const cppSection = buildLangSection('cpp', LAT, bLatMap, THR, bThrMap); + const pySection = buildLangSection('python', LAT, bLatMap, THR, bThrMap, OTH, bOthMap); + const cppSection = buildLangSection('cpp', LAT, bLatMap, THR, bThrMap, OTH, bOthMap); el.innerHTML = `
@@ -1470,7 +1588,11 @@ def generate_html( // ── Raw ─────────────────────────────────────────────────────────────────────── function renderRaw() {{ - const all = [...LAT.map(m=>({{'type':'latency',...m}})), ...THR.map(m=>({{'type':'throughput',...m}}))]; + const all = [ + ...LAT.map(m=>({{'type':'latency',...m}})), + ...THR.map(m=>({{'type':'throughput',...m}})), + ...OTH.map(m=>({{'type':m.category || 'other',...m}})), + ]; const byProfile = ['baseline', 'extended', 'other'].sort((a,b)=>profileOrder(a)-profileOrder(b)).map(profile => {{ const rows = all.filter(m => m.profile === profile); if (!rows.length) return ''; @@ -1492,10 +1614,12 @@ def generate_html( // ── Init ────────────────────────────────────────────────────────────────────── populateFilter('lat-filter', LAT); populateFilter('thr-filter', THR); +populateFilter('oth-filter', OTH); // scl-op is populated lazily on first tab activation (needs SCL data) renderOverview(); renderLatency(); renderThroughput(); +renderOther(); renderRaw(); diff --git a/benchmarks/run_benchmarks.py b/benchmarks/run_benchmarks.py index 6f3a7aaa..7ccb35e9 100644 --- a/benchmarks/run_benchmarks.py +++ b/benchmarks/run_benchmarks.py @@ -8,7 +8,7 @@ python run_benchmarks.py --cpp-only # skip Python python run_benchmarks.py --python-only # skip C++ python run_benchmarks.py --build # cmake build before running - python run_benchmarks.py --all # include hidden tests ([.multi], [.extended]) + python run_benchmarks.py --all # include hidden tests ([.extended]) python run_benchmarks.py --cpp-filter "[LATENCY]"# pass filter to dsr_benchmarks python run_benchmarks.py --report # open HTML report when done python run_benchmarks.py --compare # compare against a previous run @@ -37,7 +37,7 @@ BUILD_DIR = os.path.join(SCRIPT_DIR, "build") RESULTS_ROOT = os.path.join(SCRIPT_DIR, "results") RUNS_INDEX = os.path.join(RESULTS_ROOT, "runs.json") -BASELINE_CPP_FILTER = "[BASELINE]~[.multi]" +BASELINE_CPP_FILTER = "[BASELINE]" # Catch2 v3 has no single spec that matches both visible and hidden tests. # _run_cpp_once detects this sentinel and runs the binary twice: # 1. no filter → all visible tests @@ -878,7 +878,7 @@ def main(): parser.add_argument("--cpp-only", action="store_true", help="Skip Python suite") parser.add_argument("--python-only", action="store_true", help="Skip C++ suite") parser.add_argument("--all", action="store_true", - help="Run all C++ tests including hidden ones ([.multi], [.extended])") + help="Run all C++ tests including hidden ones ([.extended])") parser.add_argument("--baseline", action="store_true", help="Run only the curated low-noise baseline benchmark set") parser.add_argument("--verbose", "-v", action="store_true", diff --git a/benchmarks/scalability/agent_scaling_bench.cpp b/benchmarks/scalability/agent_scaling_bench.cpp index 3764f0da..6fe9ecb5 100644 --- a/benchmarks/scalability/agent_scaling_bench.cpp +++ b/benchmarks/scalability/agent_scaling_bench.cpp @@ -17,18 +17,19 @@ using namespace DSR; using namespace DSR::Benchmark; using namespace std::chrono; -// Multi-agent scaling benchmarks. Tagged [.multi] so they are excluded from -// the default test run (DDS multi-agent tests are slow and require specific -// network setup). Opt in with: --cpp-filter "[SCALABILITY][agents]" +// Multi-agent scaling benchmarks. Tagged so they are excluded from +// the default test run. Opt in with: --cpp-filter "[SCALABILITY][agents]" // // Loop over {1, 2, 4} agents. One thread per agent operates on its own -// DSRGraph instance; a 3-second window measures total throughput and latency. +// DSRGraph instance; a 3-second window measures total throughput. +// Latency is not collected here — merged per-thread percentiles are +// misleading. Use the single-agent latency benchmarks for latency. static constexpr auto AGENT_DUR = std::chrono::seconds(3); // ── Node insert ─────────────────────────────────────────────────────────────── -TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("node_insert_agent_scaling"); @@ -43,9 +44,6 @@ TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(500000 / N); - std::vector threads; threads.reserve(N); @@ -56,16 +54,13 @@ TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M auto* graph = fixture.get_agent(agent_idx); uint64_t base_id = 800000ULL + agent_idx * 200000ULL; uint64_t local_ops = 0; - auto& samples = per_thread_samples[agent_idx]; sync_point.arrive_and_wait(); while (!stop_flag.load(std::memory_order_relaxed)) { auto node = GraphGenerator::create_test_node( base_id + local_ops, graph->get_agent_id()); - uint64_t ts = bench_now(); auto res = graph->insert_node(node); - samples.push_back(bench_now() - ts); if (!res.has_value()) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -85,16 +80,8 @@ TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_insert", total_ops.load(), dur, - {{"agents", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_insert", merged.stats(), - {{"agents", n_str}}); + collector.record_throughput("node_insert", total_ops.load(), dur, {{"agents", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -109,7 +96,7 @@ TEST_CASE("Node insert agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M // ── Node read ───────────────────────────────────────────────────────────────── -TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("node_read_agent_scaling"); @@ -119,7 +106,6 @@ TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MUL REQUIRE(fixture.create_agents(N, config_file)); fixture.wait_for_sync(); - // Pre-populate 1000 nodes on agent 0; they sync to all agents. auto* graph0 = fixture.get_agent(0); std::vector node_ids; node_ids.reserve(1000); @@ -138,9 +124,6 @@ TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MUL std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(500000 / N); - std::vector threads; threads.reserve(N); @@ -150,15 +133,12 @@ TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MUL threads.emplace_back([&, agent_idx = i]() { auto* graph = fixture.get_agent(agent_idx); uint64_t local_ops = 0; - auto& samples = per_thread_samples[agent_idx]; sync_point.arrive_and_wait(); while (!stop_flag.load(std::memory_order_relaxed)) { uint64_t id = node_ids[local_ops % pool_size]; - uint64_t ts = bench_now(); auto node = graph->get_node(id); - samples.push_back(bench_now() - ts); if (!node.has_value()) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -178,16 +158,8 @@ TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MUL auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_read", total_ops.load(), dur, - {{"agents", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_read", merged.stats(), - {{"agents", n_str}}); + collector.record_throughput("node_read", total_ops.load(), dur, {{"agents", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -202,7 +174,7 @@ TEST_CASE("Node read agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MUL // ── Node update ─────────────────────────────────────────────────────────────── -TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][MULTIAGENT]") { +TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][PROFILE][MULTIAGENT]") { GraphGenerator generator; MetricsCollector collector("node_update_agent_scaling"); @@ -212,7 +184,6 @@ TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M REQUIRE(fixture.create_agents(N, config_file)); fixture.wait_for_sync(); - // Each agent gets its own dedicated node to avoid update contention. std::vector agent_node_ids(N); for (uint32_t i = 0; i < N; ++i) { auto* graph = fixture.get_agent(i); @@ -230,9 +201,6 @@ TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(500000 / N); - std::vector threads; threads.reserve(N); @@ -243,7 +211,6 @@ TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M auto* graph = fixture.get_agent(agent_idx); uint64_t nid = agent_node_ids[agent_idx]; uint64_t local_ops = 0; - auto& samples = per_thread_samples[agent_idx]; sync_point.arrive_and_wait(); @@ -252,9 +219,7 @@ TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M if (node) { graph->add_or_modify_attrib_local( *node, static_cast(local_ops % 1000)); - uint64_t ts = bench_now(); bool ok = graph->update_node(*node); - samples.push_back(bench_now() - ts); if (!ok) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -277,16 +242,8 @@ TEST_CASE("Node update agent scaling", "[SCALABILITY][agents][.multi][PROFILE][M auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_update", total_ops.load(), dur, - {{"agents", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_update", merged.stats(), - {{"agents", n_str}}); + collector.record_throughput("node_update", total_ops.load(), dur, {{"agents", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); diff --git a/benchmarks/scalability/graph_size_impact_bench.cpp b/benchmarks/scalability/graph_size_impact_bench.cpp index 618ea84b..dee26245 100644 --- a/benchmarks/scalability/graph_size_impact_bench.cpp +++ b/benchmarks/scalability/graph_size_impact_bench.cpp @@ -184,6 +184,88 @@ TEST_CASE("Graph size impact on performance", "[SCALABILITY][graphsize]") { } } + SECTION("Query operations vs graph size") { + // get_nodes, get_nodes_by_type, and name/id lookups — all at fixed graph sizes. + // These are O(n) or O(1) operations; measuring them here lets us detect + // regressions in their scaling without a separate query bench file. + for (uint32_t size : {100u, 1000u, 5000u}) { + MultiAgentFixture fixture; + auto config_file = generator.generate_empty_graph(); + REQUIRE(fixture.create_agents(1, config_file)); + + auto* graph = fixture.get_agent(0); + REQUIRE(graph != nullptr); + + std::vector node_ids; + node_ids.reserve(size); + for (uint32_t i = 0; i < size; ++i) { + auto node = GraphGenerator::create_test_node( + i, graph->get_agent_id(), "query_node_" + std::to_string(i)); + auto inserted = graph->insert_node(node); + REQUIRE(inserted.has_value()); + node_ids.push_back(*inserted); + } + + // Cache warmup + (void)graph->get_nodes(); + (void)graph->get_nodes_by_type("test_node"); + + const std::string sz = std::to_string(size); + + { + auto bench = make_latency_bench(100, 0); + bench.minEpochIterations(5); + bench.run("get_nodes", [&] { + auto nodes = graph->get_nodes(); + ankerl::nanobench::doNotOptimizeAway(nodes); + }); + auto stats = nb_to_stats(bench); + collector.record_scalability("get_nodes", size, stats.mean_us(), "us", + {{"graph_size", sz}}); + } + + { + auto bench = make_latency_bench(100, 0); + bench.minEpochIterations(5); + bench.run("get_nodes_by_type", [&] { + auto nodes = graph->get_nodes_by_type("test_node"); + ankerl::nanobench::doNotOptimizeAway(nodes); + }); + auto stats = nb_to_stats(bench); + collector.record_scalability("get_nodes_by_type", size, stats.mean_us(), "us", + {{"graph_size", sz}}); + } + + { + size_t idx = 0; + auto bench = make_latency_bench(200, 0); + bench.minEpochIterations(1000); + bench.run("get_name_from_id", [&] { + auto name = graph->get_name_from_id(node_ids[idx++ % node_ids.size()]); + ankerl::nanobench::doNotOptimizeAway(name); + }); + auto stats = nb_to_stats(bench); + collector.record_scalability("get_name_from_id", size, stats.mean_ns, "ns", + {{"graph_size", sz}}); + } + + { + size_t idx = 0; + auto bench = make_latency_bench(200, 0); + bench.minEpochIterations(1000); + bench.run("get_id_from_name", [&] { + auto id = graph->get_id_from_name("query_node_" + std::to_string(idx++ % size)); + ankerl::nanobench::doNotOptimizeAway(id); + }); + auto stats = nb_to_stats(bench); + collector.record_scalability("get_id_from_name", size, stats.mean_ns, "ns", + {{"graph_size", sz}}); + } + + INFO(size << " nodes — query ops measured"); + } + } + SECTION("get_nodes performance vs graph size") { for (uint32_t size : {100, 1000, 5000}) { MultiAgentFixture fixture; diff --git a/benchmarks/scalability/multi_agent_sync_bench.cpp b/benchmarks/scalability/multi_agent_sync_bench.cpp deleted file mode 100644 index 6707751a..00000000 --- a/benchmarks/scalability/multi_agent_sync_bench.cpp +++ /dev/null @@ -1,286 +0,0 @@ -#include -#include -#include -#include - -#include "../core/timing_utils.h" -#include "../core/metrics_collector.h" -#include "../core/report_generator.h" -#include "../fixtures/multi_agent_fixture.h" -#include "../fixtures/graph_generator.h" - -using namespace DSR; -using namespace DSR::Benchmark; - -TEST_CASE("Multi-agent synchronization benchmarks", "[SCALABILITY][sync][.multi][PROFILE][MULTIAGENT]") { - GraphGenerator generator; - MetricsCollector collector("multi_agent_sync"); - - SECTION("Initial sync time vs agent count") { - for (uint32_t num_agents : {2, 4, 8, 16}) { - auto config_file = generator.generate_empty_graph(); - - LatencyTracker tracker(10); - - for (int trial = 0; trial < 10; ++trial) { - MultiAgentFixture fixture; - - uint64_t start = get_unix_timestamp(); - bool created = fixture.create_agents(num_agents, config_file); - if (!created) { - WARN("Could not create " << num_agents << " agents"); - break; - } - - fixture.wait_for_sync(); - bool converged = fixture.verify_convergence(); - uint64_t elapsed = get_unix_timestamp() - start; - - if (converged) { - tracker.record(elapsed); - } - - // Cleanup before next trial - } - - if (tracker.count() > 0) { - auto stats = tracker.stats(); - collector.record_scalability( - "initial_sync_time", - num_agents, - stats.mean_ms(), - "ms", - {{"num_agents", std::to_string(num_agents)}}); - - INFO(num_agents << " agents - Initial sync: " << stats.mean_ms() << " ms"); - } - } - } - - SECTION("Convergence time after operation") { - for (uint32_t num_agents : {2, 4, 8}) { - MultiAgentFixture fixture; - auto config_file = generator.generate_empty_graph(); - - if (!fixture.create_agents(num_agents, config_file)) { - WARN("Could not create " << num_agents << " agents"); - continue; - } - fixture.wait_for_sync(); - - LatencyTracker tracker(50); - - // Measure convergence time after node insertion - for (int i = 0; i < 50; ++i) { - auto* sender = fixture.get_agent(0); - auto node = GraphGenerator::create_test_node( - 700000 + i, sender->get_agent_id(), - "sync_node_" + std::to_string(i)); - - uint64_t start = get_unix_timestamp(); - sender->insert_node(node); - - auto conv_time = fixture.measure_convergence_time(); - if (conv_time.count() >= 0) { - tracker.record(static_cast(conv_time.count()) * 1'000'000); // ms to ns - } - } - - if (tracker.count() > 0) { - auto stats = tracker.stats(); - collector.record_scalability( - "convergence_after_insert", - num_agents, - stats.mean_ms(), - "ms", - {{"num_agents", std::to_string(num_agents)}}); - - INFO(num_agents << " agents - Convergence time: " << stats.mean_ms() << " ms"); - } - } - } - - SECTION("Broadcast time to all agents") { - for (uint32_t num_agents : {2, 4, 8}) { - MultiAgentFixture fixture; - auto config_file = generator.generate_empty_graph(); - - if (!fixture.create_agents(num_agents, config_file)) { - WARN("Could not create " << num_agents << " agents"); - continue; - } - fixture.wait_for_sync(); - - LatencyTracker tracker(50); - - // Track when each agent receives the update - std::vector> receive_times(num_agents - 1); - std::vector> received(num_agents - 1); - - for (size_t i = 1; i < num_agents; ++i) { - auto* receiver = fixture.get_agent(i); - QObject::connect(receiver, &DSR::DSRGraph::update_node_signal, receiver, - [&, idx = i - 1](uint64_t id, const std::string& type, DSR::SignalInfo) { - if (id >= 800000 && id < 900000 && !received[idx].load()) { - receive_times[idx].store(get_unix_timestamp()); - received[idx].store(true); - } - }, Qt::DirectConnection); - } - - auto* sender = fixture.get_agent(0); - - for (int i = 0; i < 50; ++i) { - // Reset tracking - for (size_t j = 0; j < num_agents - 1; ++j) { - receive_times[j].store(0); - received[j].store(false); - } - - auto node = GraphGenerator::create_test_node( - 800000 + i, sender->get_agent_id(), - "broadcast_node_" + std::to_string(i)); - - uint64_t send_time = get_unix_timestamp(); - sender->insert_node(node); - - // Wait for all receivers - auto start = std::chrono::steady_clock::now(); - while (true) { - bool all_received = true; - for (size_t j = 0; j < num_agents - 1; ++j) { - if (!received[j].load()) { - all_received = false; - break; - } - } - - if (all_received) break; - - fixture.process_events(1); - - if (std::chrono::steady_clock::now() - start > std::chrono::seconds(5)) { - break; - } - } - - // Find max receive time (last agent to receive) - uint64_t max_time = 0; - for (size_t j = 0; j < num_agents - 1; ++j) { - if (received[j].load()) { - max_time = std::max(max_time, receive_times[j].load()); - } - } - - if (max_time > send_time) { - tracker.record(max_time - send_time); - } - } - - if (tracker.count() > 0) { - auto stats = tracker.stats(); - collector.record_scalability( - "broadcast_to_all", - num_agents, - stats.mean_us(), - "us", - {{"num_agents", std::to_string(num_agents)}}); - - INFO(num_agents << " agents - Broadcast time: " << stats.mean_us() << " us"); - } - } - } - - auto result = collector.finalize(); - ReportGenerator reporter("results"); - reporter.export_all(result, "multi_agent_sync"); -} - -TEST_CASE("Scaling efficiency", "[SCALABILITY][efficiency][.multi][PROFILE][MULTIAGENT]") { - GraphGenerator generator; - MetricsCollector collector("scaling_efficiency"); - - std::map throughputs; - - SECTION("Throughput scaling with agents") { - for (uint32_t num_agents : {1, 2, 4, 8}) { - MultiAgentFixture fixture; - auto config_file = generator.generate_empty_graph(); - - if (!fixture.create_agents(num_agents, config_file)) { - WARN("Could not create " << num_agents << " agents"); - continue; - } - fixture.wait_for_sync(); - - constexpr auto TEST_DURATION = std::chrono::seconds(3); - std::atomic total_ops{0}; - std::atomic stop_flag{false}; - - std::vector threads; - threads.reserve(num_agents); - - auto start = std::chrono::steady_clock::now(); - - for (size_t i = 0; i < num_agents; ++i) { - threads.emplace_back([&, agent_idx = i]() { - auto* graph = fixture.get_agent(agent_idx); - uint64_t base_id = 900000 + agent_idx * 50000; - uint64_t local_ops = 0; - - while (!stop_flag.load(std::memory_order_relaxed)) { - auto node = GraphGenerator::create_test_node( - base_id + local_ops, graph->get_agent_id()); - graph->insert_node(node); - local_ops++; - } - - total_ops.fetch_add(local_ops, std::memory_order_relaxed); - }); - } - - std::this_thread::sleep_for(TEST_DURATION); - stop_flag.store(true); - - for (auto& t : threads) { - t.join(); - } - - auto actual_duration = std::chrono::duration_cast( - std::chrono::steady_clock::now() - start); - - double ops_per_sec = static_cast(total_ops.load()) / - (static_cast(actual_duration.count()) / 1000.0); - - throughputs[num_agents] = ops_per_sec; - - collector.record_scalability( - "throughput_scaling", - num_agents, - ops_per_sec, - "ops/sec", - {{"num_agents", std::to_string(num_agents)}}); - - INFO(num_agents << " agents - Throughput: " << ops_per_sec << " ops/sec"); - } - - // Calculate scaling efficiency - if (throughputs.count(1) > 0 && throughputs.count(2) > 0) { - double efficiency_2 = throughputs[2] / (2 * throughputs[1]) * 100; - collector.record("scaling_efficiency_2_agents", MetricCategory::Scalability, - efficiency_2, "%"); - INFO("Scaling efficiency (2 agents): " << efficiency_2 << "%"); - } - - if (throughputs.count(1) > 0 && throughputs.count(4) > 0) { - double efficiency_4 = throughputs[4] / (4 * throughputs[1]) * 100; - collector.record("scaling_efficiency_4_agents", MetricCategory::Scalability, - efficiency_4, "%"); - INFO("Scaling efficiency (4 agents): " << efficiency_4 << "%"); - } - } - - auto result = collector.finalize(); - ReportGenerator reporter("results"); - reporter.export_all(result, "scaling_efficiency"); -} diff --git a/benchmarks/scalability/thread_scaling_bench.cpp b/benchmarks/scalability/thread_scaling_bench.cpp index 86f543d1..64d89900 100644 --- a/benchmarks/scalability/thread_scaling_bench.cpp +++ b/benchmarks/scalability/thread_scaling_bench.cpp @@ -19,17 +19,12 @@ using namespace DSR; using namespace DSR::Benchmark; using namespace std::chrono; -// Measures throughput + latency across {1, 2, 4, 8} threads for each -// operation. Each iteration runs a 5-second window; per-thread raw latency -// samples are merged into a single LatencyTracker for aggregate stats. -// A record_scalability() entry is added so the Scalability tab can plot -// the efficiency curve (scale_dim = "threads"). -// -// nanobench wraps each (op, thread-count) run so results appear in the shared -// nanobench table (stdout + results/nanobench_report.md). bench.batch() is -// set to total_ops so the table shows per-operation throughput, not wall time. - -static constexpr auto THREAD_DUR = std::chrono::seconds(5); +// Measures throughput across {1, 2, 4, 8} threads for each operation. +// Each iteration runs a 3-second window. Per-thread latency is intentionally +// not collected here — merged percentiles from concurrent threads are +// statistically misleading. Use the single-agent latency benchmarks instead. + +static constexpr auto THREAD_DUR = std::chrono::seconds(3); // ── Node insert ─────────────────────────────────────────────────────────────── @@ -52,9 +47,6 @@ TEST_CASE("Node insert thread scaling", "[SCALABILITY][threads]") { std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(2000000 / N); - std::vector threads; threads.reserve(N); @@ -65,16 +57,13 @@ TEST_CASE("Node insert thread scaling", "[SCALABILITY][threads]") { threads.emplace_back([&, tid = t]() { uint64_t base_id = 200000ULL + tid * 200000ULL; uint64_t local_ops = 0; - auto& samples = per_thread_samples[tid]; sync_point.arrive_and_wait(); while (!stop_flag.load(std::memory_order_relaxed)) { auto node = GraphGenerator::create_test_node( base_id + local_ops, graph->get_agent_id()); - uint64_t ts = bench_now(); auto res = graph->insert_node(node); - samples.push_back(bench_now() - ts); if (!res.has_value()) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -98,16 +87,8 @@ TEST_CASE("Node insert thread scaling", "[SCALABILITY][threads]") { auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_insert", total_ops.load(), dur, - {{"threads", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_insert", merged.stats(), - {{"threads", n_str}}); + collector.record_throughput("node_insert", total_ops.load(), dur, {{"threads", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -132,7 +113,6 @@ TEST_CASE("Node read thread scaling", "[SCALABILITY][threads]") { auto* graph = fixture.get_agent(0); REQUIRE(graph != nullptr); - // Pre-populate once; all thread-count iterations share this pool. std::vector node_ids; node_ids.reserve(1000); for (uint64_t i = 0; i < 1000; ++i) { @@ -152,9 +132,6 @@ TEST_CASE("Node read thread scaling", "[SCALABILITY][threads]") { std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(2000000 / N); - std::vector threads; threads.reserve(N); @@ -164,15 +141,12 @@ TEST_CASE("Node read thread scaling", "[SCALABILITY][threads]") { for (uint32_t t = 0; t < N; ++t) { threads.emplace_back([&, tid = t]() { uint64_t local_ops = 0; - auto& samples = per_thread_samples[tid]; sync_point.arrive_and_wait(); while (!stop_flag.load(std::memory_order_relaxed)) { uint64_t id = node_ids[local_ops % pool_size]; - uint64_t ts = bench_now(); auto node = graph->get_node(id); - samples.push_back(bench_now() - ts); if (!node.has_value()) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -196,16 +170,8 @@ TEST_CASE("Node read thread scaling", "[SCALABILITY][threads]") { auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_read", total_ops.load(), dur, - {{"threads", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_read", merged.stats(), - {{"threads", n_str}}); + collector.record_throughput("node_read", total_ops.load(), dur, {{"threads", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -230,15 +196,12 @@ TEST_CASE("Node update thread scaling", "[SCALABILITY][threads]") { auto* graph = fixture.get_agent(0); REQUIRE(graph != nullptr); - // Pre-insert 8 nodes (one per thread for the largest N); each thread - // updates its own node to measure scaling without lock contention. constexpr uint32_t MAX_THREADS = 8; std::vector node_ids; node_ids.reserve(MAX_THREADS); for (uint32_t t = 0; t < MAX_THREADS; ++t) { auto node = GraphGenerator::create_test_node( - 500000 + t, graph->get_agent_id(), - "update_node_" + std::to_string(t)); + 500000 + t, graph->get_agent_id(), "update_node_" + std::to_string(t)); auto res = graph->insert_node(node); REQUIRE(res.has_value()); node_ids.push_back(res.value()); @@ -253,9 +216,6 @@ TEST_CASE("Node update thread scaling", "[SCALABILITY][threads]") { std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(2000000 / N); - std::vector threads; threads.reserve(N); @@ -265,7 +225,6 @@ TEST_CASE("Node update thread scaling", "[SCALABILITY][threads]") { for (uint32_t t = 0; t < N; ++t) { threads.emplace_back([&, tid = t]() { uint64_t local_ops = 0; - auto& samples = per_thread_samples[tid]; uint64_t nid = node_ids[tid]; sync_point.arrive_and_wait(); @@ -275,9 +234,7 @@ TEST_CASE("Node update thread scaling", "[SCALABILITY][threads]") { if (node) { graph->add_or_modify_attrib_local( *node, static_cast(local_ops % 1000)); - uint64_t ts = bench_now(); bool ok = graph->update_node(*node); - samples.push_back(bench_now() - ts); if (!ok) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -304,16 +261,8 @@ TEST_CASE("Node update thread scaling", "[SCALABILITY][threads]") { auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("node_update", total_ops.load(), dur, - {{"threads", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("node_update", merged.stats(), - {{"threads", n_str}}); + collector.record_throughput("node_update", total_ops.load(), dur, {{"threads", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -341,7 +290,6 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { auto root = graph->get_node_root(); REQUIRE(root.has_value()); - // Pre-populate target node pool; shared across all N iterations. constexpr uint32_t POOL_SIZE = 10000; std::vector pool; pool.reserve(POOL_SIZE); @@ -362,9 +310,6 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(2000000 / N); - std::vector threads; threads.reserve(N); @@ -375,7 +320,6 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { for (uint32_t t = 0; t < N; ++t) { threads.emplace_back([&, tid = t]() { uint64_t local_ops = 0; - auto& samples = per_thread_samples[tid]; sync_point.arrive_and_wait(); @@ -383,9 +327,7 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { uint64_t idx = (local_ops + tid * stride) % pool_size; auto edge = GraphGenerator::create_test_edge( root->id(), pool[idx], graph->get_agent_id()); - uint64_t ts = bench_now(); bool ok = graph->insert_or_assign_edge(edge); - samples.push_back(bench_now() - ts); if (!ok) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -409,16 +351,8 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("edge_insert", total_ops.load(), dur, - {{"threads", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("edge_insert", merged.stats(), - {{"threads", n_str}}); + collector.record_throughput("edge_insert", total_ops.load(), dur, {{"threads", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); @@ -446,7 +380,6 @@ TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { auto root = graph->get_node_root(); REQUIRE(root.has_value()); - // Pre-populate 1000 nodes + edges; shared across all N iterations. constexpr uint32_t POOL_SIZE = 1000; std::vector pool; pool.reserve(POOL_SIZE); @@ -455,8 +388,7 @@ TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { auto res = graph->insert_node(node); REQUIRE(res.has_value()); pool.push_back(res.value()); - auto edge = GraphGenerator::create_test_edge( - root->id(), res.value(), graph->get_agent_id()); + auto edge = GraphGenerator::create_test_edge(root->id(), res.value(), graph->get_agent_id()); REQUIRE(graph->insert_or_assign_edge(edge)); } const size_t pool_size = pool.size(); @@ -470,9 +402,6 @@ TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { std::atomic stop_flag{false}; std::barrier sync_point(N); - std::vector> per_thread_samples(N); - for (auto& s : per_thread_samples) s.reserve(2000000 / N); - std::vector threads; threads.reserve(N); @@ -483,15 +412,12 @@ TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { for (uint32_t t = 0; t < N; ++t) { threads.emplace_back([&, tid = t]() { uint64_t local_ops = 0; - auto& samples = per_thread_samples[tid]; sync_point.arrive_and_wait(); while (!stop_flag.load(std::memory_order_relaxed)) { uint64_t idx = (local_ops + tid * stride) % pool_size; - uint64_t ts = bench_now(); auto edge = graph->get_edge(root->id(), pool[idx], "test_edge"); - samples.push_back(bench_now() - ts); if (!edge.has_value()) failed_ops.fetch_add(1, std::memory_order_relaxed); local_ops++; @@ -515,16 +441,8 @@ TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { auto dur = duration_cast(steady_clock::now() - wall_start); - LatencyTracker merged; - for (auto& s : per_thread_samples) - for (auto v : s) merged.record(v); - const std::string n_str = std::to_string(N); - collector.record_throughput("edge_read", total_ops.load(), dur, - {{"threads", n_str}}); - if (!merged.empty()) - collector.record_latency_stats("edge_read", merged.stats(), - {{"threads", n_str}}); + collector.record_throughput("edge_read", total_ops.load(), dur, {{"threads", n_str}}); double ops_per_sec = static_cast(total_ops.load()) / (static_cast(dur.count()) / 1000.0); diff --git a/benchmarks/throughput/concurrent_writers_bench.cpp b/benchmarks/throughput/concurrent_writers_bench.cpp index 6c9bda76..8d5228f6 100644 --- a/benchmarks/throughput/concurrent_writers_bench.cpp +++ b/benchmarks/throughput/concurrent_writers_bench.cpp @@ -28,7 +28,7 @@ TEST_CASE("Concurrent writers throughput", "[THROUGHPUT][concurrent][PROFILE][LO auto* graph = fixture.get_agent(0); REQUIRE(graph != nullptr); - constexpr auto TEST_DURATION = std::chrono::seconds(5); + constexpr auto TEST_DURATION = std::chrono::seconds(2); ankerl::nanobench::Bench bench; bench.output(&nb_report_stream()).warmup(0).epochs(1).epochIterations(1); @@ -131,7 +131,7 @@ TEST_CASE("Concurrent read-write throughput", "[THROUGHPUT][concurrent][PROFILE] pre_node_ids.push_back(result.value()); } - constexpr auto TEST_DURATION = std::chrono::seconds(5); + constexpr auto TEST_DURATION = std::chrono::seconds(2); ankerl::nanobench::Bench bench; bench.output(&nb_report_stream()).warmup(0).epochs(1).epochIterations(1); @@ -293,7 +293,7 @@ TEST_CASE("Concurrent read-write throughput", "[THROUGHPUT][concurrent][PROFILE] reporter.export_all(result, "concurrent_read_write"); } -TEST_CASE("Multi-agent concurrent operations", "[THROUGHPUT][concurrent][multiagent][.multi][PROFILE][LOAD][MULTIAGENT]") { +TEST_CASE("Multi-agent concurrent operations", "[THROUGHPUT][concurrent][multiagent][PROFILE][LOAD][MULTIAGENT]") { MultiAgentFixture fixture; GraphGenerator generator; MetricsCollector collector("multiagent_concurrent"); @@ -302,7 +302,7 @@ TEST_CASE("Multi-agent concurrent operations", "[THROUGHPUT][concurrent][multiag REQUIRE(fixture.create_agents(4, config_file)); fixture.wait_for_sync(); - constexpr auto TEST_DURATION = std::chrono::seconds(5); + constexpr auto TEST_DURATION = std::chrono::seconds(2); SECTION("Each agent writes independently") { std::atomic total_ops{0}; diff --git a/benchmarks/throughput/query_ops_bench.cpp b/benchmarks/throughput/query_ops_bench.cpp deleted file mode 100644 index 360d71f8..00000000 --- a/benchmarks/throughput/query_ops_bench.cpp +++ /dev/null @@ -1,131 +0,0 @@ -#include - -#include "../core/nanobench_adapter.h" -#include "../core/metrics_collector.h" -#include "../core/report_generator.h" -#include "../fixtures/multi_agent_fixture.h" -#include "../fixtures/graph_generator.h" - -using namespace DSR; -using namespace DSR::Benchmark; - -TEST_CASE("Graph query convenience operations", "[EXTENDED][LATENCY][THROUGHPUT][query][single][.extended]") { - MultiAgentFixture fixture; - GraphGenerator generator; - MetricsCollector collector("graph_query_baseline"); - collector.add_metadata("profile", "extended"); - - auto config_file = generator.generate_empty_graph(); - REQUIRE(fixture.create_agents(1, config_file)); - auto* graph = fixture.get_agent(0); - REQUIRE(graph != nullptr); - - auto root = graph->get_node_root(); - REQUIRE(root.has_value()); - - std::vector node_ids; - node_ids.reserve(1000); - for (uint64_t i = 0; i < 1000; ++i) { - auto node = GraphGenerator::create_test_node(i, graph->get_agent_id(), "query_node_" + std::to_string(i)); - auto inserted = graph->insert_node(node); - REQUIRE(inserted.has_value()); - node_ids.push_back(*inserted); - - auto edge = GraphGenerator::create_test_edge(root->id(), *inserted, graph->get_agent_id()); - REQUIRE(graph->insert_or_assign_edge(edge)); - } - - for (auto id : node_ids) { - (void)graph->get_node(id); - } - (void)graph->get_nodes(); - (void)graph->get_nodes_by_type("test_node"); - (void)graph->get_edges(root->id()); - (void)graph->get_edges_to_id(root->id()); - (void)graph->get_edges_by_type("test_edge"); - - { - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(10); - bench.run("get_nodes", [&] { - auto nodes = graph->get_nodes(); - ankerl::nanobench::doNotOptimizeAway(nodes); - }); - collector.record_latency_stats("get_nodes", nb_to_stats(bench)); - collector.record("get_nodes", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(10); - bench.run("get_nodes_by_type", [&] { - auto nodes = graph->get_nodes_by_type("test_node"); - ankerl::nanobench::doNotOptimizeAway(nodes); - }); - collector.record_latency_stats("get_nodes_by_type", nb_to_stats(bench)); - collector.record("get_nodes_by_type", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(20); - bench.run("get_edges_from_root", [&] { - auto edges = graph->get_edges(root->id()); - ankerl::nanobench::doNotOptimizeAway(edges); - }); - collector.record_latency_stats("get_edges_from_root", nb_to_stats(bench)); - collector.record("get_edges_from_root", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(20); - bench.run("get_edges_to_root", [&] { - auto edges = graph->get_edges_to_id(root->id()); - ankerl::nanobench::doNotOptimizeAway(edges); - }); - collector.record_latency_stats("get_edges_to_root", nb_to_stats(bench)); - collector.record("get_edges_to_root", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(20); - bench.run("get_edges_by_type", [&] { - auto edges = graph->get_edges_by_type("test_edge"); - ankerl::nanobench::doNotOptimizeAway(edges); - }); - collector.record_latency_stats("get_edges_by_type", nb_to_stats(bench)); - collector.record("get_edges_by_type", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - size_t idx = 0; - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(5000); - bench.run("get_name_from_id", [&] { - auto name = graph->get_name_from_id(node_ids[idx++ % node_ids.size()]); - REQUIRE(name.has_value()); - ankerl::nanobench::doNotOptimizeAway(name); - }); - collector.record_latency_stats("get_name_from_id", nb_to_stats(bench)); - collector.record("get_name_from_id", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - { - size_t idx = 0; - auto bench = make_latency_bench(1000, 0); - bench.minEpochIterations(5000); - bench.run("get_id_from_name", [&] { - auto id = graph->get_id_from_name("query_node_" + std::to_string(idx++ % node_ids.size())); - REQUIRE(id.has_value()); - ankerl::nanobench::doNotOptimizeAway(id); - }); - collector.record_latency_stats("get_id_from_name", nb_to_stats(bench)); - collector.record("get_id_from_name", MetricCategory::Throughput, nb_throughput(bench), "ops/sec"); - } - - auto result = collector.finalize(); - ReportGenerator reporter("results"); - reporter.export_all(result, "graph_query_baseline"); -} diff --git a/tests/synchronization/graph_signals.cpp b/tests/synchronization/graph_signals.cpp index dcdaf67d..af226267 100644 --- a/tests/synchronization/graph_signals.cpp +++ b/tests/synchronization/graph_signals.cpp @@ -685,8 +685,8 @@ TEST_CASE("delete an edge", "[GRAPH][SIGNALS]") { G.insert_or_assign_edge(e); Edge e2 = new_edge_(0).second; - e.from(*r2); - e.to(*r); + e2.from(*r2); + e2.to(*r); G.insert_or_assign_edge(e2); bool update_node_signal_recv = false; diff --git a/tests/synchronization/graph_synchronization.cpp b/tests/synchronization/graph_synchronization.cpp index ab113999..f62c5525 100644 --- a/tests/synchronization/graph_synchronization.cpp +++ b/tests/synchronization/graph_synchronization.cpp @@ -4,6 +4,9 @@ #include "dsr/api/dsr_api.h" #include "../utils.h" #include +#include +#include +#include #include "catch2/catch_test_macros.hpp" #include "catch2/generators/catch_generators.hpp" @@ -181,3 +184,4 @@ TEST_CASE("Node delta join rejects incompatible protocol versions", "[SYNCHRONIZ REQUIRE_FALSE(receiver.get_node(node.id()).has_value()); } + diff --git a/tests/synchronization/lww_sync_engine.cpp b/tests/synchronization/lww_sync_engine.cpp index edec6d87..be17d050 100644 --- a/tests/synchronization/lww_sync_engine.cpp +++ b/tests/synchronization/lww_sync_engine.cpp @@ -26,9 +26,18 @@ struct FakeSyncHost final : SyncEngineHost SyncMode local_sync_mode() const override { return mode; } bool is_copy_graph() const override { return copy; } - void update_maps_node_insert(const Node& node) override { nodes[node.id()] = node; } + void update_maps_node_insert(uint64_t id, std::string_view name, std::string_view type, const EdgeKeyList& outgoing_edges) override + { + Node node(agent, std::string{type}); + node.id(id); + node.name(std::string{name}); + for (const auto& [to, edge_type] : outgoing_edges) { + node.fano().emplace(std::pair{to, edge_type}, Edge(to, id, edge_type, {}, agent)); + } + nodes[id] = std::move(node); + } - void update_maps_node_delete(uint64_t id, const std::optional&) override + void update_maps_node_delete(uint64_t id, std::optional, const EdgeKeyList&) override { nodes.erase(id); for (auto it = edges.begin(); it != edges.end(); ) { From efd1dd710d9f5468af8866bfd137b9cd9ce143bb Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 23 Apr 2026 22:20:18 +0200 Subject: [PATCH 24/38] refactor: avoid unnecessary type translations --- api/dsr_api.cpp | 98 +----------- api/dsr_crdt_sync_engine.cpp | 52 ++++-- api/dsr_lww_sync_engine.cpp | 158 ++++++++++++------- api/include/dsr/api/dsr_api.h | 55 ++++++- api/include/dsr/api/dsr_crdt_sync_engine.h | 1 + api/include/dsr/api/dsr_graph_settings.h | 11 +- api/include/dsr/api/dsr_lww_sync_engine.h | 12 +- api/include/dsr/api/dsr_sync_engine.h | 7 +- core/include/dsr/core/types/internal_types.h | 10 ++ core/include/dsr/core/types/lww_index.h | 66 ++++---- core/include/dsr/core/types/lww_types.h | 75 ++++++++- core/include/dsr/core/types/user_types.h | 4 - 12 files changed, 317 insertions(+), 232 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index b1abd4f1..05e311ed 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -1070,106 +1070,16 @@ std::string DSRGraph::get_node_type(Node &n) ////////////////////////////////////////////////////////////////////////////////////////////// -void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional &n) +void DSRGraph::update_maps_node_insert(uint64_t id, std::string_view name, std::string_view type, const EdgeKeyList& outgoing_edges) { - std::unique_lock lck(_mutex_cache_maps); - if (id_map.contains(id)) - { - name_map.erase(id_map.at(id)); - id_map.erase(id); - } - deleted.insert(id); - to_edges.erase(id); - - if (n.has_value()) - { - if (nodeType.contains(n->type())) { - nodeType.at(n->type()).erase(id); - if (nodeType.at(n->type()).empty()) nodeType.erase(n->type()); - } - for (const auto &[k, v] : n->fano()) { - if (auto tuple = std::pair{id, v.read_reg().to()}; edges.contains(tuple)) { - edges.at(tuple).erase(k.second); - if (edges.at(tuple).empty()) edges.erase(tuple); - } - if (auto tuple = std::pair{id, k.first}; edgeType.contains(k.second)) { - edgeType.at(k.second).erase(tuple); - if (edgeType.at(k.second).empty())edgeType.erase(k.second); - } - if (auto tuple = std::pair{id, k.second}; to_edges.contains(k.first)) { - to_edges.at(k.first).erase(tuple); - if (to_edges.at(k.first).empty()) to_edges.erase(k.first); - } - } - } + update_maps_node_insert_impl(id, std::string{name}, std::string{type}, outgoing_edges); } -void DSRGraph::update_maps_node_insert(uint64_t id, const CRDTNode &n) +void DSRGraph::update_maps_node_delete(uint64_t id, std::optional type, const EdgeKeyList& outgoing_edges) { - std::unique_lock lck(_mutex_cache_maps); - - name_map[n.name()] = id; - id_map[id] = n.name(); - nodeType[n.type()].emplace(id); - for (const auto &[k, v] : n.fano()) - { - edges[{id, k.first}].insert(k.second); - edgeType[k.second].insert({id, k.first}); - to_edges[k.first].insert({id, k.second}); - } + update_maps_node_delete_impl(id, type, outgoing_edges); } -void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional& n) -{ - std::unique_lock lck(_mutex_cache_maps); - if (id_map.contains(id)) - { - name_map.erase(id_map.at(id)); - id_map.erase(id); - } - deleted.insert(id); - to_edges.erase(id); - - if (n.has_value()) - { - if (nodeType.contains(n->type())) { - nodeType.at(n->type()).erase(id); - if (nodeType.at(n->type()).empty()) nodeType.erase(n->type()); - } - for (const auto &[k, v] : n->fano()) { - if (const auto tuple = std::pair{id, v.to()}; edges.contains(tuple)) { - edges.at(tuple).erase(k.second); - if (edges.at(tuple).empty()) edges.erase(tuple); - } - if (edgeType.contains(k.second)) { - edgeType.at(k.second).erase({id, k.first}); - if (edgeType.at(k.second).empty()) edgeType.erase(k.second); - } - if (to_edges.contains(k.first)) { - to_edges.at(k.first).erase({id, k.second}); - if (to_edges.at(k.first).empty()) to_edges.erase(k.first); - } - } - } -} - -void DSRGraph::update_maps_node_insert(const Node& n) -{ - std::unique_lock lck(_mutex_cache_maps); - - deleted.erase(n.id()); - name_map[n.name()] = n.id(); - id_map[n.id()] = n.name(); - nodeType[n.type()].emplace(n.id()); - for (const auto& [k, v] : n.fano()) - { - edges[{n.id(), k.first}].insert(k.second); - edgeType[k.second].insert({n.id(), k.first}); - to_edges[k.first].insert({n.id(), k.second}); - } -} - - void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key) { diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 7b554b6b..f539588a 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -11,6 +11,17 @@ using namespace DSR; namespace { +template +SyncEngineHost::EdgeKeyList collect_outgoing_edge_keys(const Fano& fano) +{ + SyncEngineHost::EdgeKeyList outgoing_edges; + outgoing_edges.reserve(fano.size()); + for (const auto& [key, _] : fano) { + outgoing_edges.emplace_back(key.first, key.second); + } + return outgoing_edges; +} + bool protocol_version_matches( DSR::GraphSettings::LOGLEVEL log_level, const char* channel, @@ -98,7 +109,7 @@ std::optional CRDTSyncEngine::get_node(uint64_t id) const std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { - if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + if (const auto* edge = get_crdt_edge_ptr(from, to, type); edge != nullptr) { return to_user_edge(*edge); } return {}; @@ -143,7 +154,7 @@ bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vi bool found = false; host_.for_each_incoming_edge(to, [&](uint64_t from, const std::string& type) { found = true; - if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + if (const auto* edge = get_crdt_edge_ptr(from, to, type); edge != nullptr) { Edge out = to_user_edge(*edge); visitor(from, type, out); } @@ -154,7 +165,7 @@ bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vi void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { host_.for_each_edge_of_type_cache(type, [&](uint64_t from, uint64_t to) { - if (auto edge = get_crdt_edge(from, to, type); edge.has_value()) { + if (const auto* edge = get_crdt_edge_ptr(from, to, type); edge != nullptr) { Edge out = to_user_edge(*edge); visitor(from, to, out); } @@ -372,19 +383,27 @@ std::optional CRDTSyncEngine::get_crdt_node(uint64_t id) const return {}; } -std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const +const CRDTEdge* CRDTSyncEngine::get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const { auto from_it = nodes_.find(from); if (from_it == nodes_.end() || from_it->second.empty() || !nodes_.contains(to)) { - return {}; + return nullptr; } auto& fano = from_it->second.read_reg().fano(); auto edge = fano.find({to, key}); if (edge != fano.end() && !edge->second.empty()) { - return edge->second.read_reg(); + return &edge->second.read_reg(); } + return nullptr; +} + +std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const +{ + if (const auto* edge = get_crdt_edge_ptr(from, to, key); edge != nullptr) { + return *edge; + } return {}; } @@ -399,7 +418,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR } uint64_t id = node.id(); - host_.update_maps_node_insert(to_user_node(node)); + host_.update_maps_node_insert(id, node.name(), node.type(), collect_outgoing_edge_keys(node.fano())); auto delta = nodes_[id].write(std::move(node)); nodes_[id].join(mvreg(delta)); return {true, crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta))}; @@ -479,7 +498,7 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) } } - host_.update_maps_node_delete(id, std::make_optional(to_user_node(node))); + host_.update_maps_node_delete(id, node.type(), collect_outgoing_edge_keys(node.fano())); return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; } @@ -706,14 +725,15 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) incoming_edge_cache.emplace_back(from, type); }); } - std::optional deleted_node_user = maybe_deleted_node.has_value() - ? std::make_optional(to_user_node(*maybe_deleted_node)) : std::nullopt; - host_.update_maps_node_delete(id, deleted_node_user); + host_.update_maps_node_delete( + id, + maybe_deleted_node.has_value() ? std::optional{maybe_deleted_node->type()} : std::nullopt, + maybe_deleted_node.has_value() ? collect_outgoing_edge_keys(maybe_deleted_node->fano()) : SyncEngineHost::EdgeKeyList{}); delete_unprocessed_deltas(); } else { const auto& reg = nodes_.at(id).read_reg(); current_type = reg.type(); - host_.update_maps_node_insert(to_user_node(reg)); + host_.update_maps_node_insert(reg.id(), reg.name(), reg.type(), collect_outgoing_edge_keys(reg.fano())); consume_unprocessed_deltas(); } signal = !d_empty; @@ -1044,13 +1064,15 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } it->second.join(std::move(mv)); if (mv_empty or it->second.empty()) { - std::optional nd_user = nd.has_value() ? std::make_optional(to_user_node(*nd)) : std::nullopt; - host_.update_maps_node_delete(k, nd_user); + host_.update_maps_node_delete( + k, + nd.has_value() ? std::optional{nd->type()} : std::nullopt, + nd.has_value() ? collect_outgoing_edge_keys(nd->fano()) : SyncEngineHost::EdgeKeyList{}); updates.emplace_back(false, k, "", std::nullopt, std::nullopt); delete_unprocessed_deltas(); } else { const auto& reg = it->second.read_reg(); - host_.update_maps_node_insert(to_user_node(reg)); + host_.update_maps_node_insert(reg.id(), reg.name(), reg.type(), collect_outgoing_edge_keys(reg.fano())); updates.emplace_back(true, k, reg.type(), nd, reg); consume_unprocessed_deltas(); } diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 24d41800..3d931501 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -7,6 +7,7 @@ using namespace DSR; using DSR::LWW::edge_key; +using DSR::LWW::edge_key_view; using DSR::LWW::is_newer; using DSR::LWW::version_of; @@ -32,6 +33,29 @@ std::vector collect_changed_attr_names(const AttrMap& before, const return changed; } +SyncEngineHost::EdgeKeyList collect_outgoing_edge_keys(const LWW::FromIndex& from_idx, uint64_t from) +{ + SyncEngineHost::EdgeKeyList outgoing_edges; + if (auto it = from_idx.find(from); it != from_idx.end()) { + outgoing_edges.reserve(it->second.size()); + for (const auto* edge : it->second) { + outgoing_edges.emplace_back(edge->to, edge->type); + } + } + return outgoing_edges; +} + +template +SyncEngineHost::EdgeKeyList collect_outgoing_edge_keys(const Fano& fano) +{ + SyncEngineHost::EdgeKeyList outgoing_edges; + outgoing_edges.reserve(fano.size()); + for (const auto& [key, _] : fano) { + outgoing_edges.emplace_back(key.first, key.second); + } + return outgoing_edges; +} + class LWWNodeAttrsView final : public SyncEngine::NodeAttrsView { public: @@ -82,8 +106,8 @@ LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, const LWWSyncEngine& other) node_tombstones_(other.node_tombstones_), edge_tombstones_(other.edge_tombstones_) { - for (const auto& [key, _] : edges_) { - idx_insert(key); + for (const auto& [key, state] : edges_) { + LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, state); } } @@ -98,14 +122,11 @@ std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const return std::make_unique(host, *this); } -void LWWSyncEngine::idx_insert(const EdgeKey& key) -{ - LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, key); -} - -void LWWSyncEngine::idx_erase(const EdgeKey& key) +void LWWSyncEngine::maybe_prune_tombstones(uint64_t now) { - LWW::edge_index_erase(from_idx_, to_idx_, type_idx_, key); + if (now - last_prune_ms_ < 1000) return; + last_prune_ms_ = now; + prune_tombstones(now); } uint64_t LWWSyncEngine::current_time_ms() const @@ -141,12 +162,16 @@ void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std:: void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::erase_related_edges"); - std::unordered_set to_erase; + std::unordered_set to_erase; if (auto it = from_idx_.find(node_id); it != from_idx_.end()) { - to_erase.insert(it->second.begin(), it->second.end()); + for (const auto* edge : it->second) { + to_erase.emplace(edge_key(edge->from, edge->to, edge->type)); + } } if (auto it = to_idx_.find(node_id); it != to_idx_.end()) { - to_erase.insert(it->second.begin(), it->second.end()); + for (const auto* edge : it->second) { + to_erase.emplace(edge_key(edge->from, edge->to, edge->type)); + } } for (const auto& key : to_erase) { auto eit = edges_.find(key); @@ -156,7 +181,7 @@ void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint6 if (removed_edges != nullptr) { removed_edges->emplace_back(LWW::to_user_edge(eit->second)); } - idx_erase(key); + LWW::edge_index_erase(from_idx_, to_idx_, type_idx_, eit->second); edges_.erase(eit); } } @@ -166,13 +191,13 @@ std::optional LWWSyncEngine::get_node(uint64_t id) const CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_node"); auto it = nodes_.find(id); if (it == nodes_.end()) return {}; - return LWW::to_user_node(it->second, edges_, from_idx_); + return LWW::to_user_node(it->second, from_idx_); } std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_edge"); - if (auto it = edges_.find(edge_key(from, to, type)); it != edges_.end()) { + if (auto it = edges_.find(edge_key_view(from, to, type)); it != edges_.end()) { return LWW::to_user_edge(it->second); } return {}; @@ -207,19 +232,19 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& if (auto it = from_idx_.find(from); it == from_idx_.end()) { return true; } - return LWW::for_each_edge_from(edges_, from_idx_, from, visitor); + return LWW::for_each_edge_from(from_idx_, from, visitor); } bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_to"); - return LWW::for_each_edge_to(edges_, to_idx_, to, visitor); + return LWW::for_each_edge_to(to_idx_, to, visitor); } void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_of_type"); - LWW::for_each_edge_of_type(edges_, type_idx_, type, visitor); + LWW::for_each_edge_of_type(type_idx_, type, visitor); } size_t LWWSyncEngine::size() const @@ -231,8 +256,8 @@ std::map LWWSyncEngine::snapshot() const { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::snapshot"); std::map out; - for (const auto& [id, _] : nodes_) { - out.emplace(id, *get_node(id)); + for (const auto& [id, st] : nodes_) { + out.emplace(id, LWW::to_user_node(st, from_idx_)); } return out; } @@ -241,7 +266,7 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) { CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::insert_node_local"); auto now = next_timestamp(); - prune_tombstones(now); + maybe_prune_tombstones(now); NodeMutationEffect effect; effect.id = node.id(); @@ -257,11 +282,12 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) effect.changed_attributes.emplace_back(name); } - nodes_[node.id()] = std::move(state); + auto& slot = nodes_[node.id()]; + slot = std::move(state); node_tombstones_.erase(node.id()); - host_.update_maps_node_insert(node); + host_.update_maps_node_insert(node.id(), node.name(), node.type(), collect_outgoing_edge_keys(node.fano())); effect.applied = true; - effect.node_delta = NodeDeltaMessage{*export_node_delta(effect.id)}; + effect.node_delta = NodeDeltaMessage{LWW::to_node_msg(slot)}; return effect; } @@ -269,7 +295,7 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) { CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::update_node_local"); auto now = next_timestamp(); - prune_tombstones(now); + maybe_prune_tombstones(now); NodeMutationEffect effect; effect.id = node.id(); @@ -280,7 +306,8 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) return effect; } - auto old_node = get_node(node.id()); + const auto old_type = it->second.type; + auto old_outgoing_edges = collect_outgoing_edge_keys(from_idx_, node.id()); auto version = version_of(now, host_.local_agent_id()); it->second.type = node.type(); it->second.name = node.name(); @@ -291,10 +318,10 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) effect.changed_attributes = collect_changed_attr_names(it->second.attrs, next_attrs); it->second.attrs = std::move(next_attrs); - host_.update_maps_node_delete(node.id(), old_node); - host_.update_maps_node_insert(node); + host_.update_maps_node_delete(node.id(), old_type, old_outgoing_edges); + host_.update_maps_node_insert(node.id(), node.name(), node.type(), collect_outgoing_edge_keys(node.fano())); effect.applied = true; - effect.node_delta = NodeDeltaMessage{*export_node_delta(effect.id)}; + effect.node_delta = NodeDeltaMessage{LWW::to_node_msg(it->second)}; return effect; } @@ -302,7 +329,7 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) { CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::delete_node_local"); auto now = next_timestamp(); - prune_tombstones(now); + maybe_prune_tombstones(now); NodeMutationEffect effect; effect.id = id; @@ -312,11 +339,12 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) } auto version = version_of(now, host_.local_agent_id()); - auto deleted_node = get_node(id); + std::optional deleted_node = LWW::to_user_node(it->second, from_idx_); + auto outgoing_edges = collect_outgoing_edge_keys(from_idx_, id); effect.deleted_node = deleted_node; effect.deleted_edges.clear(); erase_related_edges(id, version, now, &effect.deleted_edges); - host_.update_maps_node_delete(id, deleted_node); + host_.update_maps_node_delete(id, it->second.type, outgoing_edges); store_node_tombstone(id, version, now); nodes_.erase(it); effect.applied = true; @@ -336,35 +364,47 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) { CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::insert_or_assign_edge_local"); auto now = next_timestamp(); - prune_tombstones(now); + maybe_prune_tombstones(now); EdgeMutationEffect effect; effect.from = edge.from(); effect.to = edge.to(); effect.type = edge.type(); - auto version = version_of(now, host_.local_agent_id()); - if (!nodes_.contains(edge.from()) || !nodes_.contains(edge.to()) || - LWW::delta_is_stale(edge_tombstones_, edges_, edge_key(edge.from(), edge.to(), edge.type()), version)) { + if (!nodes_.contains(edge.from()) || !nodes_.contains(edge.to())) { return effect; } + auto version = version_of(now, host_.local_agent_id()); auto key = edge_key(edge.from(), edge.to(), edge.type()); + + // For local mutations our version is always the newest; only tombstone dominance matters. + auto ts_it = edge_tombstones_.find(key); + if (ts_it != edge_tombstones_.end() && !LWW::is_newer(version, ts_it->second.version)) { + return effect; + } + + auto [it, inserted] = edges_.try_emplace(key); auto next_state = LWW::to_edge_state(edge, version, host_.local_agent_id()); - if (const auto old_it = edges_.find(key); old_it != edges_.end()) { - effect.changed_attributes = collect_changed_attr_names(old_it->second.attrs, next_state.attrs); - } else { + if (inserted) { effect.changed_attributes.reserve(next_state.attrs.size()); for (const auto& [name, _] : next_state.attrs) { effect.changed_attributes.emplace_back(name); } + it->second = std::move(next_state); + LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, it->second); + } else { + effect.changed_attributes = collect_changed_attr_names(it->second.attrs, next_state.attrs); + it->second = std::move(next_state); + // Index pointers remain valid — unordered_map guarantees pointer stability. + } + + if (ts_it != edge_tombstones_.end()) { + edge_tombstones_.erase(ts_it); } - edges_[key] = std::move(next_state); - idx_insert(key); // idempotent for updates - edge_tombstones_.erase(key); host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); effect.applied = true; - effect.edge_delta = EdgeDeltaMessage{*export_edge_delta(effect.from, effect.to, effect.type)}; + effect.edge_delta = EdgeDeltaMessage{LWW::to_edge_msg(it->second)}; return effect; } @@ -372,7 +412,7 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, { CORTEX_PROFILE_ZONE_CS("LWWSyncEngine::delete_edge_local"); auto now = next_timestamp(); - prune_tombstones(now); + maybe_prune_tombstones(now); EdgeMutationEffect effect; effect.from = from; @@ -389,7 +429,7 @@ EdgeMutationEffect LWWSyncEngine::delete_edge_local(uint64_t from, uint64_t to, effect.deleted_edge = LWW::to_user_edge(it->second); host_.update_maps_edge_delete(from, to, type); store_edge_tombstone(from, to, type, version, now); - idx_erase(key); + LWW::edge_index_erase(from_idx_, to_idx_, type_idx_, it->second); edges_.erase(it); effect.applied = true; if (auto delta = export_edge_delta(from, to, type); delta.has_value()) { @@ -420,9 +460,10 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) std::optional deleted_node; std::vector deleted_edges; if (auto it = nodes_.find(payload->id); it != nodes_.end()) { + auto outgoing_edges = collect_outgoing_edge_keys(from_idx_, payload->id); deleted_node = get_node(payload->id); erase_related_edges(payload->id, version, now, &deleted_edges); - host_.update_maps_node_delete(payload->id, deleted_node); + host_.update_maps_node_delete(payload->id, it->second.type, outgoing_edges); nodes_.erase(it); } store_node_tombstone(payload->id, version, now); @@ -434,13 +475,12 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_delta upsert"); - auto maybe_old = get_node(payload->id); - if (maybe_old.has_value()) { - host_.update_maps_node_delete(payload->id, maybe_old); + if (const auto* current = get_node_ptr(payload->id); current != nullptr) { + host_.update_maps_node_delete(payload->id, current->type, collect_outgoing_edge_keys(from_idx_, payload->id)); } nodes_[payload->id] = std::move(state); node_tombstones_.erase(payload->id); - host_.update_maps_node_insert(*get_node(payload->id)); + host_.update_maps_node_insert(payload->id, payload->name, payload->type, collect_outgoing_edge_keys(from_idx_, payload->id)); } host_.on_remote_node_updated(payload->id, payload->type, payload->agent_id); } @@ -458,7 +498,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) prune_tombstones(now); auto version = version_of(payload->timestamp, payload->agent_id); - if (LWW::delta_is_stale(edge_tombstones_, edges_, edge_key(payload->from, payload->to, payload->type), version)) { + if (LWW::delta_is_stale(edge_tombstones_, edges_, edge_key_view(payload->from, payload->to, payload->type), version)) { return; } if (!nodes_.contains(payload->from) || !nodes_.contains(payload->to)) { @@ -472,7 +512,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) if (auto it = edges_.find(key); it != edges_.end()) { deleted_edge = LWW::to_user_edge(it->second); host_.update_maps_edge_delete(payload->from, payload->to, payload->type); - idx_erase(key); + LWW::edge_index_erase(from_idx_, to_idx_, type_idx_, it->second); edges_.erase(it); } store_edge_tombstone(payload->from, payload->to, payload->type, version, now); @@ -483,8 +523,10 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_delta upsert"); EdgeState state = LWW::to_edge_state(*payload); - edges_[key] = std::move(state); - idx_insert(key); + auto [it, inserted] = edges_.insert_or_assign(key, std::move(state)); + if (inserted) { + LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, it->second); + } edge_tombstones_.erase(key); host_.update_maps_edge_insert(payload->from, payload->to, payload->type); } @@ -553,11 +595,11 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat std::vector attrs; uint32_t agent_id{0}; }; - std::map changes; + std::unordered_map changes; { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); for (const auto& item : payload->vec) { - auto it = edges_.find(edge_key(item.from, item.to, item.type)); + auto it = edges_.find(edge_key_view(item.from, item.to, item.type)); if (it == edges_.end()) { continue; } @@ -580,7 +622,7 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat { CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch emit"); for (const auto& [key, change] : changes) { - host_.on_remote_edge_attrs_updated(std::get<0>(key), std::get<1>(key), std::get<2>(key), change.attrs, change.agent_id); + host_.on_remote_edge_attrs_updated(key.from, key.to, key.type, change.attrs, change.agent_id); } } } @@ -638,7 +680,7 @@ std::optional LWWSyncEngine::node_tombstone(uint64_t i std::optional LWWSyncEngine::edge_tombstone(uint64_t from, uint64_t to, const std::string& type) const { - if (auto it = edge_tombstones_.find(edge_key(from, to, type)); it != edge_tombstones_.end()) { + if (auto it = edge_tombstones_.find(edge_key_view(from, to, type)); it != edge_tombstones_.end()) { return it->second; } return {}; diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index a1bef738..d3760f5e 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -671,16 +671,63 @@ namespace DSR std::unordered_map, hash_tuple>> edgeType; // collection with all edge types. std::unordered_map> nodeType; // collection with all node types. - void update_maps_node_delete(uint64_t id, const std::optional& n); - void update_maps_node_insert(uint64_t id, const CRDTNode &n); + template + void update_maps_node_delete_impl(uint64_t id, std::optional type, const T& outgoing_edges) { + std::unique_lock lck(_mutex_cache_maps); + if (id_map.contains(id)) + { + name_map.erase(id_map.at(id)); + id_map.erase(id); + } + deleted.insert(id); + to_edges.erase(id); + + if (type.has_value()) + { + if (nodeType.contains(std::string{*type})) { + nodeType.at(std::string{*type}).erase(id); + if (nodeType.at(std::string{*type}).empty()) nodeType.erase(std::string{*type}); + } + for (const auto& [to, edge_type] : outgoing_edges) { + if (const auto tuple = std::pair{id, to}; edges.contains(tuple)) { + edges.at(tuple).erase(edge_type); + if (edges.at(tuple).empty()) edges.erase(tuple); + } + if (edgeType.contains(edge_type)) { + edgeType.at(edge_type).erase({id, to}); + if (edgeType.at(edge_type).empty()) edgeType.erase(edge_type); + } + if (to_edges.contains(to)) { + to_edges.at(to).erase({id, edge_type}); + if (to_edges.at(to).empty()) to_edges.erase(to); + } + } + } + } + + template + void update_maps_node_insert_impl(uint64_t id, std::string name, const std::string& type, const T& outgoing_edges) { + std::unique_lock lck(_mutex_cache_maps); + + name_map[name] = id; + id_map[id] = std::move(name); + nodeType[type].emplace(id); + for (const auto& [to, edge_type] : outgoing_edges) + { + edges[{id, to}].insert(edge_type); + edgeType[edge_type].insert({id, to}); + to_edges[to].insert({id, edge_type}); + } + } void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key = "") override; void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key) override; uint32_t local_agent_id() const override { return agent_id; } SyncMode local_sync_mode() const override { return sync_mode; } bool is_copy_graph() const override { return copy; } - void update_maps_node_insert(const Node& node) override; - void update_maps_node_delete(uint64_t id, const std::optional& node) override; + void update_maps_node_insert(uint64_t id, std::string_view name, std::string_view type, const EdgeKeyList& outgoing_edges) override; + void update_maps_node_delete(uint64_t id, std::optional type, const EdgeKeyList& outgoing_edges) override; + GraphSettings::LOGLEVEL get_log_level() const override { return log_level; } bool is_attribute_ignored(const std::string& name) const override; diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index bcce62bc..d9939fa8 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -52,6 +52,7 @@ class CRDTSyncEngine final : public SyncEngine private: const CRDTNode* get_node_ptr(uint64_t id) const; std::optional get_crdt_node(uint64_t id) const; + const CRDTEdge* get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const; std::optional get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const; std::tuple> insert_node_raw(CRDTNode&& node); diff --git a/api/include/dsr/api/dsr_graph_settings.h b/api/include/dsr/api/dsr_graph_settings.h index 474a70f2..827afe1f 100644 --- a/api/include/dsr/api/dsr_graph_settings.h +++ b/api/include/dsr/api/dsr_graph_settings.h @@ -1,21 +1,12 @@ #pragma once +#include "dsr/core/types/internal_types.h" #include #include #include namespace DSR { -enum struct SyncMode : uint8_t { - CRDT = 0, - LWW = 1, -}; - -constexpr uint8_t sync_mode_wire_value(SyncMode mode) noexcept -{ - return static_cast(mode); -} - struct GraphSettings { uint32_t agent_id {0}; int theradpool_threads {5}; diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index fcee3908..5ab6b860 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -62,6 +62,8 @@ class LWWSyncEngine final : public SyncEngine using NodeState = LWW::NodeState; using EdgeState = LWW::EdgeState; using EdgeKey = LWW::EdgeKey; + using EdgeKeyHash = LWW::EdgeKeyHash; + using EdgeKeyEqual = LWW::EdgeKeyEqual; using FromIndex = LWW::FromIndex; using ToIndex = LWW::ToIndex; using TypeIndex = LWW::TypeIndex; @@ -71,22 +73,20 @@ class LWWSyncEngine final : public SyncEngine uint64_t current_time_ms() const; uint64_t next_timestamp(); void prune_tombstones(uint64_t now); + void maybe_prune_tombstones(uint64_t now); void store_node_tombstone(uint64_t id, Version version, uint64_t now); void store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now); void erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges = nullptr); - // Secondary indices — maintained in sync with edges_ for O(degree) lookup. - void idx_insert(const EdgeKey& key); - void idx_erase(const EdgeKey& key); - SyncEngineHost& host_; uint64_t tombstone_window_ms_; uint64_t logical_clock_ms_{0}; + uint64_t last_prune_ms_{0}; std::unordered_map nodes_; - std::unordered_map edges_; + std::unordered_map edges_; std::unordered_map node_tombstones_; - std::unordered_map edge_tombstones_; + std::unordered_map edge_tombstones_; FromIndex from_idx_; ToIndex to_idx_; diff --git a/api/include/dsr/api/dsr_sync_engine.h b/api/include/dsr/api/dsr_sync_engine.h index 470c8805..8ab8f459 100644 --- a/api/include/dsr/api/dsr_sync_engine.h +++ b/api/include/dsr/api/dsr_sync_engine.h @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -59,14 +60,16 @@ struct EdgeMutationEffect class SyncEngineHost { public: + using EdgeKeyList = std::vector>; + virtual ~SyncEngineHost() = default; virtual uint32_t local_agent_id() const = 0; virtual SyncMode local_sync_mode() const = 0; virtual bool is_copy_graph() const = 0; - virtual void update_maps_node_insert(const Node& node) = 0; - virtual void update_maps_node_delete(uint64_t id, const std::optional& node) = 0; + virtual void update_maps_node_insert(uint64_t id, std::string_view name, std::string_view type, const EdgeKeyList& outgoing_edges) = 0; + virtual void update_maps_node_delete(uint64_t id, std::optional type, const EdgeKeyList& outgoing_edges) = 0; virtual void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string& type) = 0; virtual void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string& type) = 0; diff --git a/core/include/dsr/core/types/internal_types.h b/core/include/dsr/core/types/internal_types.h index 00b4ab35..db919fab 100644 --- a/core/include/dsr/core/types/internal_types.h +++ b/core/include/dsr/core/types/internal_types.h @@ -8,6 +8,16 @@ namespace DSR { + enum struct SyncMode : uint8_t { + CRDT = 0, + LWW = 1, + }; + + constexpr uint8_t sync_mode_wire_value(SyncMode mode) noexcept + { + return static_cast(mode); + } + inline constexpr uint32_t DSR_PROTOCOL_VERSION = 1; // ---- GraphRequest -------------------------------------------------------- diff --git a/core/include/dsr/core/types/lww_index.h b/core/include/dsr/core/types/lww_index.h index c9febcfc..35eb9d92 100644 --- a/core/include/dsr/core/types/lww_index.h +++ b/core/include/dsr/core/types/lww_index.h @@ -7,42 +7,41 @@ namespace DSR::LWW { -using EdgeSet = std::unordered_set; -using FromIndex = std::unordered_map; -using ToIndex = std::unordered_map; -using TypeIndex = std::unordered_map; +using EdgePtrSet = std::unordered_set; +using FromIndex = std::unordered_map; +using ToIndex = std::unordered_map; +using TypeIndex = std::unordered_map; -inline void edge_index_insert(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeKey& key) +inline void edge_index_insert(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeState& edge) { - from_idx[std::get<0>(key)].insert(key); - to_idx[std::get<1>(key)].insert(key); - type_idx[std::get<2>(key)].insert(key); + from_idx[edge.from].insert(&edge); + to_idx[edge.to].insert(&edge); + type_idx[edge.type].insert(&edge); } -inline void edge_index_erase(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeKey& key) +inline void edge_index_erase(FromIndex& from_idx, ToIndex& to_idx, TypeIndex& type_idx, const EdgeState& edge) { - if (auto it = from_idx.find(std::get<0>(key)); it != from_idx.end()) { - it->second.erase(key); + if (auto it = from_idx.find(edge.from); it != from_idx.end()) { + it->second.erase(&edge); if (it->second.empty()) { from_idx.erase(it); } } - if (auto it = to_idx.find(std::get<1>(key)); it != to_idx.end()) { - it->second.erase(key); + if (auto it = to_idx.find(edge.to); it != to_idx.end()) { + it->second.erase(&edge); if (it->second.empty()) { to_idx.erase(it); } } - if (auto it = type_idx.find(std::get<2>(key)); it != type_idx.end()) { - it->second.erase(key); + if (auto it = type_idx.find(edge.type); it != type_idx.end()) { + it->second.erase(&edge); if (it->second.empty()) { type_idx.erase(it); } } } -template -Node to_user_node(const NodeState& state, const EdgeMap& edges, const FromIndex& from_idx) +inline Node to_user_node(const NodeState& state, const FromIndex& from_idx) { Node out(state.agent_id, state.type); out.id(state.id); @@ -56,52 +55,47 @@ Node to_user_node(const NodeState& state, const EdgeMap& edges, const FromIndex& return out; } auto& fano = out.fano(); - for (const auto& key : fit->second) { - if (auto eit = edges.find(key); eit != edges.end()) { - fano.emplace(std::pair{eit->second.to, eit->second.type}, to_user_edge(eit->second)); - } + for (const auto* edge : fit->second) { + fano.emplace(std::pair{edge->to, edge->type}, to_user_edge(*edge)); } return out; } -template -bool for_each_edge_from(const EdgeMap& edges, const FromIndex& from_idx, uint64_t from, Visitor&& visitor) +template +bool for_each_edge_from(const FromIndex& from_idx, uint64_t from, Visitor&& visitor) { auto it = from_idx.find(from); if (it == from_idx.end()) { return false; } - for (const auto& key : it->second) { - const auto& edge = edges.at(key); - visitor(edge.to, edge.type, to_user_edge(edge)); + for (const auto* edge : it->second) { + visitor(edge->to, edge->type, to_user_edge(*edge)); } return true; } -template -bool for_each_edge_to(const EdgeMap& edges, const ToIndex& to_idx, uint64_t to, Visitor&& visitor) +template +bool for_each_edge_to(const ToIndex& to_idx, uint64_t to, Visitor&& visitor) { auto it = to_idx.find(to); if (it == to_idx.end()) { return false; } - for (const auto& key : it->second) { - const auto& edge = edges.at(key); - visitor(edge.from, edge.type, to_user_edge(edge)); + for (const auto* edge : it->second) { + visitor(edge->from, edge->type, to_user_edge(*edge)); } return true; } -template -void for_each_edge_of_type(const EdgeMap& edges, const TypeIndex& type_idx, const std::string& type, Visitor&& visitor) +template +void for_each_edge_of_type(const TypeIndex& type_idx, const std::string& type, Visitor&& visitor) { auto it = type_idx.find(type); if (it == type_idx.end()) { return; } - for (const auto& key : it->second) { - const auto& edge = edges.at(key); - visitor(edge.from, edge.to, to_user_edge(edge)); + for (const auto* edge : it->second) { + visitor(edge->from, edge->to, to_user_edge(*edge)); } } diff --git a/core/include/dsr/core/types/lww_types.h b/core/include/dsr/core/types/lww_types.h index 20f207d4..3b6dd08b 100644 --- a/core/include/dsr/core/types/lww_types.h +++ b/core/include/dsr/core/types/lww_types.h @@ -4,9 +4,12 @@ #include "dsr/core/utils.h" #include +#include #include #include +#include #include +#include namespace DSR::LWW { @@ -50,7 +53,68 @@ struct EdgeState std::map attrs; }; -using EdgeKey = std::tuple; +struct EdgeKeyView +{ + uint64_t from{}; + uint64_t to{}; + std::string_view type; +}; + +struct EdgeKey +{ + uint64_t from{}; + uint64_t to{}; + std::string type; + + auto tie() const { return std::tie(from, to, type); } +}; + +inline bool operator==(const EdgeKey& lhs, const EdgeKey& rhs) +{ + return lhs.from == rhs.from && lhs.to == rhs.to && lhs.type == rhs.type; +} + +inline bool operator==(const EdgeKey& lhs, EdgeKeyView rhs) +{ + return lhs.from == rhs.from && lhs.to == rhs.to && lhs.type == rhs.type; +} + +inline bool operator==(EdgeKeyView lhs, const EdgeKey& rhs) +{ + return rhs == lhs; +} + +inline bool operator<(const EdgeKey& lhs, const EdgeKey& rhs) +{ + return lhs.tie() < rhs.tie(); +} + +struct EdgeKeyHash +{ + using is_transparent = void; + + size_t operator()(const EdgeKey& key) const noexcept + { + return (*this)(EdgeKeyView{key.from, key.to, key.type}); + } + + size_t operator()(EdgeKeyView key) const noexcept + { + size_t seed = std::hash{}(key.from); + seed ^= std::hash{}(key.to) + 0x9e3779b97f4a7c15ULL + (seed << 6) + (seed >> 2); + seed ^= std::hash{}(key.type) + 0x9e3779b97f4a7c15ULL + (seed << 6) + (seed >> 2); + return seed; + } +}; + +struct EdgeKeyEqual +{ + using is_transparent = void; + + bool operator()(const EdgeKey& lhs, const EdgeKey& rhs) const noexcept { return lhs == rhs; } + bool operator()(const EdgeKey& lhs, EdgeKeyView rhs) const noexcept { return lhs == rhs; } + bool operator()(EdgeKeyView lhs, const EdgeKey& rhs) const noexcept { return rhs == lhs; } +}; inline bool is_newer(const Version& lhs, const Version& rhs) { @@ -62,9 +126,14 @@ inline Version version_of(uint64_t timestamp, uint32_t agent_id) return Version{timestamp, agent_id}; } -inline EdgeKey edge_key(uint64_t from, uint64_t to, const std::string& type) +inline EdgeKey edge_key(uint64_t from, uint64_t to, std::string type) +{ + return EdgeKey{from, to, std::move(type)}; +} + +inline EdgeKeyView edge_key_view(uint64_t from, uint64_t to, std::string_view type) { - return EdgeKey{from, to, type}; + return EdgeKeyView{from, to, type}; } } // namespace DSR::LWW diff --git a/core/include/dsr/core/types/user_types.h b/core/include/dsr/core/types/user_types.h index 5324ae80..3d999d56 100644 --- a/core/include/dsr/core/types/user_types.h +++ b/core/include/dsr/core/types/user_types.h @@ -32,7 +32,6 @@ namespace DSR { Edge() = default; ~Edge() = default; - [[deprecated("Use Edge::create(...)")]] Edge(uint64_t to, uint64_t from, std::string type, uint32_t agent_id) : m_to(to), m_from(from), @@ -45,7 +44,6 @@ namespace DSR { } } - [[deprecated("Use Edge::create(...)")]] Edge(uint64_t to, uint64_t from, std::string type, std::map attrs, uint32_t agent_id) @@ -171,7 +169,6 @@ namespace DSR { Node() = default; ~Node() = default; - [[deprecated("Use Node::create(...)")]] Node(uint64_t agent_id, std::string type) : m_id(0), m_type(std::move(type)), @@ -184,7 +181,6 @@ namespace DSR { } } - [[deprecated("Use Node::create(...)")]] Node(std::string type, uint32_t agent_id, std::map attrs, std::map, Edge > fano) From 81144103c3d76fad1e53465109c99234c0150b7d Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 24 Apr 2026 13:52:48 +0200 Subject: [PATCH 25/38] refactor: fix in lww backend --- api/dsr_lww_sync_engine.cpp | 42 ++++++++++++++++++--------------- tests/graph/node_operations.cpp | 18 ++++++++++++++ 2 files changed, 41 insertions(+), 19 deletions(-) diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 3d931501..058e4262 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -118,7 +118,7 @@ SyncBackendInfo LWWSyncEngine::backend_info() const std::unique_ptr LWWSyncEngine::clone(SyncEngineHost& host) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::clone"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::clone"); return std::make_unique(host, *this); } @@ -144,7 +144,7 @@ uint64_t LWWSyncEngine::next_timestamp() void LWWSyncEngine::prune_tombstones(uint64_t now) { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::prune_tombstones"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::prune_tombstones"); std::erase_if(node_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); std::erase_if(edge_tombstones_, [now](const auto& item) { return item.second.expires_at_ms <= now; }); } @@ -161,7 +161,7 @@ void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std:: void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::erase_related_edges"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::erase_related_edges"); std::unordered_set to_erase; if (auto it = from_idx_.find(node_id); it != from_idx_.end()) { for (const auto* edge : it->second) { @@ -188,7 +188,7 @@ void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint6 std::optional LWWSyncEngine::get_node(uint64_t id) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_node"); + CORTEX_PROFILE_HOT_N("LWWSyncEngine::get_node"); auto it = nodes_.find(id); if (it == nodes_.end()) return {}; return LWW::to_user_node(it->second, from_idx_); @@ -196,7 +196,7 @@ std::optional LWWSyncEngine::get_node(uint64_t id) const std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::get_edge"); + CORTEX_PROFILE_HOT_N("LWWSyncEngine::get_edge"); if (auto it = edges_.find(edge_key_view(from, to, type)); it != edges_.end()) { return LWW::to_user_edge(it->second); } @@ -205,6 +205,7 @@ std::optional LWWSyncEngine::get_edge(uint64_t from, uint64_t to, const st bool LWWSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("LWWSyncEngine::with_node_attrs"); if (const auto* node = get_node_ptr(id); node != nullptr) { LWWNodeAttrsView attrs(node->attrs); visitor(attrs); @@ -215,6 +216,7 @@ bool LWWSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor bool LWWSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("LWWSyncEngine::with_node_view"); if (const auto* node = get_node_ptr(id); node != nullptr) { LWWNodeView view(*node); visitor(view); @@ -225,7 +227,7 @@ bool LWWSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_from"); + CORTEX_PROFILE_HOT_N("LWWSyncEngine::for_each_edge_from"); if (!nodes_.contains(from)) { return false; } @@ -237,13 +239,13 @@ bool LWWSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& bool LWWSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_to"); + CORTEX_PROFILE_HOT_N("LWWSyncEngine::for_each_edge_to"); return LWW::for_each_edge_to(to_idx_, to, visitor); } void LWWSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::for_each_edge_of_type"); + CORTEX_PROFILE_HOT_N("LWWSyncEngine::for_each_edge_of_type"); LWW::for_each_edge_of_type(type_idx_, type, visitor); } @@ -254,7 +256,7 @@ size_t LWWSyncEngine::size() const std::map LWWSyncEngine::snapshot() const { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::snapshot"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::snapshot"); std::map out; for (const auto& [id, st] : nodes_) { out.emplace(id, LWW::to_user_node(st, from_idx_)); @@ -278,6 +280,7 @@ NodeMutationEffect LWWSyncEngine::insert_node_local(Node&& node) } NodeState state = LWW::to_node_state(node, version, host_.local_agent_id()); + effect.changed_attributes.reserve(node.attrs().size()); for (const auto& [name, _] : node.attrs()) { effect.changed_attributes.emplace_back(name); } @@ -339,6 +342,7 @@ NodeMutationEffect LWWSyncEngine::delete_node_local(uint64_t id) } auto version = version_of(now, host_.local_agent_id()); + //TODO: do we NEED the complete node? I think we might send it in a signal? std::optional deleted_node = LWW::to_user_node(it->second, from_idx_); auto outgoing_edges = collect_outgoing_edge_keys(from_idx_, id); effect.deleted_node = deleted_node; @@ -456,7 +460,7 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) } if (payload->deleted) { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_delta delete"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_node_delta delete"); std::optional deleted_node; std::vector deleted_edges; if (auto it = nodes_.find(payload->id); it != nodes_.end()) { @@ -474,7 +478,7 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) NodeState state = LWW::to_node_state(*payload); { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_delta upsert"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_node_delta upsert"); if (const auto* current = get_node_ptr(payload->id); current != nullptr) { host_.update_maps_node_delete(payload->id, current->type, collect_outgoing_edge_keys(from_idx_, payload->id)); } @@ -507,7 +511,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) auto key = edge_key(payload->from, payload->to, payload->type); if (payload->deleted) { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_delta delete"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_delta delete"); std::optional deleted_edge; if (auto it = edges_.find(key); it != edges_.end()) { deleted_edge = LWW::to_user_edge(it->second); @@ -521,7 +525,7 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) } { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_delta upsert"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_delta upsert"); EdgeState state = LWW::to_edge_state(*payload); auto [it, inserted] = edges_.insert_or_assign(key, std::move(state)); if (inserted) { @@ -549,7 +553,7 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat }; std::unordered_map changes; { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_attr_batch merge"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_node_attr_batch merge"); for (const auto& item : payload->vec) { auto it = nodes_.find(item.node_id); if (it == nodes_.end()) { @@ -575,7 +579,7 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat } { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_node_attr_batch emit"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_node_attr_batch emit"); for (const auto& [id, change] : changes) { host_.on_remote_node_attrs_updated(id, change.type, change.attrs, change.agent_id); } @@ -597,7 +601,7 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat }; std::unordered_map changes; { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); for (const auto& item : payload->vec) { auto it = edges_.find(edge_key_view(item.from, item.to, item.type)); if (it == edges_.end()) { @@ -620,7 +624,7 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat } { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::apply_remote_edge_attr_batch emit"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_attr_batch emit"); for (const auto& [key, change] : changes) { host_.on_remote_edge_attrs_updated(key.from, key.to, key.type, change.attrs, change.agent_id); } @@ -637,13 +641,13 @@ void LWWSyncEngine::import_full_graph(FullGraphMessage&& full_graph) tombstone_window_ms_ = payload->tombstone_window_ms == 0 ? tombstone_window_ms_ : payload->tombstone_window_ms; { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::import_full_graph nodes"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::import_full_graph nodes"); for (const auto& node : payload->nodes) { apply_remote_node_delta(NodeDeltaMessage{node}); } } { - CORTEX_PROFILE_ZONE_N("LWWSyncEngine::import_full_graph edges"); + CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::import_full_graph edges"); for (const auto& edge : payload->edges) { apply_remote_edge_delta(EdgeDeltaMessage{edge}); } diff --git a/tests/graph/node_operations.cpp b/tests/graph/node_operations.cpp index 43023a38..cc5c727f 100644 --- a/tests/graph/node_operations.cpp +++ b/tests/graph/node_operations.cpp @@ -68,6 +68,24 @@ TEST_CASE("Graph node operations", "[NODE]") { REQUIRE_FALSE(G.remove_attrib_local(n_id.value(), "level")); } + SECTION("Update existing node repeatedly") { + auto node_name = random_string(); + auto n = Node::create(node_name); + std::optional r = G.insert_node(n); + REQUIRE(r.has_value()); + + for (int value : {1, 2, 3}) { + auto node = G.get_node(*r); + REQUIRE(node.has_value()); + G.add_or_modify_attrib_local(*node, value); + REQUIRE(G.update_node(*node)); + } + + auto updated = G.get_node(*r); + REQUIRE(updated.has_value()); + REQUIRE(G.get_attrib_by_name(*updated) == 3); + } + SECTION("Can't update an existent node with different id") { auto node_name = random_string(); auto n = Node::create(node_name); From 177d0b1484c4a44f9e3ab60472802f7d5c1d2cdd Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 24 Apr 2026 13:53:14 +0200 Subject: [PATCH 26/38] refactor: tracing --- PROFILING.md | 331 +++++++++++++++++++--- api/dsr_api.cpp | 76 ++--- api/dsr_crdt_sync_engine.cpp | 58 ++-- api/include/dsr/api/dsr_api.h | 4 + benchmarks/CMakeLists.txt | 1 + benchmarks/benchmark_main.cpp | 15 +- benchmarks/fixtures/multi_agent_fixture.h | 3 + benchmarks/flamegraph.sh | 34 ++- benchmarks/perfetto.sh | 192 +++++++++++++ core/include/dsr/core/profiling.h | 165 +++++++++-- core/profiling.cpp | 112 +++++++- 11 files changed, 857 insertions(+), 134 deletions(-) create mode 100644 benchmarks/perfetto.sh diff --git a/PROFILING.md b/PROFILING.md index ac249fda..06745de1 100644 --- a/PROFILING.md +++ b/PROFILING.md @@ -1,10 +1,18 @@ -# Profiling Backends +# Profiling -The repository supports multiple profiling backends through CMake. +The repository supports multiple profiling backends through CMake and uses a +shared instrumentation surface across them. + +The important design point is: + +- the same `CORTEX_PROFILE_*` call sites are used for both Perfetto and Tracy +- backend choice changes collection and visualization, not where zones exist +- profiling detail is now an explicit runtime level instead of an implicit + “everything is always on” model ## Backend Selection -Use: +Use one of: ```bash -DCORTEX_PROFILING_BACKEND=NONE @@ -18,9 +26,10 @@ No profiling backend is enabled. ### `TRACY` -Uses the interactive Tracy client/profiler flow. +Uses the interactive Tracy workflow. -If `CORTEX_ENABLE_TRACY` is not explicitly configured, the build falls back to the `DEFAULT` Tracy preset. +If `CORTEX_ENABLE_TRACY` is not explicitly configured, the build falls back to +the `DEFAULT` Tracy preset. What you need: @@ -32,7 +41,8 @@ Important: - Tracy is mainly an interactive workflow - traces are not written automatically to disk by the client -- if you want a saved trace, connect with the profiler and save the session from the UI +- if you want a saved trace, connect with the profiler and save the session + from the UI Typical usage: @@ -45,59 +55,221 @@ cmake --build build --target tests ./build/tests/tests "[SYNCHRONIZATION][GRAPH]" ``` -Tracy options are OFF, ON, DEFAULT, MEDIUM, EXTRA, WSL, WSL_EXTRA +Tracy presets are: + +- `OFF` +- `ON` +- `DEFAULT` +- `MEDIUM` +- `EXTRA` +- `WSL` +- `WSL_EXTRA` ### `PERFETTO` -Uses Perfetto's in-process backend and writes an offline trace file automatically at process exit. +Uses Perfetto and writes an offline trace file automatically at process exit. What you need: - an instrumented build with `-DCORTEX_PROFILING_BACKEND=PERFETTO` - a generated `.pftrace` file -- either the web UI at `https://ui.perfetto.dev/` or another Perfetto-compatible viewer +- either the web UI at `https://ui.perfetto.dev/` or another + Perfetto-compatible viewer + +## Shared Instrumentation Model + +Both Tracy and Perfetto use the same instrumentation macros from +[core/include/dsr/core/profiling.h](/abs/path/C:/Users/juanc/Projects/cortex/core/include/dsr/core/profiling.h). + +The main macros are: + +- `CORTEX_PROFILE_ZONE()` +- `CORTEX_PROFILE_ZONE_N("name")` +- `CORTEX_PROFILE_ZONE_CS("name")` + +Those remain the default function-level surface. + +There are also level-specific variants: + +- `CORTEX_PROFILE_MIN_N("name")` +- `CORTEX_PROFILE_DETAIL_N("name")` +- `CORTEX_PROFILE_HOT_N("name")` +- `CORTEX_PROFILE_MIN_CS("name")` +- `CORTEX_PROFILE_DETAIL_CS("name")` +- `CORTEX_PROFILE_HOT_CS("name")` + +The intent is: + +- `min`: coarse lifecycle and benchmark-structure zones +- `default`: normal function-level zones +- `detail`: inner merge/apply/helper phases +- `hot`: very frequent per-call zones in hot paths -#### Callstack mode (`CORTEX_PERFETTO_MODE`) +This lets long runs stay readable while still allowing focused deep traces. + +## Profiling Detail Levels + +Profiling detail is controlled at runtime, not configure time. + +Accepted values: + +- `off` +- `min` +- `default` +- `detail` +- `hot` + +You can set it with either environment variable: + +```bash +export CORTEX_PROFILE_DETAIL=min +export BENCH_PROFILE_DETAIL=detail +``` + +For `dsr_benchmarks`, `BENCH_PROFILE_DETAIL` is the most convenient form. + +Examples: + +```bash +BENCH_PROFILE_DETAIL=min ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +BENCH_PROFILE_DETAIL=detail ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +BENCH_PROFILE_DETAIL=hot ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +``` + +Recommended usage: + +- `min` for long benchmark suites where you care about setup, graph bootstrap, + thread creation, and major phase boundaries +- `default` for ordinary development profiling +- `detail` for focused synchronization / merge / apply analysis +- `hot` only for short targeted runs, because it can generate a very large + number of events + +## Perfetto Callstack Mode (`CORTEX_PERFETTO_MODE`) Three modes are available, selected at configure time: | Mode | CMake flag | What you get | |------|-----------|--------------| | `DEFAULT` | _(omit)_ | Zone events only, no callstacks | -| `STACKFRAME` | `-DCORTEX_PERFETTO_MODE=STACKFRAME` | Callstacks attached to `CORTEX_PROFILE_ZONE_CS` zones via `callstack_iid` + `InternedData` (native flamechart in the UI) | -| `LINUX_PERF` | `-DCORTEX_PERFETTO_MODE=LINUX_PERF` | Kernel-driven CPU sampling correlated to zone events by timestamp | +| `STACKFRAME` | `-DCORTEX_PERFETTO_MODE=STACKFRAME` | Callstacks attached to `CORTEX_PROFILE_ZONE_CS` zones | +| `LINUX_PERF` | `-DCORTEX_PERFETTO_MODE=LINUX_PERF` | Kernel CPU sampling correlated with zone events | + +### `STACKFRAME` + +Captures a callstack at every `CORTEX_PROFILE_ZONE_CS` call site using +`backtrace()`, resolves symbols with `dladdr` + demangling, and emits proper +Perfetto `Callstack` / `Frame` / `InternedString` data. + +Important: + +- `STACKFRAME` is only useful on `_CS` zones +- if most important coarse zones are plain `_N` zones, you will not get much + extra value from `STACKFRAME` +- if work happens inside lambdas or unnamed helpers, wrap those bodies with + explicit named zones if you want readable callsites + +`-fno-omit-frame-pointer` is added automatically. + +### `LINUX_PERF` + +Adds a `linux.perf` data source alongside track events. The kernel interrupts +the process at 1 kHz and records sampled CPU stacks independently of +instrumentation. -**STACKFRAME** captures a callstack at every `CORTEX_PROFILE_ZONE_CS` call site using `backtrace()`, resolves symbols with `dladdr` + demangling, and emits them as proper `Callstack` / `Frame` / `InternedString` proto entries. The Perfetto UI renders these as an expandable flamechart on the event. `-fno-omit-frame-pointer` is added automatically. +This is useful for: -**LINUX_PERF** adds a `linux.perf` data source alongside track events. The kernel interrupts the process at 1 kHz and records the CPU stack independently of instrumentation — useful for finding hotspots in uninstrumented code. `-fno-omit-frame-pointer` is added automatically. +- hotspots in uninstrumented code +- inner work that would be too expensive to zone explicitly +- correlating coarse zones with sampled stacks + +`-fno-omit-frame-pointer` is added automatically. Requirements for `LINUX_PERF`: -- `traced`, `traced_probes`, and `traced_perf` must be running (all three) +- `traced`, `traced_probes`, and `traced_perf` must be running - `perf_event_paranoid <= 0`: ```bash sudo sysctl -w kernel.perf_event_paranoid=0 ``` -- The `tracebox` binary (not its symlink) needs `CAP_SYS_PTRACE` for DWARF stack unwinding. `readlink -f` may not resolve the real path — locate it manually if needed: +- the real `tracebox` binary needs `CAP_PERFMON` and often `CAP_SYS_PTRACE`: ```bash - # find the actual binary (example path — yours may differ) - ls -la $(which tracebox) # shows where symlink points - sudo setcap cap_perfmon,cap_sys_ptrace+ep /home/jc/.local/share/perfetto/prebuilts/tracebox + ls -la $(which tracebox) + sudo setcap cap_perfmon,cap_sys_ptrace+ep /path/to/real/tracebox ``` -- Run `traced_perf` as root if `setcap` is not an option (root can open `/proc//mem` and connect to user-owned sockets): +- if `setcap` is not an option, run `traced_perf` as root: ```bash - tracebox traced --background # as your user - tracebox traced_probes --background # as your user - sudo tracebox traced_perf # as root + tracebox traced --background + tracebox traced_probes --background + sudo tracebox traced_perf ``` -**Important — LINUX_PERF vs DEFAULT/STACKFRAME modes:** +Important: + +- `LINUX_PERF` does not replace track events, it complements them +- zone events and sampled stacks land in the same `.pftrace` +- sampled stacks show up separately in the UI, typically under + `Process callstacks cpu-clock` + +## Perfetto Buffer Behavior + +Perfetto currently uses separate buffers for: + +- `track_event` +- `linux.perf` (when `LINUX_PERF` mode is enabled) + +Current implementation details are in +[core/profiling.cpp](/abs/path/C:/Users/juanc/Projects/cortex/core/profiling.cpp): + +- `track_event` buffer: `64 MB` +- `linux.perf` buffer: `64 MB` +- flush period: `1000 ms` +- incremental state clear period: `1000 ms` +- `track_event` incremental timestamps are disabled +- `track_event` buffer uses `DISCARD` + +That last point matters: + +- `DISCARD` preserves early setup / bootstrap zones once the event buffer fills +- later track events are dropped instead of overwriting the beginning of the + run + +This was chosen deliberately because long benchmark suites were saturating +`track_event` and hiding graph setup / agent bootstrap / subscription-thread +setup. -LINUX_PERF mode registers the process as a system-backend producer only. It does **not** write a `.pftrace` file itself — the trace is owned by `traced` and read back at process exit via the consumer API. Zone events and CPU samples land in the same file and are visible as separate track groups in the UI ("Process callstacks cpu-clock" for samples, thread rows for zones). To correlate them, expand both groups and select an area that spans both. +Tradeoff: -#### Typical usage +- `DISCARD` is better when you care about early setup visibility +- ring-buffer overwrite is better when you care about the tail of the run -DEFAULT (zone events only, no daemons needed): +For long benchmark suites, `DISCARD` is usually the better debugging default. + +## Why Perfetto and `linux.perf` Behave Differently + +It is normal for `track_event` and `linux.perf` to fail differently. + +`track_event`: + +- event-based +- records every emitted zone +- can saturate quickly if hot functions emit one zone per call + +`linux.perf`: + +- sampled +- records periodic interrupts rather than every function call +- can lose samples due to kernel ring-buffer overruns +- still often remains useful even when some samples are lost + +So these are different failure modes: + +- `track_event` overflow can hide setup or tail phases depending on fill policy +- `linux.perf` lost records show up as missing samples, not missing zones + +## Typical Usage + +### Perfetto `DEFAULT` ```bash cmake -S . -B build-perfetto \ @@ -107,7 +279,7 @@ cmake --build build-perfetto --target tests ./build-perfetto/tests/tests "[SYNCHRONIZATION][GRAPH]" ``` -STACKFRAME (callstacks on `_CS` zones, no daemons needed): +### Perfetto `STACKFRAME` ```bash cmake -S . -B build-perfetto \ @@ -118,17 +290,15 @@ cmake --build build-perfetto --target tests ./build-perfetto/tests/tests "[SYNCHRONIZATION][GRAPH]" ``` -LINUX_PERF (kernel CPU sampling correlated with zone events): +### Perfetto `LINUX_PERF` ```bash -# One-time setup: sudo sysctl -w kernel.perf_event_paranoid=0 sudo setcap cap_perfmon,cap_sys_ptrace+ep /path/to/real/tracebox -# Start daemons (traced_perf as root OR with setcap applied): tracebox traced --background tracebox traced_probes --background -tracebox traced_perf --background # or: sudo tracebox traced_perf +tracebox traced_perf --background cmake -S . -B build-pf-lp \ -DWITH_TESTS=ON \ @@ -138,6 +308,61 @@ cmake --build build-pf-lp -j$(nproc) ./build-pf-lp/bin/your_component ``` +### Tracy + +```bash +cmake -S . -B build-tracy \ + -DWITH_TESTS=ON \ + -DCORTEX_PROFILING_BACKEND=TRACY \ + -DCORTEX_ENABLE_TRACY=DEFAULT +cmake --build build-tracy --target tests +./build-tracy/tests/tests "[SYNCHRONIZATION][GRAPH]" +``` + +## Benchmark Workflow + +`dsr_benchmarks` starts profiling before `Catch::Session::run()`, so benchmark +fixture setup and graph/bootstrap phases can appear in the trace if the active +detail level includes them. + +Useful examples: + +```bash +BENCH_PROFILE_DETAIL=min ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +BENCH_PROFILE_DETAIL=default ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +BENCH_PROFILE_DETAIL=hot ./build-perfetto/benchmarks/dsr_benchmarks "[PROFILE]" +``` + +For one trace file per benchmark case, use +[benchmarks/perfetto.sh](/abs/path/C:/Users/juanc/Projects/cortex/benchmarks/perfetto.sh): + +```bash +bash benchmarks/perfetto.sh -b ./build-perfetto/benchmarks/dsr_benchmarks -p profile +bash benchmarks/perfetto.sh -b ./build-perfetto/benchmarks/dsr_benchmarks -g lww -d min "[PROFILE][LOAD]" +``` + +It mirrors the flamegraph workflow: + +- discovers matching Catch2 benchmarks first +- runs each benchmark case separately +- writes one `.pftrace` per case +- stores traces under `results/perfetto//` + +There is also a matching CMake target: + +```bash +cmake --build build-perfetto --target perfetto_traces -j1 -- BENCH_FILTER=[PROFILE] +``` + +Recommended workflow: + +1. Start with `min` for long benchmark suites. +2. Use `default` or `detail` for medium focused runs. +3. Use `hot` only on short targeted runs, ideally one benchmark or one small + benchmark group at a time. + +## Trace File Path + The trace file path can be overridden with: ```bash @@ -152,20 +377,46 @@ If not set, the default output path is: relative to the process working directory. -The generated trace file can be opened with: +## Viewing Traces + +Open the generated `.pftrace` with: - https://ui.perfetto.dev/ -- the standalone Perfetto UI / trace processor tools +- Perfetto standalone UI / trace processor tools -Recommended flow on this repository: +Recommended flow: -1. Run the instrumented binary or test. +1. Run the instrumented binary or benchmark. 2. Wait for the process to exit cleanly. 3. Open `https://ui.perfetto.dev/`. -4. Use `Open trace file` and load the `.pftrace`. +4. Load the `.pftrace`. + +## Practical Guidance + +Use Tracy when: + +- you want live interactive iteration +- you want streaming-style inspection while the process is running + +Use Perfetto when: + +- you want an artifact to inspect later +- you want timeline zones plus `linux.perf` sampled callstacks in one trace +- you want easier offline sharing / postmortem inspection + +Use `STACKFRAME` when: + +- you have deliberately marked important zones as `_CS` +- you want per-zone callstacks instead of sampled CPU stacks + +Use `LINUX_PERF` when: + +- you want coarse zones plus cheap sampled hotspots +- you care about uninstrumented code paths Notes: -- Perfetto is the better fit for offline captures that you want to inspect later. -- The trace is flushed on shutdown, so if the process is killed hard you may lose the file. -- The current instrumentation covers graph, RT, CRDT, bootstrap, and synchronization paths. +- Perfetto traces are flushed on shutdown, so hard-killing the process may lose + the trace +- current instrumentation now separates coarse lifecycle/setup visibility from + hot per-call zones through runtime detail levels diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 05e311ed..02e1f065 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -141,11 +141,11 @@ DSRGraph::DSRGraph(GraphSettings settings) : log_level(settings.log_level), engine_(make_sync_engine(*this, settings.sync_mode)) { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph"); qDebug() << "Agent name: " << QString::fromStdString(agent_name); { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph setup utils/signals"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph setup utils/signals"); utils = std::make_unique(this); if (settings.signal_mode == SignalMode::QT) { set_qt_signals(); @@ -159,13 +159,13 @@ DSRGraph::DSRGraph(GraphSettings settings) : } // RTPS Create participant auto participant_init_result = [&]() { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init participant"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph init participant"); return dsrparticipant.init(agent_id, agent_name, settings.same_host, ParticipantChangeFn(this, [&](DSR::DSRGraph *graph, eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) { - CORTEX_PROFILE_ZONE_N("DSRGraph::participant discovery callback"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::participant discovery callback"); if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT) { std::unique_lock lck(participant_set_mutex); @@ -207,7 +207,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : // RTPS Initialize publisher with general topic auto [res, pub, writer, res2, pub2, writer2, res3, pub3, writer3, res4, pub4, writer4, res5, pub5, writer5, res6, pub6, writer6] = [&]() { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph init publishers"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph init publishers"); auto [r1, p1, w1] = dsrpub_node.init(participant_handle, dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id()); auto [r2, p2, w2] = dsrpub_node_attrs.init(participant_handle, dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id()); auto [r3, p3, w3] = dsrpub_edge.init(participant_handle, dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id()); @@ -218,7 +218,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : }(); { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph register publishers"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph register publishers"); dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), {pub, writer}); dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), {pub2, writer2}); dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), {pub3, writer3}); @@ -232,7 +232,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : { try { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph load input graph"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph load input graph"); read_from_json_file(settings.input_file); qDebug() << __FUNCTION__ << "Warning, graph read from file " << QString::fromStdString(settings.input_file); } @@ -247,7 +247,7 @@ DSRGraph::DSRGraph(GraphSettings settings) : else { { - CORTEX_PROFILE_ZONE_N("DSRGraph::DSRGraph bootstrap subscriptions"); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph bootstrap subscriptions"); start_subscription_threads(); // regular subscription to deltas } auto [response, repeated] = start_fullgraph_request_thread(); // for agents that want to request the graph for other agent @@ -574,7 +574,7 @@ DSRGraph::NewMessageFn DSRGraph::make_fullgraph_request_functor(std::atomic DSRGraph::get_node(const std::string &name) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(name)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_node(name)"); std::shared_lock lock(_mutex); if (name.empty()) return {}; std::optional id = get_id_from_name(name); @@ -587,7 +587,7 @@ std::optional DSRGraph::get_node(const std::string &name) std::optional DSRGraph::get_node(uint64_t id) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_node(id)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_node(id)"); std::shared_lock lock(_mutex); return engine_->get_node(id); } @@ -615,9 +615,9 @@ std::optional DSRGraph::insert_node(No &&node) { if (effect.node_delta.has_value()) { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node publish deltas"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_node publish deltas"); publish_node_message(*effect.node_delta); - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node emit signals"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_node emit signals"); DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); for (const auto &[k, v]: node.fano()) @@ -658,9 +658,9 @@ std::optional DSRGraph::insert_node_with_id(No &&node) { if (effect.node_delta.has_value()) { - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_with_id send deltas"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_node_with_id send deltas"); publish_node_message(*effect.node_delta); - CORTEX_PROFILE_ZONE_N("DSRGraph::insert_node_with_id emit signals"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_node_with_id emit signals"); DSR_LOG_DEBUG("[INSERT_NODE_WITH_ID] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); for (const auto &[k, v]: node.fano()) @@ -679,7 +679,7 @@ template bool DSRGraph::update_node(No &&node) requires (std::is_same_v, DSR::Node>) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node"); + CORTEX_PROFILE_ZONE_N("DSRGraph::update_node"); NodeMutationEffect effect; { @@ -705,14 +705,14 @@ requires (std::is_same_v, DSR::Node>) } } if (!copy) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node send deltas"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::update_node send deltas"); if (effect.node_delta.has_value()) { publish_node_message(*effect.node_delta); } if (effect.node_attr_batch.has_value()) { publish_node_attr_batch(*effect.node_attr_batch); } - CORTEX_PROFILE_ZONE_CS("DSRGraph::update_node emit signals"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::update_node emit signals"); if (effect.node_delta.has_value() || effect.node_attr_batch.has_value()) { DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type()); emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id}); @@ -759,14 +759,14 @@ bool DSRGraph::delete_node(uint64_t id) } if (!copy) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node(id) send deltas"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::delete_node(id) send deltas"); if (effect.node_delta.has_value()) { publish_node_message(*effect.node_delta); } for (const auto &delta : effect.edge_deltas) { publish_edge_message(delta); } - CORTEX_PROFILE_ZONE_CS("DSRGraph::delete_node(id) emit signals"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::delete_node(id) emit signals"); DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id); emitter.del_node_signal(id, SignalInfo{ agent_id }); @@ -787,7 +787,7 @@ template bool DSRGraph::insert_or_assign_edge(Ed &&attrs) requires (std::is_same_v, DSR::Edge>) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge"); + CORTEX_PROFILE_ZONE_N("DSRGraph::insert_or_assign_edge"); EdgeMutationEffect effect; { @@ -801,14 +801,14 @@ requires (std::is_same_v, DSR::Edge>) } } if (!copy) { - CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge sned deltas"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_or_assign_edge send deltas"); if (effect.edge_delta.has_value()) { publish_edge_message(*effect.edge_delta); } if (effect.edge_attr_batch.has_value()) { publish_edge_attr_batch(*effect.edge_attr_batch); } - CORTEX_PROFILE_ZONE_CS("DSRGraph::insert_or_assign_edge emit signals"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::insert_or_assign_edge emit signals"); DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type()); emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id }); @@ -929,7 +929,7 @@ std::vector DSRGraph::get_nodes_by_types(const std::vector DSRGraph::get_edge(const std::string &from, const std::string &to, const std::string &key) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(from_str, to_str, key)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_edge(from_str, to_str, key)"); std::shared_lock lock(_mutex); std::optional id_from = get_id_from_name(from); std::optional id_to = get_id_from_name(to); @@ -942,14 +942,14 @@ std::optional DSRGraph::get_edge(const std::string &from, const std:: std::optional DSRGraph::get_edge(uint64_t from, uint64_t to, const std::string &key) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(from, to, key)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_edge(from, to, key)"); std::shared_lock lock(_mutex); return engine_->get_edge(from, to, key); } std::optional DSRGraph::get_edge(const Node &n, const std::string &to, const std::string &key) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(Node, to_str, key)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_edge(Node, to_str, key)"); std::optional id_to = get_id_from_name(to); if (id_to.has_value()) { @@ -961,7 +961,7 @@ std::optional DSRGraph::get_edge(const Node &n, const std::string &to, con std::optional DSRGraph::get_edge(const Node &n, uint64_t to, const std::string &key) { - CORTEX_PROFILE_ZONE_N("DSRGraph::get_edge(Node, to, key)"); + CORTEX_PROFILE_HOT_N("DSRGraph::get_edge(Node, to, key)"); auto it = n.fano().find({to, key}); if (it != n.fano().end()) return it->second; return {}; @@ -1213,20 +1213,20 @@ bool DSRGraph::empty(const uint64_t &id) std::pair DSRGraph::start_fullgraph_request_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::start_fullgraph_request_thread"); + CORTEX_PROFILE_MIN_N("DSRGraph::start_fullgraph_request_thread"); return fullgraph_request_thread(); } void DSRGraph::start_fullgraph_server_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::start_fullgraph_server_thread"); + CORTEX_PROFILE_MIN_N("DSRGraph::start_fullgraph_server_thread"); auto fullgraph_thread = std::thread(&DSRGraph::fullgraph_server_thread, this); if (fullgraph_thread.joinable()) fullgraph_thread.join(); } void DSRGraph::start_subscription_threads() { - CORTEX_PROFILE_ZONE_N("DSRGraph::start_subscription_threads"); + CORTEX_PROFILE_MIN_N("DSRGraph::start_subscription_threads"); auto delta_node_thread = std::thread(&DSRGraph::node_subscription_thread, this); auto delta_edge_thread = std::thread(&DSRGraph::edge_subscription_thread, this); auto delta_node_attrs_thread = std::thread(&DSRGraph::node_attrs_subscription_thread, this); @@ -1264,7 +1264,7 @@ void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::f void DSRGraph::node_subscription_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread setup"); + CORTEX_PROFILE_MIN_N("DSRGraph::node_subscription_thread setup"); dsrpub_call_node = make_node_subscription_functor(); auto [res, sub, reader] = dsrsub_node.init(dsrparticipant.getParticipant(), dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), {sub, reader}); @@ -1272,7 +1272,7 @@ void DSRGraph::node_subscription_thread() void DSRGraph::edge_subscription_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread setup"); + CORTEX_PROFILE_MIN_N("DSRGraph::edge_subscription_thread setup"); dsrpub_call_edge = make_edge_subscription_functor(); auto [res, sub, reader] = dsrsub_edge.init(dsrparticipant.getParticipant(), dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge, mtx_entity_creation); dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), {sub, reader}); @@ -1281,7 +1281,7 @@ void DSRGraph::edge_subscription_thread() void DSRGraph::edge_attrs_subscription_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread setup"); + CORTEX_PROFILE_MIN_N("DSRGraph::edge_attrs_subscription_thread setup"); dsrpub_call_edge_attrs = make_edge_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_edge_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge_attrs, mtx_entity_creation); @@ -1292,7 +1292,7 @@ void DSRGraph::edge_attrs_subscription_thread() void DSRGraph::node_attrs_subscription_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread setup"); + CORTEX_PROFILE_MIN_N("DSRGraph::node_attrs_subscription_thread setup"); dsrpub_call_node_attrs = make_node_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_node_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node_attrs, mtx_entity_creation); @@ -1302,7 +1302,7 @@ void DSRGraph::node_attrs_subscription_thread() void DSRGraph::fullgraph_server_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread setup"); + CORTEX_PROFILE_MIN_N("DSRGraph::fullgraph_server_thread setup"); auto lambda_graph_request = [&](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_server"); return true; }(); @@ -1366,7 +1366,7 @@ void DSRGraph::fullgraph_server_thread() std::pair DSRGraph::fullgraph_request_thread() { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread"); + CORTEX_PROFILE_MIN_N("DSRGraph::fullgraph_request_thread"); std::atomic sync{false}; std::atomic repeated{false}; dsrpub_request_answer_call = make_fullgraph_request_functor(sync, repeated); @@ -1375,7 +1375,7 @@ std::pair DSRGraph::fullgraph_request_thread() dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), {sub, reader}); { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread initial wait"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread initial wait"); std::this_thread::sleep_for(300ms); // NEEDED ? } @@ -1387,7 +1387,7 @@ std::pair DSRGraph::fullgraph_request_thread() gr.protocol_version = DSR::DSR_PROTOCOL_VERSION; gr.sync_mode = sync_mode_wire_value(sync_mode); { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread send request"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread send request"); dsrpub_graph_request.write(gr); } @@ -1395,7 +1395,7 @@ std::pair DSRGraph::fullgraph_request_thread() bool timeout = false; std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); while (!sync and !timeout and !repeated) { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread wait loop"); + CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread wait loop"); std::this_thread::sleep_for(1000ms); std::chrono::steady_clock::time_point end = std::chrono::steady_clock::now(); timeout = std::chrono::duration_cast(end - begin).count() > TIMEOUT * 3; diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index f539588a..10a7df9b 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -95,12 +95,14 @@ SyncBackendInfo CRDTSyncEngine::backend_info() const std::unique_ptr CRDTSyncEngine::clone(SyncEngineHost& host) const { + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::clone"); return std::make_unique(host, *this); } std::optional CRDTSyncEngine::get_node(uint64_t id) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::get_node"); if (const auto* node = get_node_ptr(id); node != nullptr) { return to_user_node(*node); } @@ -109,6 +111,7 @@ std::optional CRDTSyncEngine::get_node(uint64_t id) const std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const std::string& type) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::get_edge"); if (const auto* edge = get_crdt_edge_ptr(from, to, type); edge != nullptr) { return to_user_edge(*edge); } @@ -117,6 +120,7 @@ std::optional CRDTSyncEngine::get_edge(uint64_t from, uint64_t to, const s bool CRDTSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::with_node_attrs"); if (const auto* node = get_node_ptr(id); node != nullptr) { CRDTNodeAttrsView attrs(node->attrs()); visitor(attrs); @@ -127,6 +131,7 @@ bool CRDTSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visito bool CRDTSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::with_node_view"); if (const auto* node = get_node_ptr(id); node != nullptr) { CRDTNodeView view(*node); visitor(view); @@ -137,6 +142,7 @@ bool CRDTSyncEngine::with_node_view(uint64_t id, const NodeViewVisitor& visitor) bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::for_each_edge_from"); if (const auto* node = get_node_ptr(from); node != nullptr) { for (const auto& [key, edge_reg] : node->fano()) { if (!edge_reg.empty()) { @@ -151,6 +157,7 @@ bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::for_each_edge_to"); bool found = false; host_.for_each_incoming_edge(to, [&](uint64_t from, const std::string& type) { found = true; @@ -164,6 +171,7 @@ bool CRDTSyncEngine::for_each_edge_to(uint64_t to, const IncomingEdgeVisitor& vi void CRDTSyncEngine::for_each_edge_of_type(const std::string& type, const TypedEdgeVisitor& visitor) const { + CORTEX_PROFILE_HOT_N("CRDTSyncEngine::for_each_edge_of_type"); host_.for_each_edge_of_type_cache(type, [&](uint64_t from, uint64_t to) { if (const auto* edge = get_crdt_edge_ptr(from, to, type); edge != nullptr) { Edge out = to_user_edge(*edge); @@ -179,6 +187,7 @@ size_t CRDTSyncEngine::size() const std::map CRDTSyncEngine::snapshot() const { + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::snapshot"); const auto log_level = host_.get_log_level(); std::map out; for (const auto& [id, reg] : nodes_) { @@ -193,6 +202,7 @@ std::map CRDTSyncEngine::snapshot() const NodeMutationEffect CRDTSyncEngine::insert_node_local(Node&& node) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_node_local"); NodeMutationEffect effect; auto [applied, delta] = insert_node_raw(user_node_to_crdt(std::move(node))); effect.applied = applied; @@ -208,6 +218,7 @@ NodeMutationEffect CRDTSyncEngine::insert_node_local(Node&& node) NodeMutationEffect CRDTSyncEngine::update_node_local(Node&& node) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::update_node_local"); NodeMutationEffect effect; auto [applied, deltas] = update_node_raw(user_node_to_crdt(std::move(node))); effect.applied = applied; @@ -223,6 +234,7 @@ NodeMutationEffect CRDTSyncEngine::update_node_local(Node&& node) NodeMutationEffect CRDTSyncEngine::delete_node_local(uint64_t id) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::delete_node_local"); NodeMutationEffect effect; if (auto node = get_crdt_node(id); node.has_value()) { auto [applied, deleted_edges, delta_node, delta_edges] = delete_node_raw(id, *node); @@ -245,6 +257,7 @@ NodeMutationEffect CRDTSyncEngine::delete_node_local(uint64_t id) EdgeMutationEffect CRDTSyncEngine::insert_or_assign_edge_local(Edge&& edge) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_or_assign_edge_local"); EdgeMutationEffect effect; auto from = edge.from(); auto to = edge.to(); @@ -269,6 +282,7 @@ EdgeMutationEffect CRDTSyncEngine::insert_or_assign_edge_local(Edge&& edge) EdgeMutationEffect CRDTSyncEngine::delete_edge_local(uint64_t from, uint64_t to, const std::string& type) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::delete_edge_local"); EdgeMutationEffect effect; effect.deleted_edge = get_edge(from, to, type); if (auto delta = delete_edge_raw(from, to, type); delta.has_value()) { @@ -283,6 +297,7 @@ EdgeMutationEffect CRDTSyncEngine::delete_edge_local(uint64_t from, uint64_t to, void CRDTSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::apply_remote_node_delta"); if (auto* payload = std::get_if(&delta); payload != nullptr) { join_delta_node(std::move(*payload)); } @@ -290,6 +305,7 @@ void CRDTSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) void CRDTSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) { + CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::apply_remote_edge_delta"); if (auto* payload = std::get_if(&delta); payload != nullptr) { join_delta_edge(std::move(*payload)); } @@ -297,6 +313,7 @@ void CRDTSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& batch) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::apply_remote_node_attr_batch"); auto* payload = std::get_if(&batch); if (payload == nullptr || payload->vec.empty()) { return; @@ -325,6 +342,7 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba void CRDTSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& batch) { + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::apply_remote_edge_attr_batch"); auto* payload = std::get_if(&batch); if (payload == nullptr || payload->vec.empty()) { return; @@ -428,7 +446,7 @@ std::tuple> CRDTSyncEngine::insert_node_raw(CR std::tuple> CRDTSyncEngine::update_node_raw(CRDTNode&& node) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::update_node_raw"); + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::update_node_raw"); if (!host_.is_node_deleted(node.id())) { auto nit = nodes_.find(node.id()); @@ -520,7 +538,7 @@ std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint6 std::tuple, std::optional> CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint64_t to) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::insert_or_assign_edge_raw"); + CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_or_assign_edge_raw"); std::optional delta_edge; std::optional delta_attrs; @@ -569,7 +587,7 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_edge"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_edge"); bool signal = false; auto& node = nodes_.at(from).read_reg(); auto& fanout = node.fano(); @@ -593,7 +611,7 @@ bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::s void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_node_attr"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_node_attr"); auto& n = nodes_.at(id).read_reg(); auto& attrs = n.attrs(); auto& attr_reg = attrs[att_name]; @@ -606,7 +624,7 @@ void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::process_delta_edge_attr"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_edge_attr"); auto& n = nodes_.at(from).read_reg().fano().at({to, type}).read_reg(); auto& attrs = n.attrs(); auto& attr_reg = attrs[att_name]; @@ -638,7 +656,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) std::string current_type; auto delete_unprocessed_deltas = [&](){ - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node delete unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_node delete unprocessed deltas"); unprocessed_delta_node_att_.erase(id); decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); while (!node_handle.empty()) @@ -653,7 +671,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) }; auto consume_unprocessed_deltas = [&]() { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node consume unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_node consume unprocessed deltas"); decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); while (!node_handle_node_att.empty()) { @@ -713,7 +731,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) }; { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node crdt merge"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_node crdt merge"); if (!host_.is_node_deleted(id)) { if (auto it = nodes_.find(id); it != nodes_.end() && !it->second.empty()) { maybe_deleted_node = it->second.read_reg(); @@ -742,7 +760,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) } if (joined) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node signal emit"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_node signal emit"); if (signal) { host_.on_remote_node_updated(id, current_type, mvreg.agent_id); if (const auto* current = get_node_ptr(id); current != nullptr) { @@ -790,7 +808,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) std::optional deleted_edge; auto delete_unprocessed_deltas = [&](){ - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge delete unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge delete unprocessed deltas"); unprocessed_delta_edge_att_.erase(std::tuple{from, to, type}); std::erase_if(unprocessed_delta_edge_to_, [&](auto &it){ return std::get<0>(it.second) == from || std::get<0>(it.second) == to;}); @@ -799,7 +817,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) }; auto consume_unprocessed_deltas = [&](){ - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge consume unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge consume unprocessed deltas"); auto att_key = std::tuple{from, to, type}; decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { @@ -817,7 +835,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) }; { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge crdt merge"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge crdt merge"); deleted_edge = get_edge(from, to, type); bool cfrom{nodes_.contains(from)}, cto{nodes_.contains(to)}; bool dfrom{host_.is_node_deleted(from)}, dto{host_.is_node_deleted(to)}; @@ -860,7 +878,7 @@ void CRDTSyncEngine::join_delta_edge(MvregEdgeMsg&& mvreg) } if (joined) { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge signal emit"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge signal emit"); if (signal) { host_.on_remote_edge_updated(from, to, type, mvreg.agent_id); } else { @@ -883,7 +901,7 @@ std::optional CRDTSyncEngine::join_delta_node_attr(MvregNodeAttrMsg auto crdt_delta = std::move(mvreg.dk); auto d_empty = crdt_delta.empty(); { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_node_attr crdt merge"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_node_attr crdt merge"); if (nodes_.contains(id)) { process_delta_node_attr(id, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_node_att_, @@ -928,7 +946,7 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg auto crdt_delta = std::move(mvreg.dk); auto d_empty = crdt_delta.empty(); { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({to, type})) { process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); @@ -972,7 +990,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) uint64_t id{0}, timestamp{0}; uint32_t agent_id_ch{0}; auto delete_unprocessed_deltas = [&](){ - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph delete unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_full_graph delete unprocessed deltas"); unprocessed_delta_node_att_.erase(id); decltype(unprocessed_delta_edge_from_)::node_type node_handle = unprocessed_delta_edge_from_.extract(id); while (!node_handle.empty()) @@ -985,7 +1003,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; auto consume_unprocessed_deltas = [&](){ - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph consume unprocessed deltas"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_full_graph consume unprocessed deltas"); decltype(unprocessed_delta_node_att_)::node_type node_handle_node_att = unprocessed_delta_node_att_.extract(id); while (!node_handle_node_att.empty()) { @@ -1045,7 +1063,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) }; { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph crdt"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_full_graph crdt"); for (auto &[k, val] : full_graph.m) { auto mv = std::move(val.dk); bool mv_empty = mv.empty(); @@ -1079,7 +1097,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } } { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::join_full_graph emit phase"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_full_graph emit phase"); for (auto &[signal, node_id, type, nd, current_nd] : updates) { if (signal) { if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { @@ -1112,7 +1130,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) std::map CRDTSyncEngine::export_mvreg_map() const { - CORTEX_PROFILE_ZONE_N("CRDTSyncEngine::export_mvreg_map"); + CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::export_mvreg_map"); const auto log_level = host_.get_log_level(); std::map m; for (const auto& kv : nodes_) { diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index d3760f5e..9c064dd7 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -709,6 +709,10 @@ namespace DSR void update_maps_node_insert_impl(uint64_t id, std::string name, const std::string& type, const T& outgoing_edges) { std::unique_lock lck(_mutex_cache_maps); + // Updates in the LWW backend flow through a delete+insert cache refresh. + // Re-inserting the node must clear any stale tombstone marker so future + // local updates are not rejected as "node is deleted". + deleted.erase(id); name_map[name] = id; id_map[id] = std::move(name); nodeType[type].emplace(id); diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index ac73d385..c608a70f 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -99,6 +99,7 @@ target_include_directories(dsr_benchmarks PRIVATE target_link_libraries(dsr_benchmarks PRIVATE Catch2::Catch2 nanobench + cortex_profiling dsr_api dsr_core Qt6::Core diff --git a/benchmarks/benchmark_main.cpp b/benchmarks/benchmark_main.cpp index 4d6cf397..24f0863a 100644 --- a/benchmarks/benchmark_main.cpp +++ b/benchmarks/benchmark_main.cpp @@ -6,6 +6,7 @@ #include #include #include "core/benchmark_config.h" +#include #include #include #include @@ -74,6 +75,7 @@ void configureBenchmarkDefaultsFromEnv() { load_env_value("BENCH_MAX_AGENT_COUNT", config.max_agent_count); load_env_value("BENCH_CONCURRENT_WRITER_THREADS", config.concurrent_writer_threads); load_env_value("BENCH_RESULTS_DIRECTORY", config.results_directory); + DSR::profiling::configure_detail_level_from_env(); } } // namespace @@ -128,6 +130,12 @@ int main(int argc, char* argv[]) { // Initialize Qt (required for signals/slots) QCoreApplication app(argc, argv); configureBenchmarkDefaultsFromEnv(); + + // Start profiling before benchmark fixture setup so graph construction, + // subscription thread bootstrap, and other one-time initialization are + // captured even if no hot-path zone has fired yet. + DSR::profiling::ensure_started(); + // Initialize Catch2 Catch::Session session; @@ -146,6 +154,7 @@ int main(int argc, char* argv[]) { std::cout << "=================================\n\n"; std::cout << "Benchmark config:\n"; std::cout << " sync_mode = " << DSR::Benchmark::sync_mode_name(DSR::Benchmark::default_config().sync_mode) << "\n"; + std::cout << " profile_detail = " << DSR::profiling::detail_level_name(DSR::profiling::get_detail_level()) << "\n"; std::cout << " warmup = " << DSR::Benchmark::default_config().warmup_iterations << "\n"; std::cout << " measurements = " << DSR::Benchmark::default_config().measurement_iterations << "\n"; std::cout << " sync_wait_ms = " << DSR::Benchmark::default_config().sync_wait_time.count() << "\n"; @@ -176,10 +185,14 @@ int main(int argc, char* argv[]) { std::cout << " ./dsr_benchmarks \"[.multi]\" # Run multi-agent tests (may timeout)\n"; std::cout << " ./dsr_benchmarks -r json::out=x.json # Export to JSON\n"; std::cout << " ./dsr_benchmarks --verbose # Show Qt debug messages\n"; + std::cout << " BENCH_PROFILE_DETAIL=min ./dsr_benchmarks \"[PROFILE]\" # Coarser zones\n"; + std::cout << " BENCH_PROFILE_DETAIL=hot ./dsr_benchmarks \"[PROFILE]\" # Full hot-path zones\n"; std::cout << "\n"; std::cout << "Note: [.multi] and [.extended] tests are hidden by default.\n"; std::cout << "\n"; } - return session.run(); + const int result = session.run(); + DSR::profiling::shutdown(); + return result; } diff --git a/benchmarks/fixtures/multi_agent_fixture.h b/benchmarks/fixtures/multi_agent_fixture.h index 86d77eaa..9946fed7 100644 --- a/benchmarks/fixtures/multi_agent_fixture.h +++ b/benchmarks/fixtures/multi_agent_fixture.h @@ -12,6 +12,7 @@ #include #include #include +#include #include #include "../core/benchmark_config.h" #include "../core/timing_utils.h" @@ -61,6 +62,7 @@ class MultiAgentFixture { // Create N agent instances with DSRGraph // First agent loads from config_file, others sync via DDS bool create_agents(uint32_t num_agents, const std::string& config_file) { + CORTEX_PROFILE_MIN_N("MultiAgentFixture::create_agents"); if (num_agents == 0 || num_agents > config_.max_agent_count) { qWarning("Can't create agents"); return false; @@ -238,6 +240,7 @@ class MultiAgentFixture { // Cleanup all agents void cleanup() { + CORTEX_PROFILE_MIN_N("MultiAgentFixture::cleanup"); agents_.clear(); } diff --git a/benchmarks/flamegraph.sh b/benchmarks/flamegraph.sh index 60671012..e1c367ce 100755 --- a/benchmarks/flamegraph.sh +++ b/benchmarks/flamegraph.sh @@ -6,9 +6,12 @@ # # Options: # -b BINARY Path to dsr_benchmarks (default: ./build/dsr_benchmarks) +# -g BACKEND Graph backend for dsr_benchmarks: crdt or lww +# (default: use dsr_benchmarks default) # -o OUTPUT Output root directory for run subdirectories # (default: ./results/flamegraphs) # -F FREQ perf sampling frequency in Hz (default: 999) +# -i Enable inline frame expansion in stackcollapse-perf.pl # -k Keep raw perf.data files (deleted by default) # -l List matching profile targets and exit # -p PRESET Built-in preset: load, multiagent, profile @@ -50,17 +53,21 @@ set -euo pipefail BINARY="./build/dsr_benchmarks" OUTROOT="./results/flamegraphs" FREQ=999 +INLINE=0 KEEP_DATA=0 LIST_ONLY=0 PRESET="" FILTER="" +BACKEND="${BENCH_SYNC_MODE:-}" RUN_ID="flamegraph-$(date +%Y%m%d-%H%M%S)" -while getopts "b:o:F:klp:r:h" opt; do +while getopts "b:g:o:F:iklp:r:h" opt; do case "$opt" in b) BINARY="$OPTARG" ;; + g) BACKEND="$OPTARG" ;; o) OUTROOT="$OPTARG" ;; F) FREQ="$OPTARG" ;; + i) INLINE=1 ;; k) KEEP_DATA=1 ;; l) LIST_ONLY=1 ;; p) PRESET="$OPTARG" ;; @@ -131,6 +138,17 @@ EOF exit 1 fi +if [[ -n "$BACKEND" ]]; then + case "$BACKEND" in + crdt|CRDT) BACKEND="crdt" ;; + lww|LWW) BACKEND="lww" ;; + *) + echo "ERROR: unknown graph backend '$BACKEND' (expected: crdt or lww)" >&2 + exit 1 + ;; + esac +fi + [[ -x "$BINARY" ]] || { echo "ERROR: binary not found or not executable: $BINARY" >&2; exit 1; } command -v perf >/dev/null 2>&1 || { echo "ERROR: perf not found" >&2; exit 1; } @@ -138,7 +156,7 @@ OUTDIR="${OUTROOT}/${RUN_ID}" mkdir -p "$OUTDIR" mapfile -t TEST_NAMES < <( - "$BINARY" --list-tests --verbosity quiet "$FILTER" 2>/dev/null \ + BENCH_SYNC_MODE="$BACKEND" "$BINARY" --list-tests --verbosity quiet "$FILTER" 2>/dev/null \ | sed 's/\r$//' \ | grep -v '^[[:space:]]' \ | grep -v '^All available test cases:' \ @@ -159,6 +177,7 @@ fi COLLAPSE="$(find_tool stackcollapse-perf.pl)" FLAMEGRAPH="$(find_tool flamegraph.pl)" +COLLAPSE_ARGS=() if [[ -z "$COLLAPSE" || -z "$FLAMEGRAPH" ]]; then cat >&2 <<'EOF' @@ -171,8 +190,15 @@ EOF exit 1 fi +if [[ $INLINE -eq 1 ]]; then + COLLAPSE_ARGS+=(--inline) +fi + echo "Found ${#TEST_NAMES[@]} test(s) to profile." echo "Output: $OUTDIR" +if [[ -n "$BACKEND" ]]; then + echo "Backend: $BACKEND" +fi echo PASS=0 @@ -193,10 +219,10 @@ for name in "${TEST_NAMES[@]}"; do -g \ --call-graph dwarf \ -o "$perf_tmp" \ - -- "$BINARY" "$name" 2>/dev/null; then + -- env BENCH_SYNC_MODE="$BACKEND" "$BINARY" "$name" 2>/dev/null; then perf script -i "$perf_tmp" 2>/dev/null \ - | perl "$COLLAPSE" --inline \ + | perl "$COLLAPSE" "${COLLAPSE_ARGS[@]}" \ | perl "$FLAMEGRAPH" --title "$name" \ > "$svg_tmp" diff --git a/benchmarks/perfetto.sh b/benchmarks/perfetto.sh new file mode 100644 index 00000000..def57087 --- /dev/null +++ b/benchmarks/perfetto.sh @@ -0,0 +1,192 @@ +#!/usr/bin/env bash +# perfetto.sh - generate one Perfetto trace per benchmark test case. +# +# Usage: +# ./perfetto.sh [OPTIONS] [FILTER] +# +# Options: +# -b BINARY Path to dsr_benchmarks (default: ./build/dsr_benchmarks) +# -d DETAIL Profiling detail: off, min, default, detail, hot +# (default: use BENCH_PROFILE_DETAIL or binary default) +# -g BACKEND Graph backend for dsr_benchmarks: crdt or lww +# (default: use BENCH_SYNC_MODE or dsr_benchmarks default) +# -o OUTPUT Output root directory for run subdirectories +# (default: ./results/perfetto) +# -l List matching profile targets and exit +# -p PRESET Built-in preset: load, multiagent, profile +# -r RUN_ID Run directory name under OUTPUT +# (default: perfetto-YYYYMMDD-HHMMSS) +# -k Keep running after individual benchmark failures +# -h Show this help +# +# FILTER is forwarded to Catch2 as a tag expression or exact test name, e.g.: +# ./perfetto.sh "Signal emission under load" +# ./perfetto.sh "[PROFILE][LOAD]" +# ./perfetto.sh -p multiagent +# ./perfetto.sh -l -p profile +# +# The script intentionally does not default to "all benchmarks". Pass an exact +# benchmark name, a Catch2 tag expression, or a preset for scoped profiling. + +set -euo pipefail + +BINARY="./build/dsr_benchmarks" +OUTROOT="./results/perfetto" +LIST_ONLY=0 +PRESET="" +FILTER="" +BACKEND="${BENCH_SYNC_MODE:-}" +DETAIL="${BENCH_PROFILE_DETAIL:-}" +RUN_ID="perfetto-$(date +%Y%m%d-%H%M%S)" +KEEP_GOING=0 + +while getopts "b:d:g:o:lp:r:kh" opt; do + case "$opt" in + b) BINARY="$OPTARG" ;; + d) DETAIL="$OPTARG" ;; + g) BACKEND="$OPTARG" ;; + o) OUTROOT="$OPTARG" ;; + l) LIST_ONLY=1 ;; + p) PRESET="$OPTARG" ;; + r) RUN_ID="$OPTARG" ;; + k) KEEP_GOING=1 ;; + h) + sed -n '2,/^set -/p' "$0" | grep '^#' | sed 's/^# \{0,1\}//' + exit 0 + ;; + *) echo "Unknown option: -$OPTARG" >&2; exit 1 ;; + esac +done +shift $((OPTIND - 1)) +FILTER="${1:-}" + +preset_to_filter() { + case "$1" in + load) echo "[PROFILE][LOAD]" ;; + multiagent) echo "[PROFILE][MULTIAGENT]" ;; + profile) echo "[PROFILE]" ;; + *) + echo "ERROR: unknown preset '$1' (expected: load, multiagent, profile)" >&2 + exit 1 + ;; + esac +} + +if [[ -n "$PRESET" && -n "$FILTER" ]]; then + echo "ERROR: use either -p PRESET or a FILTER argument, not both" >&2 + exit 1 +fi + +if [[ -n "$PRESET" ]]; then + FILTER="$(preset_to_filter "$PRESET")" +fi + +if [[ -z "$FILTER" ]]; then + cat >&2 <<'EOF' +ERROR: a benchmark filter is required. +Examples: + ./perfetto.sh "Signal emission under load" + ./perfetto.sh "[PROFILE][LOAD]" + ./perfetto.sh -p multiagent + ./perfetto.sh -l -p profile +EOF + exit 1 +fi + +if [[ -n "$BACKEND" ]]; then + case "$BACKEND" in + crdt|CRDT) BACKEND="crdt" ;; + lww|LWW) BACKEND="lww" ;; + *) + echo "ERROR: unknown graph backend '$BACKEND' (expected: crdt or lww)" >&2 + exit 1 + ;; + esac +fi + +if [[ -n "$DETAIL" ]]; then + case "$DETAIL" in + off|min|default|detail|hot) ;; + *) + echo "ERROR: unknown profiling detail '$DETAIL' (expected: off, min, default, detail, hot)" >&2 + exit 1 + ;; + esac +fi + +[[ -x "$BINARY" ]] || { echo "ERROR: binary not found or not executable: $BINARY" >&2; exit 1; } + +OUTDIR="${OUTROOT}/${RUN_ID}" +mkdir -p "$OUTDIR" + +mapfile -t TEST_NAMES < <( + BENCH_SYNC_MODE="$BACKEND" BENCH_PROFILE_DETAIL="$DETAIL" "$BINARY" --list-tests --verbosity quiet "$FILTER" 2>/dev/null \ + | sed 's/\r$//' \ + | grep -v '^[[:space:]]' \ + | grep -v '^All available test cases:' \ + | grep -v '^[0-9][0-9]* test cases$' \ + | grep -v '^$' +) + +if [[ ${#TEST_NAMES[@]} -eq 0 ]]; then + echo "No tests matched filter: '${FILTER}'" >&2 + echo "Run '$BINARY --list-tests' to see available tests." >&2 + exit 1 +fi + +if [[ $LIST_ONLY -eq 1 ]]; then + printf '%s\n' "${TEST_NAMES[@]}" + exit 0 +fi + +echo "Found ${#TEST_NAMES[@]} test(s) to trace." +echo "Output: $OUTDIR" +if [[ -n "$BACKEND" ]]; then + echo "Backend: $BACKEND" +fi +if [[ -n "$DETAIL" ]]; then + echo "Profile detail: $DETAIL" +fi +echo + +PASS=0 +FAIL=0 + +for name in "${TEST_NAMES[@]}"; do + safe="$(echo "$name" | tr -cs 'A-Za-z0-9_-' '_' | sed 's/_\+/_/g; s/^_//; s/_$//')" + trace_out="${OUTDIR}/${safe}.pftrace" + trace_tmp="${trace_out}.tmp.$$" + + echo "-- $name" + + if env \ + BENCH_SYNC_MODE="$BACKEND" \ + BENCH_PROFILE_DETAIL="$DETAIL" \ + CORTEX_PERFETTO_TRACE_FILE="$trace_tmp" \ + "$BINARY" "$name" 2>/dev/null; then + + if [[ -s "$trace_tmp" ]]; then + mv -f "$trace_tmp" "$trace_out" + echo " -> $trace_out" + ((PASS++)) || true + else + echo " x trace file missing or empty" >&2 + rm -f "$trace_tmp" + ((FAIL++)) || true + if [[ $KEEP_GOING -eq 0 ]]; then + exit 1 + fi + fi + else + echo " x benchmark run failed" >&2 + rm -f "$trace_tmp" + ((FAIL++)) || true + if [[ $KEEP_GOING -eq 0 ]]; then + exit 1 + fi + fi +done + +echo +echo "Done: $PASS succeeded, $FAIL failed." +[[ $FAIL -eq 0 ]] diff --git a/core/include/dsr/core/profiling.h b/core/include/dsr/core/profiling.h index a7273e28..44f0db75 100644 --- a/core/include/dsr/core/profiling.h +++ b/core/include/dsr/core/profiling.h @@ -1,18 +1,74 @@ #ifndef DSR_CORE_PROFILING_H #define DSR_CORE_PROFILING_H +#include +#include +#include +#include + +#ifndef CORTEX_CALLSTACK_DEPTH +#define CORTEX_CALLSTACK_DEPTH 0 +#endif + namespace DSR::profiling { + +enum class DetailLevel : int { + Off = 0, + Min = 1, + Default = 2, + Detail = 3, + Hot = 4, +}; + void ensure_started(); void shutdown(); -} +void configure_detail_level_from_env() noexcept; +void set_detail_level(DetailLevel level) noexcept; +DetailLevel get_detail_level() noexcept; +bool detail_enabled(DetailLevel level) noexcept; +bool try_parse_detail_level(const char* value, DetailLevel& out) noexcept; +const char* detail_level_name(DetailLevel level) noexcept; + +} // namespace DSR::profiling #if defined(CORTEX_PROFILING_BACKEND_TRACY) #include -#define CORTEX_PROFILE_ZONE() ZoneScoped -#define CORTEX_PROFILE_ZONE_N(name_literal) ZoneScopedN(name_literal) -#define CORTEX_PROFILE_ZONE_CS(name_literal) ZoneScopedNS(name_literal, CORTEX_CALLSTACK_DEPTH) +namespace DSR::profiling { + +class ScopedZone { +public: + template + ScopedZone(DetailLevel level, + uint32_t line, + const char* source, + const char* function, + const char (&name)[N], + int callstack_depth = 0) + { + if (!detail_enabled(level)) + return; + + const auto source_sz = std::strlen(source); + const auto function_sz = std::strlen(function); + const auto name_sz = std::strlen(name); + + if (callstack_depth > 0) { + zone_ = std::make_unique( + line, source, source_sz, function, function_sz, name, name_sz, callstack_depth, true); + } else { + zone_ = std::make_unique( + line, source, source_sz, function, function_sz, name, name_sz, true); + } + } + +private: + std::unique_ptr zone_; +}; + +} // namespace DSR::profiling + #define CORTEX_PROFILE_FRAME() FrameMark #define CORTEX_PROFILE_TEXT(text_ptr, text_size) ZoneText(text_ptr, text_size) #define CORTEX_PROFILE_VALUE(value) ZoneValue(value) @@ -40,42 +96,66 @@ CallstackFrames capture_callstack(int depth) noexcept; void emit_callstack_stackframe(perfetto::EventContext& ctx, const CallstackFrames& cs) noexcept; #endif -} // namespace DSR::profiling - -#define CORTEX_PROFILE_ZONE() \ - ::DSR::profiling::ensure_started(); \ - TRACE_EVENT("cortex", perfetto::StaticString{__func__}) - -#define CORTEX_PROFILE_ZONE_N(name_literal) \ - ::DSR::profiling::ensure_started(); \ - TRACE_EVENT("cortex", name_literal) +class ScopedZone { +public: + template + ScopedZone(DetailLevel level, + uint32_t, + const char*, + const char*, + const char (&name)[N], + int callstack_depth = 0) + : active_(detail_enabled(level)) + { + if (!active_) + return; + + ensure_started(); #if defined(CORTEX_PERFETTO_CALLSTACK_STACKFRAME) -#define CORTEX_PROFILE_ZONE_CS(name_literal) \ - ::DSR::profiling::ensure_started(); \ - auto _cortex_cs = ::DSR::profiling::capture_callstack(CORTEX_CALLSTACK_DEPTH); \ - TRACE_EVENT("cortex", name_literal, [&_cortex_cs](perfetto::EventContext ctx) { \ - ::DSR::profiling::emit_callstack_stackframe(ctx, _cortex_cs); \ - }) + if (callstack_depth > 0) { + auto cs = capture_callstack(callstack_depth); + TRACE_EVENT_BEGIN("cortex", perfetto::StaticString{name}, [cs](perfetto::EventContext ctx) { + emit_callstack_stackframe(ctx, cs); + }); + return; + } #else -/* DEFAULT / LINUX_PERF: no per-zone callstack capture needed; - linux.perf samples the whole process at the configured frequency. */ -#define CORTEX_PROFILE_ZONE_CS(name_literal) \ - ::DSR::profiling::ensure_started(); \ - TRACE_EVENT("cortex", name_literal) + static_cast(callstack_depth); #endif + TRACE_EVENT_BEGIN("cortex", perfetto::StaticString{name}); + } + + ~ScopedZone() + { + if (active_) + TRACE_EVENT_END("cortex"); + } + +private: + bool active_ = false; +}; + +} // namespace DSR::profiling #define CORTEX_PROFILE_FRAME() ((void)0) #define CORTEX_PROFILE_TEXT(text_ptr, text_size) ((void)0) #define CORTEX_PROFILE_VALUE(value) ((void)0) #define CORTEX_PROFILE_THREAD_NAME(name) \ - do { char _tn[16]; strncpy(_tn, (name), 15); _tn[15] = '\0'; pthread_setname_np(pthread_self(), _tn); } while(0) + do { char _tn[16]; std::strncpy(_tn, (name), 15); _tn[15] = '\0'; pthread_setname_np(pthread_self(), _tn); } while(0) #else -#define CORTEX_PROFILE_ZONE() ((void)0) -#define CORTEX_PROFILE_ZONE_N(name_literal) ((void)0) -#define CORTEX_PROFILE_ZONE_CS(name_literal) ((void)0) +namespace DSR::profiling { + +class ScopedZone { +public: + template + ScopedZone(DetailLevel, uint32_t, const char*, const char*, const char (&)[N], int = 0) {} +}; + +} // namespace DSR::profiling + #define CORTEX_PROFILE_FRAME() ((void)0) #define CORTEX_PROFILE_TEXT(text_ptr, text_size) ((void)0) #define CORTEX_PROFILE_VALUE(value) ((void)0) @@ -83,4 +163,33 @@ void emit_callstack_stackframe(perfetto::EventContext& ctx, const CallstackFrame #endif +#define CORTEX_PROFILE_CONCAT_IMPL(a, b) a##b +#define CORTEX_PROFILE_CONCAT(a, b) CORTEX_PROFILE_CONCAT_IMPL(a, b) + +#define CORTEX_PROFILE_ZONE_L(level) \ + ::DSR::profiling::ScopedZone CORTEX_PROFILE_CONCAT(_cortex_zone_, __LINE__)( \ + (level), __LINE__, __FILE__, __func__, __func__) + +#define CORTEX_PROFILE_ZONE_N_L(level, name_literal) \ + ::DSR::profiling::ScopedZone CORTEX_PROFILE_CONCAT(_cortex_zone_, __LINE__)( \ + (level), __LINE__, __FILE__, __func__, (name_literal)) + +#define CORTEX_PROFILE_ZONE_CS_L(level, name_literal) \ + ::DSR::profiling::ScopedZone CORTEX_PROFILE_CONCAT(_cortex_zone_, __LINE__)( \ + (level), __LINE__, __FILE__, __func__, (name_literal), CORTEX_CALLSTACK_DEPTH) + +#define CORTEX_PROFILE_MIN() CORTEX_PROFILE_ZONE_L(::DSR::profiling::DetailLevel::Min) +#define CORTEX_PROFILE_MIN_N(name_literal) CORTEX_PROFILE_ZONE_N_L(::DSR::profiling::DetailLevel::Min, name_literal) +#define CORTEX_PROFILE_MIN_CS(name_literal) CORTEX_PROFILE_ZONE_CS_L(::DSR::profiling::DetailLevel::Min, name_literal) + +#define CORTEX_PROFILE_DETAIL_N(name_literal) CORTEX_PROFILE_ZONE_N_L(::DSR::profiling::DetailLevel::Detail, name_literal) +#define CORTEX_PROFILE_DETAIL_CS(name_literal) CORTEX_PROFILE_ZONE_CS_L(::DSR::profiling::DetailLevel::Detail, name_literal) + +#define CORTEX_PROFILE_HOT_N(name_literal) CORTEX_PROFILE_ZONE_N_L(::DSR::profiling::DetailLevel::Hot, name_literal) +#define CORTEX_PROFILE_HOT_CS(name_literal) CORTEX_PROFILE_ZONE_CS_L(::DSR::profiling::DetailLevel::Hot, name_literal) + +#define CORTEX_PROFILE_ZONE() CORTEX_PROFILE_ZONE_L(::DSR::profiling::DetailLevel::Default) +#define CORTEX_PROFILE_ZONE_N(name_literal) CORTEX_PROFILE_ZONE_N_L(::DSR::profiling::DetailLevel::Default, name_literal) +#define CORTEX_PROFILE_ZONE_CS(name_literal) CORTEX_PROFILE_ZONE_CS_L(::DSR::profiling::DetailLevel::Default, name_literal) + #endif diff --git a/core/profiling.cpp b/core/profiling.cpp index 4b457fe5..e92a4994 100644 --- a/core/profiling.cpp +++ b/core/profiling.cpp @@ -1,13 +1,104 @@ #include "dsr/core/profiling.h" +#include +#include +#include +#include +#include + +namespace DSR::profiling { +namespace { + +std::atomic g_detail_level{static_cast(DetailLevel::Default)}; +std::atomic g_detail_level_explicit{false}; +std::once_flag g_detail_init_once; + +bool try_parse_detail_level_impl(const char* value, DetailLevel& out) noexcept +{ + if (value == nullptr || value[0] == '\0') + return false; + + char normalized[16]; + size_t i = 0; + for (; value[i] != '\0' && i + 1 < sizeof(normalized); ++i) + normalized[i] = static_cast(std::tolower(static_cast(value[i]))); + normalized[i] = '\0'; + + if (std::strcmp(normalized, "off") == 0 || std::strcmp(normalized, "0") == 0) { + out = DetailLevel::Off; + } else if (std::strcmp(normalized, "min") == 0 || std::strcmp(normalized, "1") == 0) { + out = DetailLevel::Min; + } else if (std::strcmp(normalized, "default") == 0 || std::strcmp(normalized, "2") == 0) { + out = DetailLevel::Default; + } else if (std::strcmp(normalized, "detail") == 0 || std::strcmp(normalized, "3") == 0) { + out = DetailLevel::Detail; + } else if (std::strcmp(normalized, "hot") == 0 || std::strcmp(normalized, "4") == 0) { + out = DetailLevel::Hot; + } else { + return false; + } + + return true; +} + +} // namespace + +void configure_detail_level_from_env() noexcept +{ + std::call_once(g_detail_init_once, [] { + if (g_detail_level_explicit.load(std::memory_order_relaxed)) + return; + + DetailLevel parsed{}; + if (try_parse_detail_level_impl(std::getenv("CORTEX_PROFILE_DETAIL"), parsed) || + try_parse_detail_level_impl(std::getenv("BENCH_PROFILE_DETAIL"), parsed)) { + set_detail_level(parsed); + } + }); +} + +void set_detail_level(DetailLevel level) noexcept +{ + g_detail_level_explicit.store(true, std::memory_order_relaxed); + g_detail_level.store(static_cast(level), std::memory_order_relaxed); +} + +DetailLevel get_detail_level() noexcept +{ + return static_cast(g_detail_level.load(std::memory_order_relaxed)); +} + +bool detail_enabled(DetailLevel level) noexcept +{ + configure_detail_level_from_env(); + return static_cast(level) <= g_detail_level.load(std::memory_order_relaxed); +} + +bool try_parse_detail_level(const char* value, DetailLevel& out) noexcept +{ + return try_parse_detail_level_impl(value, out); +} + +const char* detail_level_name(DetailLevel level) noexcept +{ + switch (level) { + case DetailLevel::Off: return "off"; + case DetailLevel::Min: return "min"; + case DetailLevel::Default: + case DetailLevel::Detail: return "detail"; + case DetailLevel::Hot: return "hot"; + } + return "default"; +} + +} // namespace DSR::profiling + #if defined(CORTEX_PROFILING_BACKEND_PERFETTO) #include #include #include -#include -#include #include #include #include @@ -77,13 +168,26 @@ void start_session() #endif perfetto::TraceConfig cfg; - cfg.add_buffers()->set_size_kb(32 * 1024); + auto* track_buffer = cfg.add_buffers(); + track_buffer->set_size_kb(64 * 1024); + track_buffer->set_fill_policy(perfetto::TraceConfig::BufferConfig::DISCARD); +#if defined(CORTEX_PERFETTO_CALLSTACK_LINUX_PERF) + auto* perf_buffer = cfg.add_buffers(); + perf_buffer->set_size_kb(64 * 1024); +#endif + cfg.set_flush_period_ms(1000); + cfg.mutable_incremental_state_config()->set_clear_period_ms(1000); { auto* ds_cfg = cfg.add_data_sources()->mutable_config(); ds_cfg->set_name("track_event"); + ds_cfg->set_target_buffer(0); perfetto::protos::gen::TrackEventConfig te_cfg; te_cfg.add_enabled_categories("*"); + // Keep packets more self-contained on the system backend. This reduces + // the impact of isolated incremental-state loss, which is more common + // under WSL than on native Linux. + te_cfg.set_disable_incremental_timestamps(true); ds_cfg->set_track_event_config_raw(te_cfg.SerializeAsString()); } @@ -91,6 +195,7 @@ void start_session() { auto* ds_cfg = cfg.add_data_sources()->mutable_config(); ds_cfg->set_name("linux.perf"); + ds_cfg->set_target_buffer(1); perfetto::protos::gen::PerfEventConfig perf_cfg; perf_cfg.mutable_timebase()->set_frequency(1000); // Per-process scope: works without root when perf_event_paranoid <= 1. @@ -124,6 +229,7 @@ void shutdown() return; DSR::profiling::TrackEvent::Flush(); + g_session->FlushBlocking(3000); g_session->StopBlocking(); const auto trace_data = g_session->ReadTraceBlocking(); From 8ad95e46c648e4ead488c7fb3ba7b9208d80943a Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 24 Apr 2026 19:40:56 +0200 Subject: [PATCH 27/38] refactor: more work --- api/dsr_agent_info_api.cpp | 10 + api/dsr_crdt_sync_engine.cpp | 172 +++++------ api/dsr_utils.cpp | 2 +- api/include/dsr/api/dsr_api.h | 8 +- api/include/dsr/api/dsr_crdt_sync_engine.h | 32 +- benchmarks/latency/crdt_join_bench.cpp | 16 +- benchmarks/latency/type_conversion_bench.cpp | 4 +- core/include/dsr/core/crdt/delta_crdt.h | 19 +- core/include/dsr/core/traits.h | 10 +- core/include/dsr/core/types/common_types.h | 121 ++------ core/include/dsr/core/types/crdt_io.h | 98 +++---- core/include/dsr/core/types/crdt_types.h | 200 +++---------- core/include/dsr/core/types/internal_types.h | 12 +- core/include/dsr/core/types/translator.h | 8 +- core/include/dsr/core/types/user_types.h | 45 +-- core/types/common_types.cpp | 8 +- core/types/crdt_types.cpp | 275 ++++-------------- .../viewers/graph_viewer/graph_edge_widget.h | 6 +- .../viewers/graph_viewer/graph_node_widget.h | 6 +- python-wrapper/python_api.cpp | 16 +- tests/synchronization/graph_signals.cpp | 2 +- tests/synchronization/type_translation.cpp | 158 +++++----- 22 files changed, 422 insertions(+), 806 deletions(-) diff --git a/api/dsr_agent_info_api.cpp b/api/dsr_agent_info_api.cpp index ebe608c4..158550db 100644 --- a/api/dsr_agent_info_api.cpp +++ b/api/dsr_agent_info_api.cpp @@ -39,6 +39,16 @@ namespace DSR { std::string AgentInfoAPI::exec(const char* cmd) { + struct PipeCloser + { + void operator()(FILE* pipe) const noexcept + { + if (pipe != nullptr) { + pclose(pipe); + } + } + }; + std::array buffer{}; std::string result; std::unique_ptr pipe(popen(cmd, "r")); diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 10a7df9b..963abf6d 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -41,7 +41,7 @@ bool protocol_version_matches( class CRDTNodeAttrsView final : public SyncEngine::NodeAttrsView { public: - explicit CRDTNodeAttrsView(const std::map>& attrs) + explicit CRDTNodeAttrsView(const std::map>& attrs) : attrs_(attrs) {} const Attribute* find(const std::string& name) const override @@ -53,22 +53,22 @@ class CRDTNodeAttrsView final : public SyncEngine::NodeAttrsView } private: - const std::map>& attrs_; + const std::map>& attrs_; }; class CRDTNodeView final : public SyncEngine::NodeView { public: - explicit CRDTNodeView(const CRDTNode& node) - : node_(node), attrs_(node.attrs()) {} + explicit CRDTNodeView(const CRDT::Node& node) + : node_(node), attrs_(node.attrs) {} - uint64_t id() const override { return node_.id(); } - const std::string& type() const override { return node_.type(); } - const std::string& name() const override { return node_.name(); } + uint64_t id() const override { return node_.id; } + const std::string& type() const override { return node_.type; } + const std::string& name() const override { return node_.name; } const SyncEngine::NodeAttrsView& attrs() const override { return attrs_; } private: - const CRDTNode& node_; + const CRDT::Node& node_; CRDTNodeAttrsView attrs_; }; } @@ -122,7 +122,7 @@ bool CRDTSyncEngine::with_node_attrs(uint64_t id, const NodeAttrsVisitor& visito { CORTEX_PROFILE_HOT_N("CRDTSyncEngine::with_node_attrs"); if (const auto* node = get_node_ptr(id); node != nullptr) { - CRDTNodeAttrsView attrs(node->attrs()); + CRDTNodeAttrsView attrs(node->attrs); visitor(attrs); return true; } @@ -144,7 +144,7 @@ bool CRDTSyncEngine::for_each_edge_from(uint64_t from, const OutgoingEdgeVisitor { CORTEX_PROFILE_HOT_N("CRDTSyncEngine::for_each_edge_from"); if (const auto* node = get_node_ptr(from); node != nullptr) { - for (const auto& [key, edge_reg] : node->fano()) { + for (const auto& [key, edge_reg] : node->fano) { if (!edge_reg.empty()) { Edge edge = to_user_edge(edge_reg.read_reg()); visitor(key.first, key.second, edge); @@ -210,7 +210,7 @@ NodeMutationEffect CRDTSyncEngine::insert_node_local(Node&& node) effect.id = delta->id; effect.node_delta = NodeDeltaMessage{*delta}; if (const auto* inserted = get_node_ptr(delta->id); inserted != nullptr) { - effect.type = inserted->type(); + effect.type = inserted->type; } } return effect; @@ -334,7 +334,7 @@ void CRDTSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& ba if (!changed_attributes.empty()) { std::string type; if (const auto* node = get_node_ptr(id); node != nullptr) { - type = node->type(); + type = node->type; } host_.on_remote_node_attrs_updated(id, type, changed_attributes, sample_agent_id); } @@ -384,7 +384,7 @@ FullGraphMessage CRDTSyncEngine::export_full_graph() const return map; } -const CRDTNode* CRDTSyncEngine::get_node_ptr(uint64_t id) const +const CRDT::Node* CRDTSyncEngine::get_node_ptr(uint64_t id) const { auto it = nodes_.find(id); if (it != nodes_.end() && !it->second.empty()) { @@ -393,7 +393,7 @@ const CRDTNode* CRDTSyncEngine::get_node_ptr(uint64_t id) const return nullptr; } -std::optional CRDTSyncEngine::get_crdt_node(uint64_t id) const +std::optional CRDTSyncEngine::get_crdt_node(uint64_t id) const { if (const auto* node = get_node_ptr(id); node != nullptr) { return std::make_optional(*node); @@ -401,14 +401,14 @@ std::optional CRDTSyncEngine::get_crdt_node(uint64_t id) const return {}; } -const CRDTEdge* CRDTSyncEngine::get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const +const CRDT::Edge* CRDTSyncEngine::get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const { auto from_it = nodes_.find(from); if (from_it == nodes_.end() || from_it->second.empty() || !nodes_.contains(to)) { return nullptr; } - auto& fano = from_it->second.read_reg().fano(); + auto& fano = from_it->second.read_reg().fano; auto edge = fano.find({to, key}); if (edge != fano.end() && !edge->second.empty()) { return &edge->second.read_reg(); @@ -417,7 +417,7 @@ const CRDTEdge* CRDTSyncEngine::get_crdt_edge_ptr(uint64_t from, uint64_t to, co return nullptr; } -std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const +std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const { if (const auto* edge = get_crdt_edge_ptr(from, to, key); edge != nullptr) { return *edge; @@ -425,42 +425,42 @@ std::optional CRDTSyncEngine::get_crdt_edge(uint64_t from, uint64_t to return {}; } -std::tuple> CRDTSyncEngine::insert_node_raw(CRDTNode&& node) +std::tuple> CRDTSyncEngine::insert_node_raw(CRDT::Node&& node) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_node_raw"); - if (!host_.is_node_deleted(node.id())) + if (!host_.is_node_deleted(node.id)) { - if (auto it = nodes_.find(node.id()); it != nodes_.end() and not it->second.empty() and it->second.read_reg() == node) + if (auto it = nodes_.find(node.id); it != nodes_.end() and not it->second.empty() and it->second.read_reg() == node) { return {true, {}}; } - uint64_t id = node.id(); - host_.update_maps_node_insert(id, node.name(), node.type(), collect_outgoing_edge_keys(node.fano())); + uint64_t id = node.id; + host_.update_maps_node_insert(id, node.name, node.type, collect_outgoing_edge_keys(node.fano)); auto delta = nodes_[id].write(std::move(node)); - nodes_[id].join(mvreg(delta)); + nodes_[id].join(mvreg(delta)); return {true, crdt_node_to_msg(host_.local_agent_id(), id, std::move(delta))}; } return {false, {}}; } -std::tuple> CRDTSyncEngine::update_node_raw(CRDTNode&& node) +std::tuple> CRDTSyncEngine::update_node_raw(CRDT::Node&& node) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::update_node_raw"); - if (!host_.is_node_deleted(node.id())) + if (!host_.is_node_deleted(node.id)) { - auto nit = nodes_.find(node.id()); + auto nit = nodes_.find(node.id); if (nit != nodes_.end() && !nit->second.empty()) { MvregNodeAttrVec atts_deltas; - auto& iter = nit->second.read_reg().attrs(); - for (auto& [k, att] : node.attrs()) { - auto& attr_reg = iter.try_emplace(k, mvreg()).first->second; + auto& iter = nit->second.read_reg().attrs; + for (auto& [k, att] : node.attrs) { + auto& attr_reg = iter.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); - attr_reg.join(mvreg(delta)); + attr_reg.join(mvreg(delta)); atts_deltas.vec.emplace_back( - crdt_node_attr_to_msg(host_.local_agent_id(), node.id(), node.id(), k, std::move(delta))); + crdt_node_attr_to_msg(host_.local_agent_id(), node.id, node.id, k, std::move(delta))); } } auto it_a = iter.begin(); @@ -468,10 +468,10 @@ std::tuple> CRDTSyncEngine::update_node_ra const std::string& k = it_a->first; if (host_.is_attribute_ignored(k)) { it_a = iter.erase(it_a); - } else if (!node.attrs().contains(k)) { + } else if (!node.attrs.contains(k)) { auto delta = it_a->second.reset(); atts_deltas.vec.emplace_back( - crdt_node_attr_to_msg(node.agent_id(), node.id(), node.id(), k, std::move(delta))); + crdt_node_attr_to_msg(node.agent_id, node.id, node.id, k, std::move(delta))); it_a = iter.erase(it_a); } else { ++it_a; @@ -486,14 +486,14 @@ std::tuple> CRDTSyncEngine::update_node_ra } std::tuple, std::optional, std::vector> -CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) +CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDT::Node& node) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::delete_node_raw"); std::vector deleted_edges; std::vector delta_vec; - for (const auto& v : node.fano()) { + for (const auto& v : node.fano) { deleted_edges.emplace_back(to_user_edge(v.second.read_reg())); } auto delta = nodes_[id].reset(); @@ -508,15 +508,15 @@ CRDTSyncEngine::delete_node_raw(uint64_t id, const CRDTNode& node) { if (!nodes_.contains(from)) continue; auto& visited_node = nodes_.at(from).read_reg(); - deleted_edges.emplace_back(to_user_edge(visited_node.fano().at({id, type}).read_reg())); - auto delta_fano = visited_node.fano().at({id, type}).reset(); + deleted_edges.emplace_back(to_user_edge(visited_node.fano.at({id, type}).read_reg())); + auto delta_fano = visited_node.fano.at({id, type}).reset(); delta_vec.emplace_back(crdt_edge_to_msg(host_.local_agent_id(), from, id, type, std::move(delta_fano))); - visited_node.fano().erase({id, type}); + visited_node.fano.erase({id, type}); host_.update_maps_edge_delete(from, id, type); } } - host_.update_maps_node_delete(id, node.type(), collect_outgoing_edge_keys(node.fano())); + host_.update_maps_node_delete(id, node.type, collect_outgoing_edge_keys(node.fano)); return {true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec)}; } @@ -525,9 +525,9 @@ std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint6 { if (nodes_.contains(from)) { auto& node = nodes_.at(from).read_reg(); - if (node.fano().contains({to, key})) { - auto delta = node.fano().at({to, key}).reset(); - node.fano().erase({to, key}); + if (node.fano.contains({to, key})) { + auto delta = node.fano.at({to, key}).reset(); + node.fano.erase({to, key}); host_.update_maps_edge_delete(from, to, key); return crdt_edge_to_msg(host_.local_agent_id(), from, to, key, std::move(delta)); } @@ -536,7 +536,7 @@ std::optional CRDTSyncEngine::delete_edge_raw(uint64_t from, uint6 } std::tuple, std::optional> -CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint64_t to) +CRDTSyncEngine::insert_or_assign_edge_raw(CRDT::Edge&& attrs, uint64_t from, uint64_t to) { CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::insert_or_assign_edge_raw"); std::optional delta_edge; @@ -545,28 +545,28 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 if (nodes_.contains(from)) { auto& node = nodes_.at(from).read_reg(); - auto fano_it = node.fano().find({to, attrs.type()}); - if (fano_it != node.fano().end()) + auto fano_it = node.fano.find({to, attrs.type}); + if (fano_it != node.fano.end()) { MvregEdgeAttrVec atts_deltas; - auto& iter_edge = fano_it->second.read_reg().attrs(); - for (auto& [k, att] : attrs.attrs()) { - auto& attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; + auto& iter_edge = fano_it->second.read_reg().attrs; + for (auto& [k, att] : attrs.attrs) { + auto& attr_reg = iter_edge.try_emplace(k, mvreg()).first->second; if (attr_reg.empty() || att.read_reg() != attr_reg.read_reg()) { auto delta = attr_reg.write(std::move(att.read_reg())); - attr_reg.join(mvreg(delta)); + attr_reg.join(mvreg(delta)); atts_deltas.vec.emplace_back( - crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type(), k, std::move(delta))); + crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type, k, std::move(delta))); } } auto it = iter_edge.begin(); while (it != iter_edge.end()) { - if (!attrs.attrs().contains(it->first)) { + if (!attrs.attrs.contains(it->first)) { std::string att = it->first; auto delta = it->second.reset(); it = iter_edge.erase(it); atts_deltas.vec.emplace_back( - crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type(), std::move(att), std::move(delta))); + crdt_edge_attr_to_msg(host_.local_agent_id(), from, from, to, attrs.type, std::move(att), std::move(delta))); } else { ++it; } @@ -574,10 +574,10 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 return {true, {}, std::move(atts_deltas)}; } else { - std::string att_type = attrs.type(); - auto& edge_reg = node.fano()[{to, attrs.type()}]; + std::string att_type = attrs.type; + auto& edge_reg = node.fano[{to, attrs.type}]; auto delta = edge_reg.write(std::move(attrs)); - edge_reg.join(mvreg(delta)); + edge_reg.join(mvreg(delta)); host_.update_maps_edge_insert(from, to, att_type); return {true, crdt_edge_to_msg(host_.local_agent_id(), from, to, std::move(att_type), std::move(delta)), {}}; } @@ -585,13 +585,13 @@ CRDTSyncEngine::insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint6 return {false, {}, {}}; } -bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta) +bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta) { CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_edge"); bool signal = false; auto& node = nodes_.at(from).read_reg(); - auto& fanout = node.fano(); - std::optional prev = {}; + auto& fanout = node.fano; + std::optional prev = {}; if (auto it = fanout.find({to, type}); it != fanout.end() && !it->second.empty()) { prev = it->second.read_reg(); } @@ -609,11 +609,11 @@ bool CRDTSyncEngine::process_delta_edge(uint64_t from, uint64_t to, const std::s return signal; } -void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr) +void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr) { CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_node_attr"); auto& n = nodes_.at(id).read_reg(); - auto& attrs = n.attrs(); + auto& attrs = n.attrs; auto& attr_reg = attrs[att_name]; auto d_empty = attr.empty(); attr_reg.join(std::move(attr)); @@ -622,11 +622,11 @@ void CRDTSyncEngine::process_delta_node_attr(uint64_t id, const std::string& att } } -void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr) +void CRDTSyncEngine::process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr) { CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::process_delta_edge_attr"); - auto& n = nodes_.at(from).read_reg().fano().at({to, type}).read_reg(); - auto& attrs = n.attrs(); + auto& n = nodes_.at(from).read_reg().fano.at({to, type}).read_reg(); + auto& attrs = n.attrs; auto& attr_reg = attrs[att_name]; auto d_empty = attr.empty(); attr_reg.join(std::move(attr)); @@ -640,7 +640,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) CORTEX_PROFILE_ZONE_CS("CRDTSyncEngine::join_delta_node"); const auto log_level = host_.get_log_level(); - std::optional maybe_deleted_node = {}; + std::optional maybe_deleted_node = {}; try { if (!protocol_version_matches(log_level, "DSR_NODE", mvreg.protocol_version)) { return; @@ -690,7 +690,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) if (timestamp < timestamp_edge) { if (process_delta_edge(id, to, type, std::move(delta))) map_new_to_edges.emplace(to, type); } - if (nodes_.contains(id) and nodes_.at(id).read_reg().fano().contains({to, type})) { + if (nodes_.contains(id) and nodes_.at(id).read_reg().fano.contains({to, type})) { decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); @@ -714,7 +714,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) if (timestamp < timestamp_edge) { if (process_delta_edge(from, id, type, std::move(delta))) map_new_from_edges.emplace(from, id, type); } - if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({id, type})) { + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano.contains({id, type})) { decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); @@ -745,13 +745,13 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) } host_.update_maps_node_delete( id, - maybe_deleted_node.has_value() ? std::optional{maybe_deleted_node->type()} : std::nullopt, - maybe_deleted_node.has_value() ? collect_outgoing_edge_keys(maybe_deleted_node->fano()) : SyncEngineHost::EdgeKeyList{}); + maybe_deleted_node.has_value() ? std::optional{maybe_deleted_node->type} : std::nullopt, + maybe_deleted_node.has_value() ? collect_outgoing_edge_keys(maybe_deleted_node->fano) : SyncEngineHost::EdgeKeyList{}); delete_unprocessed_deltas(); } else { const auto& reg = nodes_.at(id).read_reg(); - current_type = reg.type(); - host_.update_maps_node_insert(reg.id(), reg.name(), reg.type(), collect_outgoing_edge_keys(reg.fano())); + current_type = reg.type; + host_.update_maps_node_insert(reg.id, reg.name, reg.type, collect_outgoing_edge_keys(reg.fano)); consume_unprocessed_deltas(); } signal = !d_empty; @@ -764,7 +764,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) if (signal) { host_.on_remote_node_updated(id, current_type, mvreg.agent_id); if (const auto* current = get_node_ptr(id); current != nullptr) { - for (const auto& [k, v] : current->fano()) { + for (const auto& [k, v] : current->fano) { host_.on_remote_edge_updated(id, k.first, k.second, mvreg.agent_id); } } @@ -776,7 +776,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) ? std::make_optional(to_user_node(*maybe_deleted_node)) : std::nullopt; std::vector deleted_edges_user; if (maybe_deleted_node.has_value()) { - for (const auto& [key, mvreg_edge] : maybe_deleted_node->fano()) { + for (const auto& [key, mvreg_edge] : maybe_deleted_node->fano) { deleted_edges_user.emplace_back(to_user_edge(mvreg_edge.read_reg())); } } @@ -947,7 +947,7 @@ std::optional CRDTSyncEngine::join_delta_edge_attr(MvregEdgeAttrMsg auto d_empty = crdt_delta.empty(); { CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_delta_edge_attr crdt merge"); - if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({to, type})) + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano.contains({to, type})) { process_delta_edge_attr(from, to, type, att_name, std::move(crdt_delta)); std::erase_if(unprocessed_delta_edge_att_, @@ -985,7 +985,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) return; } - std::vector, std::optional>> updates; + std::vector, std::optional>> updates; uint64_t id{0}, timestamp{0}; uint32_t agent_id_ch{0}; @@ -1022,7 +1022,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) if (timestamp < timestamp_edge) { process_delta_edge(id, to, type, std::move(delta)); } - if (nodes_.contains(id) and nodes_.at(id).read_reg().fano().contains({to, type})) { + if (nodes_.contains(id) and nodes_.at(id).read_reg().fano.contains({to, type})) { decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); @@ -1046,7 +1046,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) if (timestamp < timestamp_edge) { process_delta_edge(from, id, type, std::move(delta)); } - if (nodes_.contains(from) and nodes_.at(from).read_reg().fano().contains({id, type})) { + if (nodes_.contains(from) and nodes_.at(from).read_reg().fano.contains({id, type})) { decltype(unprocessed_delta_edge_att_)::node_type node_handle_edge_att = unprocessed_delta_edge_att_.extract(att_key); while (!node_handle_edge_att.empty()) { auto &[att_name, delta, timestamp_edge_att] = node_handle_edge_att.mapped(); @@ -1069,7 +1069,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) bool mv_empty = mv.empty(); agent_id_ch = val.agent_id; auto it = nodes_.find(k); - std::optional nd = + std::optional nd = (it != nodes_.end() and !it->second.empty()) ? std::make_optional(it->second.read_reg()) : std::nullopt; id = k; if (host_.is_node_deleted(k)) { @@ -1078,20 +1078,20 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) continue; } if (it == nodes_.end()) { - it = nodes_.emplace(k, mvreg{}).first; + it = nodes_.emplace(k, mvreg{}).first; } it->second.join(std::move(mv)); if (mv_empty or it->second.empty()) { host_.update_maps_node_delete( k, - nd.has_value() ? std::optional{nd->type()} : std::nullopt, - nd.has_value() ? collect_outgoing_edge_keys(nd->fano()) : SyncEngineHost::EdgeKeyList{}); + nd.has_value() ? std::optional{nd->type} : std::nullopt, + nd.has_value() ? collect_outgoing_edge_keys(nd->fano) : SyncEngineHost::EdgeKeyList{}); updates.emplace_back(false, k, "", std::nullopt, std::nullopt); delete_unprocessed_deltas(); } else { const auto& reg = it->second.read_reg(); - host_.update_maps_node_insert(reg.id(), reg.name(), reg.type(), collect_outgoing_edge_keys(reg.fano())); - updates.emplace_back(true, k, reg.type(), nd, reg); + host_.update_maps_node_insert(reg.id, reg.name, reg.type, collect_outgoing_edge_keys(reg.fano)); + updates.emplace_back(true, k, reg.type, nd, reg); consume_unprocessed_deltas(); } } @@ -1100,11 +1100,11 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) CORTEX_PROFILE_DETAIL_N("CRDTSyncEngine::join_full_graph emit phase"); for (auto &[signal, node_id, type, nd, current_nd] : updates) { if (signal) { - if (!nd.has_value() || nd->attrs() != current_nd->attrs()) { + if (!nd.has_value() || nd->attrs != current_nd->attrs) { host_.on_remote_node_updated(node_id, type, agent_id_ch); } else if (nd.value() != *current_nd) { - const auto& iter = current_nd->fano(); - for (const auto &[k, v] : nd->fano()) { + const auto& iter = current_nd->fano; + for (const auto &[k, v] : nd->fano) { if (!iter.contains(k)) { std::optional del_edge = (v.dk.ds.size() > 0) ? std::make_optional(to_user_edge(v.read_reg())) : std::nullopt; @@ -1112,7 +1112,7 @@ void CRDTSyncEngine::join_full_graph(OrMap&& full_graph) } } for (const auto &[k, v] : iter) { - if (auto it = nd->fano().find(k); it == nd->fano().end() or it->second != v) + if (auto it = nd->fano.find(k); it == nd->fano.end() or it->second != v) host_.on_remote_edge_updated(node_id, k.first, k.second, agent_id_ch); } } diff --git a/api/dsr_utils.cpp b/api/dsr_utils.cpp index 30a6276a..3f661038 100644 --- a/api/dsr_utils.cpp +++ b/api/dsr_utils.cpp @@ -123,7 +123,7 @@ void Utilities::read_from_json_file(const std::string &json_file_path, const st uint64_t srcn = link_obj.value("src").toString().toULongLong(); uint64_t dstn = link_obj.value("dst").toString().toULongLong(); std::string edgeName = link_obj.value("label").toString().toStdString(); - std::map attrs; + std::map attrs; Edge edge; edge.to(dstn); diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 9c064dd7..4069d44b 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -340,11 +340,11 @@ namespace DSR elem.attrs().insert_or_assign(name::attr_name.data(), at); } else { - CRDTAttribute at; + Attribute at; at.value(std::forward(att_value)); at.timestamp(get_unix_timestamp()); if (elem.attrs().find(name::attr_name.data()) == elem.attrs().end()) { - mvreg mv; + mvreg mv; elem.attrs().insert(make_pair(name::attr_name, mv)); } elem.attrs().at(name::attr_name.data()).write(at); @@ -364,11 +364,11 @@ namespace DSR Attribute at(std::forward(att_value), get_unix_timestamp(), agent_id); elem.attrs().insert_or_assign(att_name, at); } else { - CRDTAttribute at; + Attribute at; at.value(std::forward(att_value)); at.timestamp(get_unix_timestamp()); if (elem.attrs().find(att_name) == elem.attrs().end()) { - mvreg mv; + mvreg mv; elem.attrs().insert(make_pair(att_name, mv)); } elem.attrs().at(att_name).write(at); diff --git a/api/include/dsr/api/dsr_crdt_sync_engine.h b/api/include/dsr/api/dsr_crdt_sync_engine.h index d9939fa8..c2eb446b 100644 --- a/api/include/dsr/api/dsr_crdt_sync_engine.h +++ b/api/include/dsr/api/dsr_crdt_sync_engine.h @@ -14,7 +14,7 @@ namespace DSR { class CRDTSyncEngine final : public SyncEngine { public: - using Nodes = std::unordered_map>; + using Nodes = std::unordered_map>; friend class DSRGraph; friend class RT_API; @@ -50,18 +50,18 @@ class CRDTSyncEngine final : public SyncEngine FullGraphMessage export_full_graph() const override; private: - const CRDTNode* get_node_ptr(uint64_t id) const; - std::optional get_crdt_node(uint64_t id) const; - const CRDTEdge* get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const; - std::optional get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const; + const CRDT::Node* get_node_ptr(uint64_t id) const; + std::optional get_crdt_node(uint64_t id) const; + const CRDT::Edge* get_crdt_edge_ptr(uint64_t from, uint64_t to, const std::string& key) const; + std::optional get_crdt_edge(uint64_t from, uint64_t to, const std::string& key) const; - std::tuple> insert_node_raw(CRDTNode&& node); - std::tuple> update_node_raw(CRDTNode&& node); + std::tuple> insert_node_raw(CRDT::Node&& node); + std::tuple> update_node_raw(CRDT::Node&& node); std::tuple, std::optional, std::vector> - delete_node_raw(uint64_t id, const CRDTNode& node); + delete_node_raw(uint64_t id, const CRDT::Node& node); std::optional delete_edge_raw(uint64_t from, uint64_t to, const std::string& key); std::tuple, std::optional> - insert_or_assign_edge_raw(CRDTEdge&& attrs, uint64_t from, uint64_t to); + insert_or_assign_edge_raw(CRDT::Edge&& attrs, uint64_t from, uint64_t to); void join_delta_node(MvregNodeMsg&& mvreg); void join_delta_edge(MvregEdgeMsg&& mvreg); @@ -71,16 +71,16 @@ class CRDTSyncEngine final : public SyncEngine std::map export_mvreg_map() const; - bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta); - void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr); - void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr); + bool process_delta_edge(uint64_t from, uint64_t to, const std::string& type, mvreg&& delta); + void process_delta_node_attr(uint64_t id, const std::string& att_name, mvreg&& attr); + void process_delta_edge_attr(uint64_t from, uint64_t to, const std::string& type, const std::string& att_name, mvreg&& attr); SyncEngineHost& host_; Nodes nodes_; - std::unordered_multimap, uint64_t>> unprocessed_delta_node_att_; - std::unordered_multimap, uint64_t>> unprocessed_delta_edge_from_; - std::unordered_multimap, uint64_t>> unprocessed_delta_edge_to_; - std::unordered_multimap, std::tuple, uint64_t>, hash_tuple> unprocessed_delta_edge_att_; + std::unordered_multimap, uint64_t>> unprocessed_delta_node_att_; + std::unordered_multimap, uint64_t>> unprocessed_delta_edge_from_; + std::unordered_multimap, uint64_t>> unprocessed_delta_edge_to_; + std::unordered_multimap, std::tuple, uint64_t>, hash_tuple> unprocessed_delta_edge_att_; }; } // namespace DSR diff --git a/benchmarks/latency/crdt_join_bench.cpp b/benchmarks/latency/crdt_join_bench.cpp index 28bedaca..dcf79390 100644 --- a/benchmarks/latency/crdt_join_bench.cpp +++ b/benchmarks/latency/crdt_join_bench.cpp @@ -10,8 +10,8 @@ using namespace DSR::Benchmark; // Create a test attribute -static DSR::CRDTAttribute make_test_attribute(uint32_t agent_id, int32_t value) { - DSR::CRDTAttribute attr; +static DSR::Attribute make_test_attribute(uint32_t agent_id, int32_t value) { + DSR::Attribute attr; attr.value(value); attr.timestamp(bench_now()); attr.agent_id(agent_id); @@ -27,7 +27,7 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { // ── mvreg write ─────────────────────────────────────────────────────────── { - mvreg reg; + mvreg reg; reg.id = 100; int i = 0; @@ -43,7 +43,7 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { // ── mvreg join (same agent) ─────────────────────────────────────────────── { - mvreg reg; + mvreg reg; reg.id = 100; auto init_attr = make_test_attribute(100, 0); reg.write(init_attr); @@ -51,7 +51,7 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { auto bench = make_latency_bench(); bench.run("mvreg_join_same_agent", [&] { - mvreg delta_reg; + mvreg delta_reg; delta_reg.id = 100; auto new_attr = make_test_attribute(100, i++); auto delta = delta_reg.write(new_attr); @@ -67,13 +67,13 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { auto bench = make_latency_bench(); bench.run("mvreg_join_different_agent", [&] { - mvreg reg; + mvreg reg; reg.id = 100; auto attr = make_test_attribute(100, 0); auto delta = reg.write(attr); uint32_t other_agent = 200 + (i % 10); - mvreg delta_reg; + mvreg delta_reg; delta_reg.id = other_agent; delta_reg.join(std::move(delta)); auto new_attr = make_test_attribute(other_agent, i * 2); @@ -88,7 +88,7 @@ TEST_CASE("CRDT mvreg operations", "[CRDT][MVREG][BASELINE]") { // ── mvreg read ──────────────────────────────────────────────────────────── { - mvreg reg; + mvreg reg; reg.id = 100; auto attr = make_test_attribute(100, 42); reg.write(attr); diff --git a/benchmarks/latency/type_conversion_bench.cpp b/benchmarks/latency/type_conversion_bench.cpp index 35117836..de8ef7a2 100644 --- a/benchmarks/latency/type_conversion_bench.cpp +++ b/benchmarks/latency/type_conversion_bench.cpp @@ -88,7 +88,7 @@ TEST_CASE("CRDT type conversion latency", "[LATENCY][CONVERSION][BASELINE]") { } { - CRDTNode crdt_node = user_node_to_crdt(node); + CRDT::Node crdt_node = user_node_to_crdt(node); auto bench = make_latency_bench(); bench.run(std::string("crdt_node_to_user_") + label, [&] { @@ -112,7 +112,7 @@ TEST_CASE("CRDT type conversion latency", "[LATENCY][CONVERSION][BASELINE]") { } { - CRDTEdge crdt_edge = user_edge_to_crdt(edge); + CRDT::Edge crdt_edge = user_edge_to_crdt(edge); auto bench = make_latency_bench(); bench.run(std::string("crdt_edge_to_user_") + label, [&] { diff --git a/core/include/dsr/core/crdt/delta_crdt.h b/core/include/dsr/core/crdt/delta_crdt.h index a839dd5b..bdeceab8 100644 --- a/core/include/dsr/core/crdt/delta_crdt.h +++ b/core/include/dsr/core/crdt/delta_crdt.h @@ -10,14 +10,28 @@ Reimplementation from https://github.com/CBaquero/delta-enabled-crdts #include #include #include +#include +#include #include "dsr/core/serialization/serializable.h" #include "dsr/core/profiling.h" using key_type = uint64_t; +namespace detail { +template +decltype(auto) agent_id_of(T&& value) +{ + if constexpr (requires { std::forward(value).agent_id; }) { + return std::forward(value).agent_id; + } else { + return std::forward(value).agent_id(); + } +} +} // namespace detail + // Autonomous causal context, for context sharing in maps -class dot_context : public ISerializable { +struct dot_context : public ISerializable { public: std::map cc; // Compact causal context @@ -48,7 +62,6 @@ class dot_context : public ISerializable { dc = std::move(dc_); } - [[nodiscard]] bool dotin(const std::pair &d) const { const auto itm = cc.find(d.first); if (itm != cc.end() && d.second <= itm->second) return true; @@ -321,7 +334,7 @@ class dot_kernel : public ISerializable> { } else if (it != ds.end() && ito != o.ds.end()) { // dot in both //replace in case of conflict if the agent id has a lower value - if (it->second.agent_id() > ito->second.agent_id() && *it != *ito) { + if (detail::agent_id_of(it->second) > detail::agent_id_of(ito->second) && *it != *ito) { it = ds.erase(it); ds.insert(std::move(*ito)); } else { diff --git a/core/include/dsr/core/traits.h b/core/include/dsr/core/traits.h index 877f0026..b2576728 100644 --- a/core/include/dsr/core/traits.h +++ b/core/include/dsr/core/traits.h @@ -14,8 +14,10 @@ namespace DSR { class Node; class Edge; - class CRDTNode; - class CRDTEdge; + namespace CRDT { + class Node; + class Edge; + } namespace LWW { class NodeState; class EdgeState; @@ -52,7 +54,7 @@ concept allowed_types = one_of::value; template -concept any_node_or_edge = one_of::value;; +concept any_node_or_edge = one_of::value;; template concept node_or_edge = one_of::value;; @@ -61,7 +63,7 @@ template concept lww_node_or_edge = one_of::value; template -concept crdt_node_or_edge = one_of::value;; +concept crdt_node_or_edge = one_of::value;; //Attributes requires valid types to be defined diff --git a/core/include/dsr/core/types/common_types.h b/core/include/dsr/core/types/common_types.h index 2407d57c..d1a9c529 100644 --- a/core/include/dsr/core/types/common_types.h +++ b/core/include/dsr/core/types/common_types.h @@ -23,13 +23,16 @@ namespace DSR { "UINT64_VEC", "FLOAT_VEC2", "FLOAT_VEC3", "FLOAT_VEC4", "FLOAT_VEC6"}; - using ValType = std::variant, bool, std::vector, uint32_t, uint64_t, double, std::vector, std::array, std::array, std::array, std::array>; + //Compatibility. Will be removed at some point. + using ValType = Value; + enum Types : uint32_t { STRING = 0, INT = 1, @@ -55,39 +58,14 @@ namespace DSR { Attribute() = default; ~Attribute() = default; - Attribute(const ValType &value, uint64_t timestamp, uint32_t agent_id) - : m_value(ValType(value)), m_timestamp(timestamp), m_agent_id(agent_id) + Attribute(const Value &value, uint64_t timestamp, uint32_t agent_id) + : m_value(Value(value)), m_timestamp(timestamp), m_agent_id(agent_id) {} - Attribute (const Attribute& attr) - { - m_timestamp = attr.timestamp(); - m_agent_id = attr.agent_id(); - m_value = attr.m_value; - } - - Attribute (Attribute&& attr) noexcept - { - m_timestamp = attr.timestamp(); - m_agent_id = attr.agent_id(); - m_value = std::move(attr.m_value); - } - - Attribute& operator= (const Attribute& attr) - { - m_timestamp = attr.timestamp(); - m_agent_id = attr.agent_id(); - m_value = attr.m_value; - return *this; - } - - Attribute& operator= (Attribute&& attr) noexcept - { - m_timestamp = attr.timestamp(); - m_agent_id = attr.agent_id(); - m_value = std::move(attr.m_value); - return *this; - } + Attribute (const Attribute& attr) = default; + Attribute (Attribute&& attr) noexcept = default; + Attribute& operator= (const Attribute& attr) = default; + Attribute& operator= (Attribute&& attr) noexcept = default; // ---- ISerializable implementation ---- void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; @@ -99,81 +77,64 @@ namespace DSR { ////////////////////// [[nodiscard]] uint64_t timestamp() const; - void timestamp(uint64_t t); - [[nodiscard]] uint32_t agent_id() const; - void agent_id(uint32_t agent_id); - [[nodiscard]] std::size_t selected() const; /////////////////////// // Variant ////////////////////// - void value(const ValType &value); - - void value(ValType &&value); + void value(const Value &value); + void value(Value &&value); - [[nodiscard]] const ValType &value() const; - - [[nodiscard]] ValType& value(); + [[nodiscard]] const Value &value() const; + [[nodiscard]] Value& value(); /////////////////////// // String ////////////////////// [[nodiscard]] std::string &str(); - [[nodiscard]] const std::string &str() const; - void str(const std::string &str); - void str(std::string &&str); /////////////////////// // int32 ////////////////////// void dec(int32_t dec); - [[nodiscard]] int32_t dec() const; /////////////////////// // uint32 ////////////////////// void uint(uint32_t uint); - [[nodiscard]] uint32_t uint() const; /////////////////////// // uint64 ////////////////////// void uint64(uint64_t uint); - [[nodiscard]] uint64_t uint64() const; /////////////////////// // float ////////////////////// void fl(float fl); - [[nodiscard]] float fl() const; /////////////////////// // double ////////////////////// void dob(double dob); - [[nodiscard]] double dob() const; /////////////////////// // vector ////////////////////// void float_vec(const std::vector &float_vec); - void float_vec(std::vector &&float_vec); - [[nodiscard]] const std::vector &float_vec() const; - std::vector &float_vec(); /////////////////////// @@ -187,58 +148,44 @@ namespace DSR { // vector ////////////////////// void byte_vec(const std::vector &float_vec); - void byte_vec(std::vector &&float_vec); - [[nodiscard]] const std::vector &byte_vec() const; - [[nodiscard]] std::vector &byte_vec(); /////////////////////// // vector ////////////////////// void u64_vec(const std::vector &uint64_vec); - void u64_vec(std::vector &&uint64_vec); - [[nodiscard]] const std::vector &u64_vec() const; - [[nodiscard]] std::vector &u64_vec(); /////////////////////// // array ////////////////////// void vec2(const std::array &vec_float2); - [[nodiscard]] const std::array &vec2() const; - [[nodiscard]] std::array &vec2(); /////////////////////// // array ////////////////////// void vec3(const std::array &vec_float3); - [[nodiscard]] const std::array &vec3() const; - [[nodiscard]] std::array &vec3(); /////////////////////// // array ////////////////////// void vec4(const std::array &vec_float4); - [[nodiscard]] const std::array &vec4() const; - [[nodiscard]] std::array &vec4(); /////////////////////// // array ////////////////////// void vec6(const std::array &vec_float6); - [[nodiscard]] const std::array &vec6() const; - [[nodiscard]] std::array &vec6(); /////////////////////// @@ -318,39 +265,19 @@ namespace DSR { return os; } - bool operator==(const Attribute &rhs) const - { - return m_value == rhs.m_value; - } - - bool operator!=(const Attribute &rhs) const - { - return !(rhs == *this); - } - - bool operator<(const Attribute &rhs) const - { - return m_value < rhs.m_value; - } - - bool operator>(const Attribute &rhs) const - { - return rhs < *this; - } - - bool operator<=(const Attribute &rhs) const - { - return !(rhs < *this); - } - - bool operator>=(const Attribute &rhs) const - { - return !(*this < rhs); - } + bool operator==(const Attribute& rhs) const + { + return m_value == rhs.m_value; + } + + bool operator<(const Attribute& rhs) const + { + return m_value < rhs.m_value; + } private: - ValType m_value; + Value m_value; uint64_t m_timestamp = 0; uint32_t m_agent_id = 0; }; diff --git a/core/include/dsr/core/types/crdt_io.h b/core/include/dsr/core/types/crdt_io.h index edb23fff..1e8c31f9 100644 --- a/core/include/dsr/core/types/crdt_io.h +++ b/core/include/dsr/core/types/crdt_io.h @@ -10,7 +10,7 @@ namespace DSR { -inline MvregNodeMsg crdt_node_to_msg(uint32_t agent_id, uint64_t id, mvreg&& data) +inline MvregNodeMsg crdt_node_to_msg(uint32_t agent_id, uint64_t id, mvreg&& data) { MvregNodeMsg msg; msg.dk = std::move(data); @@ -22,7 +22,7 @@ inline MvregNodeMsg crdt_node_to_msg(uint32_t agent_id, uint64_t id, mvreg -inline MvregEdgeMsg crdt_edge_to_msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) +inline MvregEdgeMsg crdt_edge_to_msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) { MvregEdgeMsg msg; msg.dk = std::move(data); @@ -37,7 +37,7 @@ inline MvregEdgeMsg crdt_edge_to_msg(uint32_t agent_id, uint64_t from, uint64_t } template -inline MvregNodeAttrMsg crdt_node_attr_to_msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) +inline MvregNodeAttrMsg crdt_node_attr_to_msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) { MvregNodeAttrMsg msg; msg.dk = std::move(data); @@ -52,7 +52,7 @@ inline MvregNodeAttrMsg crdt_node_attr_to_msg(uint32_t agent_id, uint64_t id, ui template inline MvregEdgeAttrMsg crdt_edge_attr_to_msg(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, - TS&& type, AS&& attr, mvreg&& data) + TS&& type, AS&& attr, mvreg&& data) { MvregEdgeAttrMsg msg; msg.dk = std::move(data); @@ -67,45 +67,45 @@ inline MvregEdgeAttrMsg crdt_edge_attr_to_msg(uint32_t agent_id, uint64_t id, ui return msg; } -inline CRDTEdge user_edge_to_crdt(Edge&& edge) +inline CRDT::Edge user_edge_to_crdt(Edge&& edge) { - CRDTEdge crdt_edge; + CRDT::Edge crdt_edge; - crdt_edge.agent_id(edge.agent_id()); - crdt_edge.from(edge.from()); - crdt_edge.to(edge.to()); - crdt_edge.type(std::move(edge.type())); + crdt_edge.agent_id = edge.agent_id(); + crdt_edge.from = edge.from(); + crdt_edge.to = edge.to(); + crdt_edge.type = std::move(edge.type()); for (auto&& [k, v] : edge.attrs()) { - mvreg mv; + mvreg mv; mv.write(std::move(v)); - crdt_edge.attrs().emplace(k, std::move(mv)); + crdt_edge.attrs.emplace(k, std::move(mv)); } return crdt_edge; } -inline CRDTEdge user_edge_to_crdt(const Edge& edge) +inline CRDT::Edge user_edge_to_crdt(const Edge& edge) { - CRDTEdge crdt_edge; + CRDT::Edge crdt_edge; - crdt_edge.agent_id(edge.agent_id()); - crdt_edge.from(edge.from()); - crdt_edge.to(edge.to()); - crdt_edge.type(edge.type()); + crdt_edge.agent_id = edge.agent_id(); + crdt_edge.from = edge.from(); + crdt_edge.to = edge.to(); + crdt_edge.type = edge.type(); for (auto& [k, v] : edge.attrs()) { - mvreg mv; + mvreg mv; mv.write(v); - crdt_edge.attrs().emplace(k, std::move(mv)); + crdt_edge.attrs.emplace(k, std::move(mv)); } return crdt_edge; } -inline Edge to_user_edge(const CRDTEdge& edge) +inline Edge to_user_edge(const CRDT::Edge& edge) { - Edge out(edge.to(), edge.from(), edge.type(), {}, edge.agent_id()); + Edge out(edge.to, edge.from, edge.type, {}, edge.agent_id); auto& attrs = out.attrs(); - for (const auto& [name, attr] : edge.attrs()) { + for (const auto& [name, attr] : edge.attrs) { if (!attr.empty()) { attrs.emplace(name, attr.read_reg()); } @@ -113,21 +113,21 @@ inline Edge to_user_edge(const CRDTEdge& edge) return out; } -inline Node to_user_node(const CRDTNode& node) +inline Node to_user_node(const CRDT::Node& node) { - Node out(node.agent_id(), node.type()); - out.id(node.id()); - out.name(node.name()); + Node out(node.agent_id, node.type); + out.id(node.id); + out.name(node.name); auto& attrs = out.attrs(); - for (const auto& [name, attr] : node.attrs()) { + for (const auto& [name, attr] : node.attrs) { if (!attr.empty()) { attrs.emplace(name, attr.read_reg()); } } auto& fano = out.fano(); - for (const auto& [key, edge] : node.fano()) { + for (const auto& [key, edge] : node.fano) { if (!edge.empty()) { fano.emplace(key, to_user_edge(edge.read_reg())); } @@ -136,48 +136,48 @@ inline Node to_user_node(const CRDTNode& node) return out; } -inline CRDTNode user_node_to_crdt(Node&& node) +inline CRDT::Node user_node_to_crdt(Node&& node) { - CRDTNode crdt_node; + CRDT::Node crdt_node; - crdt_node.agent_id(node.agent_id()); - crdt_node.id(node.id()); - crdt_node.type(std::move(node.type())); - crdt_node.name(std::move(node.name())); + crdt_node.agent_id = node.agent_id(); + crdt_node.id = node.id(); + crdt_node.type = std::move(node.type()); + crdt_node.name = std::move(node.name()); for (auto&& [k, val] : node.attrs()) { - mvreg mv; + mvreg mv; mv.write(std::move(val)); - crdt_node.attrs().emplace(k, std::move(mv)); + crdt_node.attrs.emplace(k, std::move(mv)); } for (auto& [k, v] : node.fano()) { - mvreg mv; + mvreg mv; mv.write(user_edge_to_crdt(std::move(v))); - crdt_node.fano().emplace(k, std::move(mv)); + crdt_node.fano.emplace(k, std::move(mv)); } return crdt_node; } -inline CRDTNode user_node_to_crdt(const Node& node) +inline CRDT::Node user_node_to_crdt(const Node& node) { - CRDTNode crdt_node; + CRDT::Node crdt_node; - crdt_node.agent_id(node.agent_id()); - crdt_node.id(node.id()); - crdt_node.type(node.type()); - crdt_node.name(node.name()); + crdt_node.agent_id = node.agent_id(); + crdt_node.id = node.id(); + crdt_node.type = node.type(); + crdt_node.name = node.name(); for (auto& [k, v] : node.attrs()) { - mvreg mv; + mvreg mv; mv.write(v); - crdt_node.attrs().emplace(k, std::move(mv)); + crdt_node.attrs.emplace(k, std::move(mv)); } for (auto& [k, v] : node.fano()) { - mvreg mv; + mvreg mv; mv.write(user_edge_to_crdt(v)); - crdt_node.fano().emplace(k, std::move(mv)); + crdt_node.fano.emplace(k, std::move(mv)); } return crdt_node; diff --git a/core/include/dsr/core/types/crdt_types.h b/core/include/dsr/core/types/crdt_types.h index 18a524ae..a075b345 100644 --- a/core/include/dsr/core/types/crdt_types.h +++ b/core/include/dsr/core/types/crdt_types.h @@ -14,240 +14,118 @@ #include "dsr/core/types/common_types.h" namespace DSR { +namespace CRDT { - typedef DSR::Attribute CRDTAttribute; - - class CRDTEdge : public ISerializable + struct Edge : public ISerializable { - public: - - CRDTEdge() : m_to(0), m_from(0), m_agent_id(0) {} - - ~CRDTEdge() = default; - - void to(uint64_t _to); - - [[nodiscard]] uint64_t to() const; - - void type(const std::string &type); - - void type(std::string &&type); - - [[nodiscard]] const std::string &type() const; - - [[nodiscard]] std::string &type(); - void from(uint64_t from); - - [[nodiscard]] uint64_t from() const; - - void attrs(const std::map> &attrs); - - void attrs(std::map> &&attrs); - - [[nodiscard]] const std::map> &attrs() const; - - [[nodiscard]] std::map> &attrs(); - - void agent_id(uint32_t agent_id); - - [[nodiscard]] uint32_t agent_id() const; + Edge() : to(0), from(0), agent_id(0) {} + ~Edge() = default; // ---- ISerializable implementation ---- void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; void deserialize_impl(eprosima::fastcdr::Cdr& cdr); size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const; - bool operator==(const CRDTEdge &rhs) const + bool operator==(const CRDT::Edge &rhs) const { if (this == &rhs) { return true; } - if (m_type != rhs.m_type || from() != rhs.from() || to() != rhs.to() || attrs() != rhs.attrs()) { + if (type != rhs.type || from != rhs.from || to != rhs.to || attrs != rhs.attrs) { return false; } return true; } - bool operator<(const CRDTEdge &rhs) const + bool operator<(const CRDT::Edge &rhs) const { if (this == &rhs) { return false; } - if (m_type < rhs.m_type) { + if (type < rhs.type) { return true; - } else if (rhs.m_type < m_type) { + } else if (rhs.type < type) { return false; } return false; } - bool operator!=(const CRDTEdge &rhs) const - { - return !operator==(rhs); - } - - bool operator<=(const CRDTEdge &rhs) const - { - return operator<(rhs) || operator==(rhs); - } - - bool operator>(const CRDTEdge &rhs) const + friend std::ostream &operator<<(std::ostream &output, const CRDT::Edge &rhs) { - return !operator<(rhs) && !operator==(rhs); - } - - bool operator>=(const CRDTEdge &rhs) const - { - return !operator<(rhs); - } - - friend std::ostream &operator<<(std::ostream &output, const CRDTEdge &rhs) - { - output << " CRDTEdge [" << rhs.m_type << ", from:" << std::to_string(rhs.from()) << "-> to:" << std::to_string(rhs.to()) + output << " CRDT::Edge [" << rhs.type << ", from:" << std::to_string(rhs.from) << "-> to:" << std::to_string(rhs.to) << " Attribs:["; - for (const auto &v : rhs.attrs()) + for (const auto &v : rhs.attrs) output << v.first << ":" << v.second << " - "; output << "]]"; return output; }; - private: - uint64_t m_to; - std::string m_type; - uint64_t m_from; - std::map> m_attrs; - uint32_t m_agent_id{}; + uint64_t to; + std::string type; + uint64_t from; + std::map> attrs; + uint32_t agent_id{}; }; - class CRDTNode : public ISerializable { - - public: - - CRDTNode() : m_id(0), m_agent_id(0) {} - - ~CRDTNode() = default; - - CRDTNode(const CRDTNode &x) - { - m_type = x.m_type; - m_name = x.m_name; - m_id = x.m_id; - m_agent_id = x.m_agent_id; - m_attrs = x.m_attrs; - m_fano = x.m_fano; - } - - void type(const std::string &type); - - void type(std::string &&type); - - [[nodiscard]] const std::string &type() const; - - [[nodiscard]] std::string &type(); - - void name(const std::string &name); - - void name(std::string &&name); - - [[nodiscard]] const std::string &name() const; - - [[nodiscard]] std::string &name(); - - void id(uint64_t id); - - [[nodiscard]] uint64_t id() const; - - void agent_id(uint32_t agent_id); - - [[nodiscard]] uint32_t agent_id() const; - - void attrs(const std::map> &attrs); - - void attrs(std::map> &&attrs); - - [[nodiscard]] std::map> &attrs() &; - - [[nodiscard]] const std::map> &attrs() const &; - - void fano(const std::map, mvreg> &fano); - - void fano(std::map, mvreg> &&fano); + struct Node : public ISerializable + { - [[nodiscard]] std::map, mvreg> &fano(); + Node() : id(0), agent_id(0) {} + ~Node() = default; - [[nodiscard]] const std::map, mvreg> &fano() const; + Node(const Node &x) = default; // ---- ISerializable implementation ---- void serialize_impl(eprosima::fastcdr::Cdr& cdr) const; void deserialize_impl(eprosima::fastcdr::Cdr& cdr); size_t serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const; - bool operator==(const CRDTNode &rhs) const + bool operator==(const CRDT::Node &rhs) const { if (this == &rhs) { return true; } - if (id() != rhs.id() || type() != rhs.type() || attrs() != rhs.attrs() || fano() != rhs.fano()) { + if (id != rhs.id || type != rhs.type || attrs != rhs.attrs || fano != rhs.fano) { return false; } return true; } - bool operator<(const CRDTNode &rhs) const + bool operator<(const CRDT::Node &rhs) const { if (this == &rhs) { return false; } - if (id() < rhs.id()) { + if (id < rhs.id) { return true; - } else if (rhs.id() < id()) { + } else if (rhs.id < id) { return false; } return false; } - bool operator!=(const CRDTNode &rhs) const - { - return !operator==(rhs); - } - - bool operator<=(const CRDTNode &rhs) const + friend std::ostream &operator<<(std::ostream &output, CRDT::Node &rhs) { - return operator<(rhs) || operator==(rhs); - } - - bool operator>(const CRDTNode &rhs) const - { - return !operator<(rhs) && !operator==(rhs); - } - - bool operator>=(const CRDTNode &rhs) const - { - return !operator<(rhs); - } - - friend std::ostream &operator<<(std::ostream &output, CRDTNode &rhs) - { - output << "CRDTNode: [" << std::to_string(rhs.id()) << "," << rhs.name() << "," << rhs.type() << "], Attribs:["; - for (const auto &v : rhs.attrs()) + output << "CRDT::Node: [" << std::to_string(rhs.id) << "," << rhs.name << "," << rhs.type << "], Attribs:["; + for (const auto &v : rhs.attrs) output << v.first << ":(" << v.second << ");"; output << "], FanOut:["; - for (auto &v : rhs.fano()) + for (auto &v : rhs.fano) output << "[ " << std::to_string(v.first.first) << " " << v.first.second << "] " << ":(" << v.second << ");"; output << "]"; return output; } - private: - std::string m_type; - std::string m_name; - uint64_t m_id{}; - uint32_t m_agent_id{}; - std::map> m_attrs; - std::map, mvreg> m_fano; - }; + std::string type; + std::string name; + uint64_t id{}; + uint32_t agent_id{}; + std::map> attrs; + std::map, mvreg> fano; + }; } +} #endif //DSR_CRDT_TYPES_H diff --git a/core/include/dsr/core/types/internal_types.h b/core/include/dsr/core/types/internal_types.h index db919fab..00c952de 100644 --- a/core/include/dsr/core/types/internal_types.h +++ b/core/include/dsr/core/types/internal_types.h @@ -1,6 +1,6 @@ #pragma once -#include "crdt_types.h" +#include "dsr/core/types/crdt_types.h" #include "dsr/core/serialization/serializable.h" #include #include @@ -58,11 +58,11 @@ namespace DSR { }; // ---- MvregNodeMsg -------------------------------------------------------- - // Delta or full mvreg plus routing metadata. + // Delta or full mvreg plus routing metadata. struct MvregNodeMsg : public ISerializable { - mvreg dk; + mvreg dk; uint64_t id{}; uint32_t agent_id{}; uint64_t timestamp{}; @@ -105,7 +105,7 @@ namespace DSR { struct MvregEdgeMsg : public ISerializable { - mvreg dk; + mvreg dk; uint64_t id{}; // "from" node id uint64_t to{}; uint64_t from{}; @@ -160,7 +160,7 @@ namespace DSR { struct MvregNodeAttrMsg : public ISerializable { - mvreg dk; + mvreg dk; uint64_t id{}; // publisher/delta id uint64_t node{}; // owning node std::string attr_name; @@ -211,7 +211,7 @@ namespace DSR { struct MvregEdgeAttrMsg : public ISerializable { - mvreg dk; + mvreg dk; uint64_t id{}; // "from" node id uint64_t from_node{}; uint64_t to_node{}; diff --git a/core/include/dsr/core/types/translator.h b/core/include/dsr/core/types/translator.h index 28d0df2e..8fdd022a 100644 --- a/core/include/dsr/core/types/translator.h +++ b/core/include/dsr/core/types/translator.h @@ -9,26 +9,26 @@ namespace DSR { -inline MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg&& data) +inline MvregNodeMsg CRDTNode_to_Msg(uint32_t agent_id, uint64_t id, mvreg&& data) { return crdt_node_to_msg(agent_id, id, std::move(data)); } template -inline MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) +inline MvregEdgeMsg CRDTEdge_to_Msg(uint32_t agent_id, uint64_t from, uint64_t to, S&& type, mvreg&& data) { return crdt_edge_to_msg(agent_id, from, to, std::forward(type), std::move(data)); } template -inline MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) +inline MvregNodeAttrMsg CRDTNodeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t node, S&& attr, mvreg&& data) { return crdt_node_attr_to_msg(agent_id, id, node, std::forward(attr), std::move(data)); } template inline MvregEdgeAttrMsg CRDTEdgeAttr_to_Msg(uint32_t agent_id, uint64_t id, uint64_t from, uint64_t to, - TS&& type, AS&& attr, mvreg&& data) + TS&& type, AS&& attr, mvreg&& data) { return crdt_edge_attr_to_msg(agent_id, id, from, to, std::forward(type), std::forward(attr), std::move(data)); } diff --git a/core/include/dsr/core/types/user_types.h b/core/include/dsr/core/types/user_types.h index 3d999d56..96a3ff52 100644 --- a/core/include/dsr/core/types/user_types.h +++ b/core/include/dsr/core/types/user_types.h @@ -7,8 +7,8 @@ #include #include -#include "type_checking/type_checker.h" -#include "common_types.h" +#include "dsr/core/types/type_checking/type_checker.h" +#include "dsr/core/types/common_types.h" #include @@ -104,11 +104,6 @@ namespace DSR { m_attrs == rhs.m_attrs; } - bool operator!=(const Edge &rhs) const - { - return !(rhs == *this); - } - bool operator<(const Edge &rhs) const { if (m_to < rhs.m_to) @@ -126,21 +121,6 @@ namespace DSR { return true; } - bool operator>(const Edge &rhs) const - { - return rhs < *this; - } - - bool operator<=(const Edge &rhs) const - { - return !(rhs < *this); - } - - bool operator>=(const Edge &rhs) const - { - return !(*this < rhs); - } - private: uint64_t m_to = 0; uint64_t m_from = 0; @@ -253,11 +233,6 @@ namespace DSR { m_fano == rhs.m_fano; } - bool operator!=(const Node &rhs) const - { - return !(rhs == *this); - } - bool operator<(const Node &rhs) const { if (m_id < rhs.m_id) @@ -275,22 +250,6 @@ namespace DSR { return true; } - bool operator>(const Node &rhs) const - { - return rhs < *this; - } - - bool operator<=(const Node &rhs) const - { - return !(rhs < *this); - } - - bool operator>=(const Node &rhs) const - { - return !(*this < rhs); - } - - private: uint64_t m_id = 0; std::string m_type; std::string m_name; diff --git a/core/types/common_types.cpp b/core/types/common_types.cpp index 5a308eb2..8dfe0b32 100644 --- a/core/types/common_types.cpp +++ b/core/types/common_types.cpp @@ -113,12 +113,12 @@ namespace DSR { return s; } - const ValType &Attribute::value() const + const Value &Attribute::value() const { return m_value; } - ValType& Attribute::value() + Value& Attribute::value() { return m_value; } @@ -138,12 +138,12 @@ namespace DSR { m_timestamp = t; } - void Attribute::value(const ValType &value) + void Attribute::value(const Value &value) { m_value = value; } - void Attribute::value(ValType &&value) + void Attribute::value(Value &&value) { m_value = std::move(value); } diff --git a/core/types/crdt_types.cpp b/core/types/crdt_types.cpp index f5e89530..19e6dd94 100644 --- a/core/types/crdt_types.cpp +++ b/core/types/crdt_types.cpp @@ -9,302 +9,129 @@ namespace DSR { - void CRDTEdge::to(uint64_t _to) + void CRDT::Edge::serialize_impl(eprosima::fastcdr::Cdr& cdr) const { - m_to = _to; - } - - uint64_t CRDTEdge::to() const - { - return m_to; - } - - void CRDTEdge::type(const std::string &type) - { - m_type = type; - } - - void CRDTEdge::type(std::string &&type) - { - m_type = std::move(type); - } - - const std::string &CRDTEdge::type() const - { - return m_type; - } - - std::string &CRDTEdge::type() - { - return m_type; - } - - void CRDTEdge::from(uint64_t from) - { - m_from = from; - } - - uint64_t CRDTEdge::from() const - { - return m_from; - } - - void CRDTEdge::attrs(const std::map> &attrs) - { - m_attrs = attrs; - } - - void CRDTEdge::attrs(std::map> &&attrs) - { - m_attrs = std::move(attrs); - } - - const std::map> &CRDTEdge::attrs() const - { - return m_attrs; - } - - std::map> &CRDTEdge::attrs() - { - return m_attrs; - } - - void CRDTEdge::agent_id(uint32_t agent_id) - { - m_agent_id = agent_id; - } - - uint32_t CRDTEdge::agent_id() const - { - return m_agent_id; - } - - void CRDTEdge::serialize_impl(eprosima::fastcdr::Cdr& cdr) const - { - cdr << m_to; - cdr << m_from; - cdr << m_type; - cdr << m_agent_id; + cdr << to; + cdr << from; + cdr << type; + cdr << agent_id; // serialize attrs map: uint32_t count, then key + value - auto count = static_cast(m_attrs.size()); + auto count = static_cast(attrs.size()); cdr << count; - for (const auto &[k, v] : m_attrs) { + for (const auto &[k, v] : attrs) { cdr << k; v.serialize(cdr); } } - void CRDTEdge::deserialize_impl(eprosima::fastcdr::Cdr& cdr) + void CRDT::Edge::deserialize_impl(eprosima::fastcdr::Cdr& cdr) { - cdr >> m_to; - cdr >> m_from; - cdr >> m_type; - cdr >> m_agent_id; + cdr >> to; + cdr >> from; + cdr >> type; + cdr >> agent_id; uint32_t count = 0; cdr >> count; - m_attrs.clear(); + attrs.clear(); for (uint32_t i = 0; i < count; ++i) { std::string key; cdr >> key; - mvreg val; + mvreg val; val.deserialize(cdr); - m_attrs.emplace(std::move(key), std::move(val)); + attrs.emplace(std::move(key), std::move(val)); } } - size_t CRDTEdge::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + size_t CRDT::Edge::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const { size_t size = 0; - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), m_to, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), m_from, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), m_type, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), m_agent_id, ca); - auto count = static_cast(m_attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), to, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), from, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), agent_id, ca); + auto count = static_cast(attrs.size()); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), count, ca); - for (const auto &[k, v] : m_attrs) { + for (const auto &[k, v] : attrs) { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), k, ca); size += v.serialized_size(calc, ca); } return size; } - - void CRDTNode::type(const std::string &type) + void CRDT::Node::serialize_impl(eprosima::fastcdr::Cdr& cdr) const { - m_type = type; - } - - void CRDTNode::type(std::string &&type) - { - m_type = std::move(type); - } - - const std::string &CRDTNode::type() const - { - return m_type; - } - - std::string &CRDTNode::type() - { - return m_type; - } - - void CRDTNode::name(const std::string &name) - { - m_name = name; - } - - void CRDTNode::name(std::string &&name) - { - m_name = std::move(name); - } - - const std::string &CRDTNode::name() const - { - return m_name; - } - - std::string &CRDTNode::name() - { - return m_name; - } - - void CRDTNode::id(uint64_t id) - { - m_id = id; - } - - uint64_t CRDTNode::id() const - { - return m_id; - } - - void CRDTNode::agent_id(uint32_t agent_id) - { - m_agent_id = agent_id; - } - - uint32_t CRDTNode::agent_id() const - { - return m_agent_id; - } - - void CRDTNode::attrs(const std::map> &attrs) - { - m_attrs = attrs; - } - - void CRDTNode::attrs(std::map> &&attrs) - { - m_attrs = std::move(attrs); - } - - std::map> &CRDTNode::attrs() & - { - return m_attrs; - } - - const std::map> &CRDTNode::attrs() const & - { - return m_attrs; - } - - void CRDTNode::fano(const std::map, mvreg> &fano) - { - m_fano = fano; - } - - void CRDTNode::fano(std::map, mvreg> &&fano) - { - m_fano = std::move(fano); - } - - std::map, mvreg> &CRDTNode::fano() - { - return m_fano; - } - - const std::map, mvreg> &CRDTNode::fano() const - { - return m_fano; - } - - - void CRDTNode::serialize_impl(eprosima::fastcdr::Cdr& cdr) const - { - cdr << m_id; - cdr << m_type; - cdr << m_name; - cdr << m_agent_id; + cdr << id; + cdr << type; + cdr << name; + cdr << agent_id; // attrs map - auto attr_count = static_cast(m_attrs.size()); + auto attr_count = static_cast(attrs.size()); cdr << attr_count; - for (const auto &[k, v] : m_attrs) { + for (const auto &[k, v] : attrs) { cdr << k; v.serialize(cdr); } // fano map: key is pair - auto fano_count = static_cast(m_fano.size()); + auto fano_count = static_cast(fano.size()); cdr << fano_count; - for (const auto &[k, v] : m_fano) { + for (const auto &[k, v] : fano) { cdr << k.first; cdr << k.second; v.serialize(cdr); } } - void CRDTNode::deserialize_impl(eprosima::fastcdr::Cdr& cdr) + void CRDT::Node::deserialize_impl(eprosima::fastcdr::Cdr& cdr) { - cdr >> m_id; - cdr >> m_type; - cdr >> m_name; - cdr >> m_agent_id; + cdr >> id; + cdr >> type; + cdr >> name; + cdr >> agent_id; uint32_t attr_count = 0; cdr >> attr_count; - m_attrs.clear(); + attrs.clear(); for (uint32_t i = 0; i < attr_count; ++i) { std::string key; cdr >> key; - mvreg val; + mvreg val; val.deserialize(cdr); - m_attrs.emplace(std::move(key), std::move(val)); + attrs.emplace(std::move(key), std::move(val)); } uint32_t fano_count = 0; cdr >> fano_count; - m_fano.clear(); + fano.clear(); for (uint32_t i = 0; i < fano_count; ++i) { uint64_t fano_to = 0; std::string fano_type; cdr >> fano_to; cdr >> fano_type; - mvreg val; + mvreg val; val.deserialize(cdr); - m_fano.emplace(std::make_pair(fano_to, std::move(fano_type)), std::move(val)); + fano.emplace(std::make_pair(fano_to, std::move(fano_type)), std::move(val)); } } - size_t CRDTNode::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const + size_t CRDT::Node::serialized_size_impl(eprosima::fastcdr::CdrSizeCalculator& calc, size_t& ca) const { size_t size = 0; - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), m_id, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), m_type, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), m_name, ca); - size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), m_agent_id, ca); - auto attr_count = static_cast(m_attrs.size()); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), id, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), type, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), name, ca); + size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), agent_id, ca); + auto attr_count = static_cast(attrs.size()); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), attr_count, ca); - for (const auto &[k, v] : m_attrs) { + for (const auto &[k, v] : attrs) { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), k, ca); size += v.serialized_size(calc, ca); } - auto fano_count = static_cast(m_fano.size()); + auto fano_count = static_cast(fano.size()); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), fano_count, ca); - for (const auto &[k, v] : m_fano) { + for (const auto &[k, v] : fano) { size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), k.first, ca); size += calc.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), k.second, ca); size += v.serialized_size(calc, ca); } return size; } - } diff --git a/gui/include/dsr/gui/viewers/graph_viewer/graph_edge_widget.h b/gui/include/dsr/gui/viewers/graph_viewer/graph_edge_widget.h index 752023b0..a581febf 100644 --- a/gui/include/dsr/gui/viewers/graph_viewer/graph_edge_widget.h +++ b/gui/include/dsr/gui/viewers/graph_viewer/graph_edge_widget.h @@ -32,9 +32,9 @@ class GraphEdgeWidget : public QTableWidget std::map attribs; attribs = edge.value().attrs(); // show id type and name as attributes - //attribs["ID"] = Attribute(ValType(node_id), 0, 0); - attribs["type"] = Attribute(ValType(edge.value().type()), 0, 0); - //attribs["name"] = Attribute(ValType(edge.value().name()), 0, 0); + //attribs["ID"] = Attribute(Value(node_id), 0, 0); + attribs["type"] = Attribute(Value(edge.value().type()), 0, 0); + //attribs["name"] = Attribute(Value(edge.value().name()), 0, 0); setHorizontalHeaderLabels(QStringList{"Key", "Value"}); for (auto &&[k, v] : attribs) { //TODO: check value range and attributes that could be editable diff --git a/gui/include/dsr/gui/viewers/graph_viewer/graph_node_widget.h b/gui/include/dsr/gui/viewers/graph_viewer/graph_node_widget.h index 0b7e0348..9de4ac24 100644 --- a/gui/include/dsr/gui/viewers/graph_viewer/graph_node_widget.h +++ b/gui/include/dsr/gui/viewers/graph_viewer/graph_node_widget.h @@ -38,9 +38,9 @@ class GraphNodeWidget : public QTableWidget setColumnCount(2); std::map& attribs = n.value().attrs(); // show id type and name as attributes - attribs["ID"] = Attribute(ValType(node_id), 0, 0); - attribs["type"] = Attribute(ValType(n.value().type()), 0, 0); - attribs["name"] = Attribute(ValType(n.value().name()), 0, 0); + attribs["ID"] = Attribute(Value(node_id), 0, 0); + attribs["type"] = Attribute(Value(n.value().type()), 0, 0); + attribs["name"] = Attribute(Value(n.value().name()), 0, 0); setHorizontalHeaderLabels(QStringList{"Key", "Value"}); for (auto &&[k, v] : attribs) { //TODO: check value range and attributes that could be editable diff --git a/python-wrapper/python_api.cpp b/python-wrapper/python_api.cpp index 90d110f9..55568409 100644 --- a/python-wrapper/python_api.cpp +++ b/python-wrapper/python_api.cpp @@ -82,10 +82,10 @@ using attribute_type = std::variant -ValType convert_variant_fn(const attribute_type & e) +Value convert_variant_fn(const attribute_type & e) { - //std::cout << "[PYTHON_VARIANT -> VALTYPE] " << attribute_type_TYPENAMES_UNION[e.index()] << std::endl; - ValType vout; + //std::cout << "[PYTHON_VARIANT -> Value] " << attribute_type_TYPENAMES_UNION[e.index()] << std::endl; + Value vout; if constexpr (std::is_same_v>) { auto tmp = std::get>(e); @@ -121,9 +121,9 @@ ValType convert_variant_fn(const attribute_type & e) -ValType convert_variant(const attribute_type & e) +Value convert_variant(const attribute_type & e) { - typedef ValType (*conver_fn) (const attribute_type &); + typedef Value (*conver_fn) (const attribute_type &); constexpr std::array cast = { convert_variant_fn<0, std::string>, convert_variant_fn<4, no_int_cast_bool>, convert_variant_fn<5, py::array_t>, @@ -143,7 +143,7 @@ ValType convert_variant(const attribute_type & e) convert_variant_fn<6, uint32_t> }; - const auto idx = e.index(); //idx_ValType.at(e.index()); + const auto idx = e.index(); //idx_Value.at(e.index()); return cast[idx](e); } @@ -249,12 +249,12 @@ PYBIND11_MODULE(pydsr, m) { }), "value"_a, "timestamp"_a, "agent_id"_a) .def(py::init([&](attribute_type const& v , uint32_t agent_id) { - //Comprobar tipos en ValType. Como se convien los arrays de numpy, las listas, los doubles, etc. + //Comprobar tipos en Value. Como se convien los arrays de numpy, las listas, los doubles, etc. return Attribute(convert_variant(v), get_unix_timestamp(), agent_id); }),"value"_a, "agent_id"_a) .def(py::init([&](attribute_type const& v) { - //Comprobar tipos en ValType. Como se convien los arrays de numpy, las listas, los doubles, etc. + //Comprobar tipos en Value. Como se convien los arrays de numpy, las listas, los doubles, etc. return Attribute(convert_variant(v), get_unix_timestamp(), local_agent_id); }),"value"_a) .def("__repr__", [](Attribute const &self) { diff --git a/tests/synchronization/graph_signals.cpp b/tests/synchronization/graph_signals.cpp index af226267..7a6d6255 100644 --- a/tests/synchronization/graph_signals.cpp +++ b/tests/synchronization/graph_signals.cpp @@ -139,7 +139,7 @@ TEST_CASE("Insert a node without attributes and edges", "[GRAPH][SIGNALS]"){ static const auto new_attribute_ = []() -> std::pair { - const auto val = random_choose(std::vector{ + const auto val = random_choose(std::vector{ (int)12, random_string(), std::vector{1.0, 2.0, 3.0} diff --git a/tests/synchronization/type_translation.cpp b/tests/synchronization/type_translation.cpp index 05a03018..683282b5 100644 --- a/tests/synchronization/type_translation.cpp +++ b/tests/synchronization/type_translation.cpp @@ -49,7 +49,7 @@ TEST_CASE("NODE: from DSR representation to CRDT and back via serialization", "[ static auto new_attribute_ = [&]() -> std::pair { - const auto val = random_choose(std::vector{ + const auto val = random_choose(std::vector{ (int)12, random_string(), std::vector{1.0, 2.0, 3.0} @@ -96,64 +96,64 @@ TEST_CASE("NODE: from DSR representation to CRDT and back via serialization", "[ SECTION("Copy node — CRDT round-trip"){ - CRDTNode crdt_node = user_node_to_crdt(node); - REQUIRE(crdt_node.attrs().size() == attributes.size()); - REQUIRE(crdt_node.fano().size() == fano.size()); - REQUIRE(crdt_node.id() == id); - REQUIRE(crdt_node.name() == name); - REQUIRE(crdt_node.agent_id() == agent_id); - - mvreg mvreg_node; + CRDT::Node crdt_node = user_node_to_crdt(node); + REQUIRE(crdt_node.attrs.size() == attributes.size()); + REQUIRE(crdt_node.fano.size() == fano.size()); + REQUIRE(crdt_node.id == id); + REQUIRE(crdt_node.name == name); + REQUIRE(crdt_node.agent_id == agent_id); + + mvreg mvreg_node; auto delta = mvreg_node.write(crdt_node); REQUIRE(mvreg_node.read_reg() == crdt_node); REQUIRE(delta.read_reg() == crdt_node); auto& reg = mvreg_node.read_reg(); - REQUIRE(reg.attrs().size() == attributes.size()); - REQUIRE(reg.fano().size() == fano.size()); - REQUIRE(reg.id() == id); - REQUIRE(reg.name() == name); - REQUIRE(reg.agent_id() == agent_id); + REQUIRE(reg.attrs.size() == attributes.size()); + REQUIRE(reg.fano.size() == fano.size()); + REQUIRE(reg.id == id); + REQUIRE(reg.name == name); + REQUIRE(reg.agent_id == agent_id); // Serialization round-trip - CRDTNode rt = roundtrip(reg); - REQUIRE(rt.attrs().size() == attributes.size()); - REQUIRE(rt.fano().size() == fano.size()); - REQUIRE(rt.id() == id); - REQUIRE(rt.name() == name); - REQUIRE(rt.agent_id() == agent_id); - REQUIRE(rt.type() == robot_node_type::attr_name); + CRDT::Node rt = roundtrip(reg); + REQUIRE(rt.attrs.size() == attributes.size()); + REQUIRE(rt.fano.size() == fano.size()); + REQUIRE(rt.id == id); + REQUIRE(rt.name == name); + REQUIRE(rt.agent_id == agent_id); + REQUIRE(rt.type == robot_node_type::attr_name); } SECTION("Move node — CRDT round-trip"){ - CRDTNode crdt_node = user_node_to_crdt(std::move(node)); - REQUIRE(crdt_node.attrs().size() == attributes.size()); - REQUIRE(crdt_node.fano().size() == fano.size()); - REQUIRE(crdt_node.id() == id); - REQUIRE(crdt_node.name() == name); - REQUIRE(crdt_node.agent_id() == agent_id); + CRDT::Node crdt_node = user_node_to_crdt(std::move(node)); + REQUIRE(crdt_node.attrs.size() == attributes.size()); + REQUIRE(crdt_node.fano.size() == fano.size()); + REQUIRE(crdt_node.id == id); + REQUIRE(crdt_node.name == name); + REQUIRE(crdt_node.agent_id == agent_id); - mvreg mvreg_node; + mvreg mvreg_node; auto delta = mvreg_node.write(std::move(crdt_node)); auto& reg = mvreg_node.read_reg(); REQUIRE(delta.read_reg() == reg); - REQUIRE(reg.attrs().size() == attributes.size()); - REQUIRE(reg.fano().size() == fano.size()); - REQUIRE(reg.id() == id); - REQUIRE(reg.name() == name); - REQUIRE(reg.agent_id() == agent_id); + REQUIRE(reg.attrs.size() == attributes.size()); + REQUIRE(reg.fano.size() == fano.size()); + REQUIRE(reg.id == id); + REQUIRE(reg.name == name); + REQUIRE(reg.agent_id == agent_id); // Serialization round-trip - CRDTNode rt = roundtrip(reg); - REQUIRE(rt.attrs().size() == attributes.size()); - REQUIRE(rt.fano().size() == fano.size()); - REQUIRE(rt.id() == id); - REQUIRE(rt.name() == name); - REQUIRE(rt.agent_id() == agent_id); - REQUIRE(rt.type() == robot_node_type::attr_name); + CRDT::Node rt = roundtrip(reg); + REQUIRE(rt.attrs.size() == attributes.size()); + REQUIRE(rt.fano.size() == fano.size()); + REQUIRE(rt.id == id); + REQUIRE(rt.name == name); + REQUIRE(rt.agent_id == agent_id); + REQUIRE(rt.type == robot_node_type::attr_name); } } @@ -184,7 +184,7 @@ TEST_CASE("Wire metadata round-trip preserves sync mode", "[TRANSLATION][SYNC_MO node.id(7); node.agent_id(3); - mvreg reg; + mvreg reg; auto delta = reg.write(user_node_to_crdt(node)); auto msg = CRDTNode_to_Msg(node.agent_id(), node.id(), std::move(delta)); msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); @@ -293,7 +293,7 @@ TEST_CASE("EDGE: from DSR representation to CRDT and back via serialization", "[ static auto new_attribute_ = [&]() -> std::pair { - auto val = random_choose(std::vector{ + auto val = random_choose(std::vector{ (int)12, random_string(), std::vector{1.0, 2.0, 3.0} @@ -319,63 +319,63 @@ TEST_CASE("EDGE: from DSR representation to CRDT and back via serialization", "[ SECTION("Copy edge — CRDT round-trip"){ - CRDTEdge crdt_edge = user_edge_to_crdt(edge); - REQUIRE(crdt_edge.attrs().size() == attributes.size()); - REQUIRE(crdt_edge.from() == from); - REQUIRE(crdt_edge.to() == to); - REQUIRE(crdt_edge.type() == in_edge_type_str); - REQUIRE(crdt_edge.agent_id() == agent_id); - - mvreg mvreg_edge; + CRDT::Edge crdt_edge = user_edge_to_crdt(edge); + REQUIRE(crdt_edge.attrs.size() == attributes.size()); + REQUIRE(crdt_edge.from == from); + REQUIRE(crdt_edge.to == to); + REQUIRE(crdt_edge.type == in_edge_type_str); + REQUIRE(crdt_edge.agent_id == agent_id); + + mvreg mvreg_edge; auto delta = mvreg_edge.write(crdt_edge); REQUIRE(mvreg_edge.read_reg() == crdt_edge); REQUIRE(delta.read_reg() == crdt_edge); auto& reg = mvreg_edge.read_reg(); - REQUIRE(reg.attrs().size() == attributes.size()); - REQUIRE(reg.from() == from); - REQUIRE(reg.to() == to); - REQUIRE(reg.type() == in_edge_type_str); - REQUIRE(reg.agent_id() == agent_id); + REQUIRE(reg.attrs.size() == attributes.size()); + REQUIRE(reg.from == from); + REQUIRE(reg.to == to); + REQUIRE(reg.type == in_edge_type_str); + REQUIRE(reg.agent_id == agent_id); // Serialization round-trip - CRDTEdge rt = roundtrip(reg); - REQUIRE(rt.attrs().size() == attributes.size()); - REQUIRE(rt.from() == from); - REQUIRE(rt.to() == to); - REQUIRE(rt.agent_id() == agent_id); - REQUIRE(rt.type() == in_edge_type_str); + CRDT::Edge rt = roundtrip(reg); + REQUIRE(rt.attrs.size() == attributes.size()); + REQUIRE(rt.from == from); + REQUIRE(rt.to == to); + REQUIRE(rt.agent_id == agent_id); + REQUIRE(rt.type == in_edge_type_str); } SECTION("Move edge — CRDT round-trip"){ - CRDTEdge crdt_edge = user_edge_to_crdt(edge); - REQUIRE(crdt_edge.attrs().size() == attributes.size()); - REQUIRE(crdt_edge.from() == from); - REQUIRE(crdt_edge.to() == to); - REQUIRE(crdt_edge.type() == in_edge_type_str); - REQUIRE(crdt_edge.agent_id() == agent_id); + CRDT::Edge crdt_edge = user_edge_to_crdt(edge); + REQUIRE(crdt_edge.attrs.size() == attributes.size()); + REQUIRE(crdt_edge.from == from); + REQUIRE(crdt_edge.to == to); + REQUIRE(crdt_edge.type == in_edge_type_str); + REQUIRE(crdt_edge.agent_id == agent_id); - mvreg mvreg_edge; + mvreg mvreg_edge; auto delta = mvreg_edge.write(crdt_edge); REQUIRE(delta.read_reg() == mvreg_edge.read_reg()); auto& reg = mvreg_edge.read_reg(); - REQUIRE(reg.attrs().size() == attributes.size()); - REQUIRE(reg.from() == from); - REQUIRE(reg.to() == to); - REQUIRE(reg.type() == in_edge_type_str); - REQUIRE(reg.agent_id() == agent_id); + REQUIRE(reg.attrs.size() == attributes.size()); + REQUIRE(reg.from == from); + REQUIRE(reg.to == to); + REQUIRE(reg.type == in_edge_type_str); + REQUIRE(reg.agent_id == agent_id); // Serialization round-trip - CRDTEdge rt = roundtrip(reg); - REQUIRE(rt.attrs().size() == attributes.size()); - REQUIRE(rt.from() == from); - REQUIRE(rt.to() == to); - REQUIRE(rt.agent_id() == agent_id); - REQUIRE(rt.type() == in_edge_type_str); + CRDT::Edge rt = roundtrip(reg); + REQUIRE(rt.attrs.size() == attributes.size()); + REQUIRE(rt.from == from); + REQUIRE(rt.to == to); + REQUIRE(rt.agent_id == agent_id); + REQUIRE(rt.type == in_edge_type_str); } } From 294d2d1bb8a25b72220a69407c136d1340012c84 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 24 Apr 2026 20:08:02 +0200 Subject: [PATCH 28/38] feat: publish lww attribute deltas --- api/dsr_lww_sync_engine.cpp | 50 ++++++------- core/include/dsr/core/types/lww_io.h | 88 +++++++++++++++++++++++ tests/synchronization/lww_sync_engine.cpp | 56 +++++++++++++++ 3 files changed, 167 insertions(+), 27 deletions(-) diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 058e4262..4a3816de 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -12,27 +12,6 @@ using DSR::LWW::is_newer; using DSR::LWW::version_of; namespace { -template -std::vector collect_changed_attr_names(const AttrMap& before, const AttrMap& after) -{ - std::vector changed; - changed.reserve(std::max(before.size(), after.size())); - - for (const auto& [name, after_attr] : after) { - const auto before_it = before.find(name); - if (before_it == before.end() || !(before_it->second.value == after_attr.value)) { - changed.emplace_back(name); - } - } - for (const auto& [name, _] : before) { - if (!after.contains(name)) { - changed.emplace_back(name); - } - } - - return changed; -} - SyncEngineHost::EdgeKeyList collect_outgoing_edge_keys(const LWW::FromIndex& from_idx, uint64_t from) { SyncEngineHost::EdgeKeyList outgoing_edges; @@ -312,19 +291,29 @@ NodeMutationEffect LWWSyncEngine::update_node_local(Node&& node) const auto old_type = it->second.type; auto old_outgoing_edges = collect_outgoing_edge_keys(from_idx_, node.id()); auto version = version_of(now, host_.local_agent_id()); + auto next_attrs = LWW::to_attr_state_map(node.attrs(), version); + auto attr_deltas = LWW::to_node_attr_delta_batch(node.id(), it->second.attrs, next_attrs); + effect.changed_attributes.reserve(attr_deltas.vec.size()); + for (const auto& item : attr_deltas.vec) { + effect.changed_attributes.emplace_back(item.attr_name); + } + + const bool metadata_changed = it->second.type != node.type() || it->second.name != node.name(); it->second.type = node.type(); it->second.name = node.name(); it->second.version = version; it->second.agent_id = host_.local_agent_id(); - - std::map next_attrs = LWW::to_attr_state_map(node.attrs(), version); - effect.changed_attributes = collect_changed_attr_names(it->second.attrs, next_attrs); it->second.attrs = std::move(next_attrs); host_.update_maps_node_delete(node.id(), old_type, old_outgoing_edges); host_.update_maps_node_insert(node.id(), node.name(), node.type(), collect_outgoing_edge_keys(node.fano())); effect.applied = true; - effect.node_delta = NodeDeltaMessage{LWW::to_node_msg(it->second)}; + if (!attr_deltas.vec.empty()) { + effect.node_attr_batch = NodeAttrDeltaBatchMessage{std::move(attr_deltas)}; + } + if (metadata_changed) { + effect.node_delta = NodeDeltaMessage{LWW::to_node_msg(it->second)}; + } return effect; } @@ -397,9 +386,17 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) } it->second = std::move(next_state); LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, it->second); + effect.edge_delta = EdgeDeltaMessage{LWW::to_edge_msg(it->second)}; } else { - effect.changed_attributes = collect_changed_attr_names(it->second.attrs, next_state.attrs); + auto attr_deltas = LWW::to_edge_attr_delta_batch(edge.from(), edge.to(), edge.type(), it->second.attrs, next_state.attrs); + effect.changed_attributes.reserve(attr_deltas.vec.size()); + for (const auto& item : attr_deltas.vec) { + effect.changed_attributes.emplace_back(item.attr_name); + } it->second = std::move(next_state); + if (!attr_deltas.vec.empty()) { + effect.edge_attr_batch = EdgeAttrDeltaBatchMessage{std::move(attr_deltas)}; + } // Index pointers remain valid — unordered_map guarantees pointer stability. } @@ -408,7 +405,6 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) } host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); effect.applied = true; - effect.edge_delta = EdgeDeltaMessage{LWW::to_edge_msg(it->second)}; return effect; } diff --git a/core/include/dsr/core/types/lww_io.h b/core/include/dsr/core/types/lww_io.h index 9d3005bd..c664999f 100644 --- a/core/include/dsr/core/types/lww_io.h +++ b/core/include/dsr/core/types/lww_io.h @@ -14,6 +14,94 @@ inline std::map to_attr_state_map(const std::map& before, + const std::map& after) +{ + LWWNodeAttrVec batch; + + for (const auto& [name, attr] : after) { + const auto before_it = before.find(name); + if (before_it == before.end() || !(before_it->second.value == attr.value)) { + batch.vec.emplace_back(LWWNodeAttrMsg{ + .node_id = node_id, + .attr_name = name, + .value = attr.value, + .agent_id = attr.version.agent_id, + .timestamp = attr.version.timestamp, + .deleted = false, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW) + }); + } + } + + for (const auto& [name, attr] : before) { + if (!after.contains(name)) { + batch.vec.emplace_back(LWWNodeAttrMsg{ + .node_id = node_id, + .attr_name = name, + .value = attr.value, + .agent_id = attr.version.agent_id, + .timestamp = attr.version.timestamp, + .deleted = true, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW) + }); + } + } + + return batch; +} + +inline LWWEdgeAttrVec to_edge_attr_delta_batch( + uint64_t from, + uint64_t to, + const std::string& type, + const std::map& before, + const std::map& after) +{ + LWWEdgeAttrVec batch; + + for (const auto& [name, attr] : after) { + const auto before_it = before.find(name); + if (before_it == before.end() || !(before_it->second.value == attr.value)) { + batch.vec.emplace_back(LWWEdgeAttrMsg{ + .from = from, + .to = to, + .type = type, + .attr_name = name, + .value = attr.value, + .agent_id = attr.version.agent_id, + .timestamp = attr.version.timestamp, + .deleted = false, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW) + }); + } + } + + for (const auto& [name, attr] : before) { + if (!after.contains(name)) { + batch.vec.emplace_back(LWWEdgeAttrMsg{ + .from = from, + .to = to, + .type = type, + .attr_name = name, + .value = attr.value, + .agent_id = attr.version.agent_id, + .timestamp = attr.version.timestamp, + .deleted = true, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW) + }); + } + } + + return batch; +} + inline NodeState to_node_state(const Node& node, const Version& version, uint32_t agent_id) { NodeState state; diff --git a/tests/synchronization/lww_sync_engine.cpp b/tests/synchronization/lww_sync_engine.cpp index be17d050..f56405d1 100644 --- a/tests/synchronization/lww_sync_engine.cpp +++ b/tests/synchronization/lww_sync_engine.cpp @@ -143,6 +143,32 @@ TEST_CASE("LWW update_node keeps full replacement API semantics", "[LWW][ENGINE] REQUIRE_FALSE(stored->attrs().contains("parent")); } +TEST_CASE("LWW local node updates emit attr batches for attr-only changes", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + auto node = make_robot(4, "robot_4", 1); + node.attrs()["parent"] = Attribute(7, 1, 17); + REQUIRE(engine.insert_node_local(std::move(node)).applied); + + auto replacement = make_robot(4, "robot_4", 5); + auto effect = engine.update_node_local(std::move(replacement)); + + REQUIRE(effect.applied); + REQUIRE_FALSE(effect.node_delta.has_value()); + REQUIRE(effect.node_attr_batch.has_value()); + REQUIRE(effect.changed_attributes == std::vector{"level", "parent"}); + + const auto* batch = std::get_if(&*effect.node_attr_batch); + REQUIRE(batch != nullptr); + REQUIRE(batch->vec.size() == 2); + REQUIRE(batch->vec[0].attr_name == "level"); + REQUIRE_FALSE(batch->vec[0].deleted); + REQUIRE(batch->vec[1].attr_name == "parent"); + REQUIRE(batch->vec[1].deleted); +} + TEST_CASE("LWW edge tombstones allow newer recreation", "[LWW][ENGINE]") { FakeSyncHost host; @@ -178,6 +204,36 @@ TEST_CASE("LWW edge tombstones allow newer recreation", "[LWW][ENGINE]") REQUIRE(stored->attrs().at("weight").dec() == 4); } +TEST_CASE("LWW local edge updates emit attr batches for attr-only changes", "[LWW][ENGINE]") +{ + FakeSyncHost host; + LWWSyncEngine engine(host); + + REQUIRE(engine.insert_node_local(make_robot(12, "robot_c", 1)).applied); + REQUIRE(engine.insert_node_local(make_robot(13, "robot_d", 1)).applied); + + auto edge = Edge::create(12, 13); + edge.attrs()["weight"] = Attribute(1, 1, 17); + REQUIRE(engine.insert_or_assign_edge_local(std::move(edge)).applied); + + auto updated = Edge::create(12, 13); + updated.attrs()["capacity"] = Attribute(9, 1, 17); + auto effect = engine.insert_or_assign_edge_local(std::move(updated)); + + REQUIRE(effect.applied); + REQUIRE_FALSE(effect.edge_delta.has_value()); + REQUIRE(effect.edge_attr_batch.has_value()); + REQUIRE(effect.changed_attributes == std::vector{"capacity", "weight"}); + + const auto* batch = std::get_if(&*effect.edge_attr_batch); + REQUIRE(batch != nullptr); + REQUIRE(batch->vec.size() == 2); + REQUIRE(batch->vec[0].attr_name == "capacity"); + REQUIRE_FALSE(batch->vec[0].deleted); + REQUIRE(batch->vec[1].attr_name == "weight"); + REQUIRE(batch->vec[1].deleted); +} + TEST_CASE("Same-process LWW agents synchronize over DDS", "[LWW][DDS]") { auto ctx = make_edge_config_file(); From 46dc4bbffca07e31da21cfbed51e2c3bf4898481 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 24 Apr 2026 20:08:40 +0200 Subject: [PATCH 29/38] refactor: add crtp transport wrappers --- api/dsr_api.cpp | 24 ++-- core/include/dsr/core/rtps/dsrparticipant.h | 15 +- core/include/dsr/core/rtps/dsrpublisher.h | 29 ++-- core/include/dsr/core/rtps/dsrsubscriber.h | 9 +- .../dsr/core/transport/transport_crtp.h | 130 ++++++++++++++++++ core/rtps/dsrparticipant.cpp | 12 +- core/rtps/dsrpublisher.cpp | 26 ++-- core/rtps/dsrsubscriber.cpp | 6 +- 8 files changed, 192 insertions(+), 59 deletions(-) create mode 100644 core/include/dsr/core/transport/transport_crtp.h diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 02e1f065..e35ba3b2 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -219,12 +219,12 @@ DSRGraph::DSRGraph(GraphSettings settings) : { CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph register publishers"); - dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), {pub, writer}); - dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), {pub2, writer2}); - dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), {pub3, writer3}); - dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), {pub4, writer4}); - dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), {pub5, writer5}); - dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), {pub6, writer6}); + dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), std::pair{pub, writer}); + dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), std::pair{pub2, writer2}); + dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), std::pair{pub3, writer3}); + dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), std::pair{pub4, writer4}); + dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), std::pair{pub5, writer5}); + dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), std::pair{pub6, writer6}); } // RTPS Initialize comms threads @@ -1267,7 +1267,7 @@ void DSRGraph::node_subscription_thread() CORTEX_PROFILE_MIN_N("DSRGraph::node_subscription_thread setup"); dsrpub_call_node = make_node_subscription_functor(); auto [res, sub, reader] = dsrsub_node.init(dsrparticipant.getParticipant(), dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), std::pair{sub, reader}); } void DSRGraph::edge_subscription_thread() @@ -1275,7 +1275,7 @@ void DSRGraph::edge_subscription_thread() CORTEX_PROFILE_MIN_N("DSRGraph::edge_subscription_thread setup"); dsrpub_call_edge = make_edge_subscription_functor(); auto [res, sub, reader] = dsrsub_edge.init(dsrparticipant.getParticipant(), dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), std::pair{sub, reader}); } @@ -1285,7 +1285,7 @@ void DSRGraph::edge_attrs_subscription_thread() dsrpub_call_edge_attrs = make_edge_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_edge_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge_attrs, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getAttEdgeTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getAttEdgeTopic()->get_name(), std::pair{sub, reader}); //dsrsub_edge_attrs_stream.init(dsrparticipant.getParticipant(), "DSR_EDGE_ATTRS_STREAM", dsrparticipant.getEdgeAttrTopicName(), // dsrpub_call_edge_attrs, true); } @@ -1296,7 +1296,7 @@ void DSRGraph::node_attrs_subscription_thread() dsrpub_call_node_attrs = make_node_attrs_subscription_functor(); auto [res, sub, reader] = dsrsub_node_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node_attrs, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getAttNodeTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getAttNodeTopic()->get_name(), std::pair{sub, reader}); } @@ -1360,7 +1360,7 @@ void DSRGraph::fullgraph_server_thread() dsrpub_graph_request_call = NewMessageFn(this, lambda_graph_request); auto [res, sub, reader] = dsrsub_graph_request.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id(), dsrpub_graph_request_call, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getGraphRequestTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getGraphRequestTopic()->get_name(), std::pair{sub, reader}); } @@ -1372,7 +1372,7 @@ std::pair DSRGraph::fullgraph_request_thread() dsrpub_request_answer_call = make_fullgraph_request_functor(sync, repeated); auto [res, sub, reader] = dsrsub_request_answer.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id(), dsrpub_request_answer_call, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), {sub, reader}); + dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), std::pair{sub, reader}); { CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread initial wait"); diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index 69924124..d92fdb47 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -11,13 +11,14 @@ #include #include #include +#include -class DSRParticipant +class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP { public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, uint8_t sync_mode_wire = 0); + [[nodiscard]] std::tuple init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, uint8_t sync_mode_wire = 0); [[nodiscard]] int8_t get_domain_id() const { return domain_id_; } [[nodiscard]] uint8_t get_sync_mode_wire() const { return sync_mode_wire_; } [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; @@ -36,12 +37,12 @@ class DSRParticipant [[nodiscard]] eprosima::fastdds::dds::Topic* getAttEdgeTopic() { return topic_edge_att;} [[nodiscard]] eprosima::fastdds::dds::DomainParticipant *getParticipant(); - void add_subscriber(const std::string& id, std::pair); - void add_publisher(const std::string& id, std::pair); - void delete_subscriber(const std::string& id); - void delete_publisher(const std::string& id); + void add_subscriber_impl(const std::string& id, std::pair); + void add_publisher_impl(const std::string& id, std::pair); + void delete_subscriber_impl(const std::string& id); + void delete_publisher_impl(const std::string& id); - void remove_participant_and_entities(); + void remove_participant_and_entities_impl(); private: int8_t domain_id_ {0}; diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index 10ad57cc..cfd131d3 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -10,29 +10,30 @@ #include #include +#include -class DSRPublisher +class DSRPublisher : public DSR::Transport::PublisherTransportCRTP { public: DSRPublisher(); virtual ~DSRPublisher(); - [[nodiscard]] std::tuple init( + [[nodiscard]] std::tuple init_impl( eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, int8_t domain_id, bool isStreamData = false); - [[nodiscard]] eprosima::fastdds::rtps::GUID_t getParticipantID() const; - bool write(const DSR::GraphRequest &object); - bool write(const DSR::MvregNodeMsg &object); - bool write(const DSR::OrMap &object); - bool write(const DSR::MvregEdgeMsg &object); - bool write(const DSR::MvregEdgeAttrVec &object); - bool write(const DSR::MvregNodeAttrVec &object); - bool write(const DSR::LWWNodeMsg &object); - bool write(const DSR::LWWEdgeMsg &object); - bool write(const DSR::LWWNodeAttrVec &object); - bool write(const DSR::LWWEdgeAttrVec &object); - bool write(const DSR::LWWGraphSnapshot &object); + [[nodiscard]] eprosima::fastdds::rtps::GUID_t getParticipantID_impl() const; + bool write_impl(const DSR::GraphRequest &object); + bool write_impl(const DSR::MvregNodeMsg &object); + bool write_impl(const DSR::OrMap &object); + bool write_impl(const DSR::MvregEdgeMsg &object); + bool write_impl(const DSR::MvregEdgeAttrVec &object); + bool write_impl(const DSR::MvregNodeAttrVec &object); + bool write_impl(const DSR::LWWNodeMsg &object); + bool write_impl(const DSR::LWWEdgeMsg &object); + bool write_impl(const DSR::LWWNodeAttrVec &object); + bool write_impl(const DSR::LWWEdgeAttrVec &object); + bool write_impl(const DSR::LWWGraphSnapshot &object); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; diff --git a/core/include/dsr/core/rtps/dsrsubscriber.h b/core/include/dsr/core/rtps/dsrsubscriber.h index bedd98bb..a3b0b7f8 100644 --- a/core/include/dsr/core/rtps/dsrsubscriber.h +++ b/core/include/dsr/core/rtps/dsrsubscriber.h @@ -6,23 +6,24 @@ #include #include +#include -class DSRSubscriber +class DSRSubscriber : public DSR::Transport::SubscriberTransportCRTP { public: DSRSubscriber(); virtual ~DSRSubscriber(); [[nodiscard]] std::tuple - init(eprosima::fastdds::dds::DomainParticipant *mp_participant_, + init_impl(eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, int8_t domain_id, const std::function& f_, std::mutex& mtx, bool isStreamData = false); - eprosima::fastdds::dds::Subscriber *getSubscriber(); - eprosima::fastdds::dds::DataReader *getDataReader(); + eprosima::fastdds::dds::Subscriber *getSubscriber_impl(); + eprosima::fastdds::dds::DataReader *getDataReader_impl(); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; diff --git a/core/include/dsr/core/transport/transport_crtp.h b/core/include/dsr/core/transport/transport_crtp.h new file mode 100644 index 00000000..5c3b487a --- /dev/null +++ b/core/include/dsr/core/transport/transport_crtp.h @@ -0,0 +1,130 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace DSR::Transport { + +template +class ParticipantTransportCRTP +{ +public: + auto init( + uint32_t agent_id, + const std::string& agent_name, + int localhost, + std::function fn, + int8_t domain_id = 0, + uint8_t sync_mode_wire = 0) + { + return derived().init_impl(agent_id, agent_name, localhost, std::move(fn), domain_id, sync_mode_wire); + } + + template + void add_subscriber(Id&& id, SubscriberEntry&& entry) + { + derived().add_subscriber_impl(std::forward(id), std::forward(entry)); + } + + template + void add_publisher(Id&& id, PublisherEntry&& entry) + { + derived().add_publisher_impl(std::forward(id), std::forward(entry)); + } + + template + void delete_subscriber(Id&& id) + { + derived().delete_subscriber_impl(std::forward(id)); + } + + template + void delete_publisher(Id&& id) + { + derived().delete_publisher_impl(std::forward(id)); + } + + void remove_participant_and_entities() + { + derived().remove_participant_and_entities_impl(); + } + +private: + Derived& derived() { return static_cast(*this); } +}; + +template +class PublisherTransportCRTP +{ +public: + template + auto init( + ParticipantHandle* participant, + TopicHandle* topic, + int8_t domain_id, + bool is_stream_data = false) + { + return derived().init_impl(participant, topic, domain_id, is_stream_data); + } + + auto getParticipantID() const + { + return derived().getParticipantID_impl(); + } + + template + bool write(const Message& object) + { + return derived().write_impl(object); + } + +private: + Derived& derived() { return static_cast(*this); } + const Derived& derived() const { return static_cast(*this); } +}; + +template +class SubscriberTransportCRTP +{ +public: + template + auto init( + ParticipantHandle* participant, + TopicHandle* topic, + int8_t domain_id, + Callback&& callback, + std::mutex& creation_mutex, + bool is_stream_data = false) + { + return derived().init_impl( + participant, + topic, + domain_id, + std::forward(callback), + creation_mutex, + is_stream_data); + } + + auto getSubscriber() + { + return derived().getSubscriber_impl(); + } + + auto getDataReader() + { + return derived().getDataReader_impl(); + } + +private: + Derived& derived() { return static_cast(*this); } +}; + +} // namespace DSR::Transport diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 0c046cd9..9f49417e 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -109,7 +109,7 @@ DSRParticipant::~DSRParticipant() } -std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, uint8_t sync_mode_wire) +std::tuple DSRParticipant::init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, uint8_t sync_mode_wire) { domain_id_ = domain_id; sync_mode_wire_ = sync_mode_wire; @@ -204,7 +204,7 @@ eprosima::fastdds::dds::DomainParticipant *DSRParticipant::getParticipant() return mp_participant; } -void DSRParticipant::remove_participant_and_entities() +void DSRParticipant::remove_participant_and_entities_impl() { //if (!cleanup_enabled_) { // return; @@ -331,18 +331,18 @@ const eprosima::fastdds::rtps::GUID_t& DSRParticipant::getID() const return mp_participant->guid(); } -void DSRParticipant::add_subscriber(const std::string& id, std::pair val) +void DSRParticipant::add_subscriber_impl(const std::string& id, std::pair val) { std::unique_lock lck (sub_mtx); subscribers.emplace(id, val); } -void DSRParticipant::add_publisher(const std::string& id, std::pair val) +void DSRParticipant::add_publisher_impl(const std::string& id, std::pair val) { std::unique_lock lck (pub_mtx); publishers.emplace(id, val); } -void DSRParticipant::delete_subscriber(const std::string& id) +void DSRParticipant::delete_subscriber_impl(const std::string& id) { std::unique_lock lck (sub_mtx); try { @@ -375,7 +375,7 @@ void DSRParticipant::delete_subscriber(const std::string& id) } } -void DSRParticipant::delete_publisher(const std::string& id) +void DSRParticipant::delete_publisher_impl(const std::string& id) { std::unique_lock lck (pub_mtx); try { diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index ee6d8de7..c555c08f 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -36,7 +36,7 @@ DSRPublisher::~DSRPublisher() } std::tuple - DSRPublisher::init(eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, int8_t domain_id, bool isStreamData ) + DSRPublisher::init_impl(eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, int8_t domain_id, bool isStreamData ) { mp_participant = mp_participant_; @@ -103,7 +103,7 @@ std::tupleguid(); } @@ -123,7 +123,7 @@ bool write_with_retry(eprosima::fastdds::dds::DataWriter* writer, const T& objec } } -bool DSRPublisher::write(const DSR::MvregNodeMsg& object) +bool DSRPublisher::write_impl(const DSR::MvregNodeMsg& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing NODE " << object.id << " after 5 attempts. error code: " << rt; @@ -131,7 +131,7 @@ bool DSRPublisher::write(const DSR::MvregNodeMsg& object) } -bool DSRPublisher::write(const DSR::MvregEdgeMsg& object) +bool DSRPublisher::write_impl(const DSR::MvregEdgeMsg& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing EDGE " << object.from << " " << object.to << " " << object.type.data() << " after 5 attempts. error code: " << rt; @@ -139,62 +139,62 @@ bool DSRPublisher::write(const DSR::MvregEdgeMsg& object) } -bool DSRPublisher::write(const DSR::OrMap& object) +bool DSRPublisher::write_impl(const DSR::OrMap& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing GRAPH " << object.m.size() << " after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::GraphRequest& object) +bool DSRPublisher::write_impl(const DSR::GraphRequest& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing GRAPH REQUEST after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::MvregEdgeAttrVec& object) +bool DSRPublisher::write_impl(const DSR::MvregEdgeAttrVec& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::MvregNodeAttrVec& object) { +bool DSRPublisher::write_impl(const DSR::MvregNodeAttrVec& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::LWWNodeMsg& object) +bool DSRPublisher::write_impl(const DSR::LWWNodeMsg& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing LWW NODE " << object.id << " after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::LWWEdgeMsg& object) +bool DSRPublisher::write_impl(const DSR::LWWEdgeMsg& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing LWW EDGE " << object.from << " " << object.to << " " << object.type.data() << " after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::LWWNodeAttrVec& object) +bool DSRPublisher::write_impl(const DSR::LWWNodeAttrVec& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing LWW NODE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::LWWEdgeAttrVec& object) +bool DSRPublisher::write_impl(const DSR::LWWEdgeAttrVec& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing LWW EDGE ATTRIBUTE VECTOR after 5 attempts. error code: " << rt; }); } -bool DSRPublisher::write(const DSR::LWWGraphSnapshot& object) +bool DSRPublisher::write_impl(const DSR::LWWGraphSnapshot& object) { return write_with_retry(mp_writer, object, [&](ReturnCode_t rt) { qInfo() << "Error writing LWW GRAPH " << object.nodes.size() << " nodes after 5 attempts. error code: " << rt; diff --git a/core/rtps/dsrsubscriber.cpp b/core/rtps/dsrsubscriber.cpp index 1a7ed709..724b32e2 100644 --- a/core/rtps/dsrsubscriber.cpp +++ b/core/rtps/dsrsubscriber.cpp @@ -33,7 +33,7 @@ DSRSubscriber::~DSRSubscriber() = default; std::tuple - DSRSubscriber::init(eprosima::fastdds::dds::DomainParticipant *mp_participant_, + DSRSubscriber::init_impl(eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, int8_t domain_id, const std::function& f_, @@ -102,11 +102,11 @@ std::tuple Date: Fri, 24 Apr 2026 21:51:21 +0200 Subject: [PATCH 30/38] refactor: move transport setup behind typed session callbacks --- api/dsr_api.cpp | 516 +++++++----------- api/include/dsr/api/dsr_api.h | 69 +-- core/include/dsr/core/rtps/dsrparticipant.h | 141 ++++- core/include/dsr/core/rtps/dsrpublisher.h | 5 +- core/include/dsr/core/rtps/dsrsubscriber.h | 22 +- .../dsr/core/transport/transport_crtp.h | 81 ++- core/rtps/dsrparticipant.cpp | 32 +- core/rtps/dsrsubscriber.cpp | 12 +- 8 files changed, 442 insertions(+), 436 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index e35ba3b2..b58c28dd 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -123,7 +123,7 @@ inline size_t full_graph_payload_size(const DSR::LWWGraphSnapshot& sample) } } -void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info); +void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const DSR::Transport::ReceivedSampleInfo& info); ///////////////////////////////////////////////// ///// PUBLIC METHODS @@ -162,26 +162,26 @@ DSRGraph::DSRGraph(GraphSettings settings) : CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph init participant"); return dsrparticipant.init(agent_id, agent_name, settings.same_host, ParticipantChangeFn(this, [&](DSR::DSRGraph *graph, - eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, - const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) + DSR::Transport::ParticipantDiscoveryStatus status, + const DSR::Transport::ParticipantDiscoveryInfo& info) { CORTEX_PROFILE_DETAIL_N("DSRGraph::participant discovery callback"); - if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT) + if (status == DSR::Transport::ParticipantDiscoveryStatus::discovered) { std::unique_lock lck(participant_set_mutex); - std::cout << "Participant matched [" << info.participant_name.to_string() << "]" << std::endl; - graph->participant_set.emplace(info.participant_name.to_string(), false); + std::cout << "Participant matched [" << info.participant_name << "]" << std::endl; + graph->participant_set.emplace(info.participant_name, false); } - else if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::REMOVED_PARTICIPANT || - status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DROPPED_PARTICIPANT) - { - std::unique_lock lck(participant_set_mutex); - graph->participant_set.erase(info.participant_name.to_string()); - std::cout << "Participant unmatched [" << info.participant_name.to_string() << "]" << std::endl; + else if (status == DSR::Transport::ParticipantDiscoveryStatus::removed || + status == DSR::Transport::ParticipantDiscoveryStatus::dropped) + { + std::unique_lock lck(participant_set_mutex); + graph->participant_set.erase(info.participant_name); + std::cout << "Participant unmatched [" << info.participant_name << "]" << std::endl; // Participant name is "Participant_ ( )" which doesn't // match the DSR node name " ". Find the agent node by // its agent_id attribute instead. - const std::string pname = info.participant_name.to_string(); + const std::string& pname = info.participant_name; const std::string prefix = "Participant_"; bool deleted = false; if (pname.size() > prefix.size() && pname.substr(0, prefix.size()) == prefix) { @@ -199,32 +199,14 @@ DSRGraph::DSRGraph(GraphSettings settings) : } if (!deleted) graph->delete_node(pname); - } - }), settings.domain_id, sync_mode_wire_value(sync_mode)); + } + }), settings.domain_id, sync_mode_wire_value(sync_mode)); }(); auto[suc, participant_handle] = std::move(participant_init_result); - - - // RTPS Initialize publisher with general topic - auto [res, pub, writer, res2, pub2, writer2, res3, pub3, writer3, res4, pub4, writer4, res5, pub5, writer5, res6, pub6, writer6] = [&]() { - CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph init publishers"); - auto [r1, p1, w1] = dsrpub_node.init(participant_handle, dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id()); - auto [r2, p2, w2] = dsrpub_node_attrs.init(participant_handle, dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id()); - auto [r3, p3, w3] = dsrpub_edge.init(participant_handle, dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id()); - auto [r4, p4, w4] = dsrpub_edge_attrs.init(participant_handle, dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id()); - auto [r5, p5, w5] = dsrpub_graph_request.init(participant_handle, dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id()); - auto [r6, p6, w6] = dsrpub_request_answer.init(participant_handle, dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id()); - return std::tuple{r1, p1, w1, r2, p2, w2, r3, p3, w3, r4, p4, w4, r5, p5, w5, r6, p6, w6}; - }(); - + static_cast(participant_handle); { - CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph register publishers"); - dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), std::pair{pub, writer}); - dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), std::pair{pub2, writer2}); - dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), std::pair{pub3, writer3}); - dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), std::pair{pub4, writer4}); - dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), std::pair{pub5, writer5}); - dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), std::pair{pub6, writer6}); + CORTEX_PROFILE_MIN_N("DSRGraph::DSRGraph init publishers"); + dsrparticipant.init_builtin_publishers(); } // RTPS Initialize comms threads @@ -298,28 +280,28 @@ void DSRGraph::reset() void DSRGraph::publish_node_message(const NodeDeltaMessage& message) { std::visit([this](const auto& payload) { - dsrpub_node.write(payload); + dsrparticipant.publish_node(payload); }, message); } void DSRGraph::publish_node_attr_batch(const NodeAttrDeltaBatchMessage& message) { std::visit([this](const auto& payload) { - dsrpub_node_attrs.write(payload); + dsrparticipant.publish_node_attrs(payload); }, message); } void DSRGraph::publish_edge_message(const EdgeDeltaMessage& message) { std::visit([this](const auto& payload) { - dsrpub_edge.write(payload); + dsrparticipant.publish_edge(payload); }, message); } void DSRGraph::publish_edge_attr_batch(const EdgeAttrDeltaBatchMessage& message) { std::visit([this](const auto& payload) { - dsrpub_edge_attrs.write(payload); + dsrparticipant.publish_edge_attrs(payload); }, message); } @@ -327,245 +309,164 @@ void DSRGraph::publish_full_graph_message(FullGraphMessage&& message, int32_t se { std::visit([this, sender_id](auto&& payload) { payload.id = sender_id; - dsrpub_request_answer.write(payload); + dsrparticipant.publish_graph_answer(payload); }, std::move(message)); } template -DSRGraph::NewMessageFn DSRGraph::make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal) +DSRGraph::SampleCallback DSRGraph::make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal) { auto name = "node_subscription_thread"; - return NewMessageFn(this, [this, channel, name, showReceived = log_level, clear_deleted_signal] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + return [this, channel, name, showReceived = log_level, clear_deleted_signal] + (Sample&& sample, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_sub"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::node_subscription_thread callback"); try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - Sample sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { - continue; - } - if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (clear_deleted_signal && sample.id == CLEAR_DELETED_SIGNAL) { - std::unique_lock lock(_mutex); - std::unique_lock lck_cache(_mutex_cache_maps); - deleted.clear(); - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { + return; + } + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + return; + } + if (clear_deleted_signal && sample.id == CLEAR_DELETED_SIGNAL) { + std::unique_lock lock(_mutex); + std::unique_lock lck_cache(_mutex_cache_maps); + deleted.clear(); + return; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << std::to_string(sample.id).c_str() << " node from: " + << m_info.source_entity_id; } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); + engine_->apply_remote_node_delta(NodeDeltaMessage{std::move(sample)}); + }); } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); + }; } template -DSRGraph::NewMessageFn DSRGraph::make_edge_subscription_functor_impl(const char* channel) +DSRGraph::SampleCallback DSRGraph::make_edge_subscription_functor_impl(const char* channel) { auto name = "edge_subscription_thread"; - return NewMessageFn(this, [this, channel, name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + return [this, channel, name, showReceived = log_level] + (Sample&& sample, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_sub"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::edge_subscription_thread callback"); try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - Sample sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { - continue; - } - if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - tp.spawn_task([this, sample = std::move(sample)]() mutable { - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (!m_info.valid_data || remote_agent_id_of(sample) == agent_id) { + return; + } + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + return; } + tp.spawn_task([this, sample = std::move(sample)]() mutable { + std::unique_lock lock(_mutex); + engine_->apply_remote_edge_delta(EdgeDeltaMessage{std::move(sample)}); + }); } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); + }; } template -DSRGraph::NewMessageFn DSRGraph::make_edge_attrs_subscription_functor_impl(const char* channel) +DSRGraph::SampleCallback DSRGraph::make_edge_attrs_subscription_functor_impl(const char* channel) { auto name = "edge_attrs_subscription_thread"; - return NewMessageFn(this, [this, channel, name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + return [this, channel, name, showReceived = log_level] + (Batch&& samples, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("edge_attr_sub"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread callback"); try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - Batch samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { - continue; - } - if (!batch_is_compatible(channel, samples, sync_mode)) { - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); - std::unique_lock lock(_mutex); - engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { + return; + } + if (!batch_is_compatible(channel, samples, sync_mode)) { + return; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " edge attr from: " + << m_info.source_entity_id; } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::edge_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); + engine_->apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(samples)}); + }); } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); + }; } template -DSRGraph::NewMessageFn DSRGraph::make_node_attrs_subscription_functor_impl(const char* channel) +DSRGraph::SampleCallback DSRGraph::make_node_attrs_subscription_functor_impl(const char* channel) { auto name = "node_attrs_subscription_thread"; - return NewMessageFn(this, [this, channel, name, showReceived = log_level] - (eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *) + return [this, channel, name, showReceived = log_level] + (Batch&& samples, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("node_attr_sub"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread callback"); try { - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - Batch samples; - if (reader->take_next_sample(&samples, &m_info) != 0) { - break; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); - if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { - continue; - } - if (!batch_is_compatible(channel, samples, sync_mode)) { - continue; - } - if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { - qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " - << m_info.sample_identity.writer_guid().entityId.value; - } - tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); - std::unique_lock lock(_mutex); - engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); - }); + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(showReceived, m_info); + if (!m_info.valid_data || !batch_is_from_remote(samples, agent_id)) { + return; + } + if (!batch_is_compatible(channel, samples, sync_mode)) { + return; + } + if (showReceived == GraphSettings::LOGLEVEL::DEBUGL) { + qDebug() << name << " Received:" << samples.vec.size() << " node attrs from: " + << m_info.source_entity_id; } + tp_delta_attr.spawn_task([this, samples = std::move(samples)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::node_attrs_subscription_thread apply batch"); + std::unique_lock lock(_mutex); + engine_->apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(samples)}); + }); } catch (const std::exception &ex) { std::cerr << ex.what() << std::endl; } - }); + }; } template -DSRGraph::NewMessageFn DSRGraph::make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated) +DSRGraph::SampleCallback DSRGraph::make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated) { - return NewMessageFn(this, [this, channel, &sync, &repeated](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + return [this, channel, &sync, &repeated](GraphSample&& sample, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_request"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread callback"); - while (true) - { - eprosima::fastdds::dds::SampleInfo m_info; - GraphSample sample; - if (reader->take_next_sample(&sample, &m_info) != 0) { - break; - } - if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (!m_info.valid_data) { - continue; - } - if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - if (static_cast(sample.id) != graph->get_agent_id()) { - if (sample.id != -1) { - qDebug() << " Received Full Graph from " << m_info.sample_identity.writer_guid().entityId.value - << " whith " << full_graph_payload_size(sample) << " elements"; - tp.spawn_task([this, s = std::move(sample)]() mutable { - CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); - std::unique_lock lock(_mutex); - engine_->import_full_graph(FullGraphMessage{std::move(s)}); - }); - qDebug() << "Synchronized."; - sync = true; - break; - } else if (!sync && sample.to_id == agent_id) { - repeated = true; - } + if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); + if (!m_info.valid_data) { + return; + } + if (!network_compatibility_or_fatal(channel, sample.protocol_version, sample.sync_mode, sync_mode)) { + return; + } + if (static_cast(sample.id) != get_agent_id()) { + if (sample.id != -1) { + qDebug() << " Received Full Graph from " << m_info.source_entity_id + << " whith " << full_graph_payload_size(sample) << " elements"; + tp.spawn_task([this, s = std::move(sample)]() mutable { + CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_request_thread apply full graph"); + std::unique_lock lock(_mutex); + engine_->import_full_graph(FullGraphMessage{std::move(s)}); + }); + qDebug() << "Synchronized."; + sync = true; + } else if (!sync && sample.to_id == agent_id) { + repeated = true; } } - }); -} - -DSRGraph::NewMessageFn DSRGraph::make_node_subscription_functor() -{ - if (sync_mode == SyncMode::LWW) { - return make_node_subscription_functor_impl("LWW_NODE"); - } - return make_node_subscription_functor_impl("DSR_NODE", true); -} - -DSRGraph::NewMessageFn DSRGraph::make_edge_subscription_functor() -{ - if (sync_mode == SyncMode::LWW) { - return make_edge_subscription_functor_impl("LWW_EDGE"); - } - return make_edge_subscription_functor_impl("DSR_EDGE"); -} - -DSRGraph::NewMessageFn DSRGraph::make_edge_attrs_subscription_functor() -{ - if (sync_mode == SyncMode::LWW) { - return make_edge_attrs_subscription_functor_impl("LWW_EDGE_ATTS"); - } - return make_edge_attrs_subscription_functor_impl("DSR_EDGE_ATTS"); -} - -DSRGraph::NewMessageFn DSRGraph::make_node_attrs_subscription_functor() -{ - if (sync_mode == SyncMode::LWW) { - return make_node_attrs_subscription_functor_impl("LWW_NODE_ATTS"); - } - return make_node_attrs_subscription_functor_impl("DSR_NODE_ATTS"); -} - -DSRGraph::NewMessageFn DSRGraph::make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated) -{ - if (sync_mode == SyncMode::LWW) { - return make_fullgraph_request_functor_impl("LWW_GRAPH_ANSWER", sync, repeated); - } - return make_fullgraph_request_functor_impl("GRAPH_ANSWER", sync, repeated); + }; } ////////////////////////////////////// @@ -1220,43 +1121,29 @@ std::pair DSRGraph::start_fullgraph_request_thread() void DSRGraph::start_fullgraph_server_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::start_fullgraph_server_thread"); - auto fullgraph_thread = std::thread(&DSRGraph::fullgraph_server_thread, this); - if (fullgraph_thread.joinable()) fullgraph_thread.join(); + fullgraph_server_thread(); } void DSRGraph::start_subscription_threads() { CORTEX_PROFILE_MIN_N("DSRGraph::start_subscription_threads"); - auto delta_node_thread = std::thread(&DSRGraph::node_subscription_thread, this); - auto delta_edge_thread = std::thread(&DSRGraph::edge_subscription_thread, this); - auto delta_node_attrs_thread = std::thread(&DSRGraph::node_attrs_subscription_thread, this); - auto delta_edge_attrs_thread = std::thread(&DSRGraph::edge_attrs_subscription_thread, this); - - if (delta_node_thread.joinable()) delta_node_thread.join(); - if (delta_edge_thread.joinable()) delta_edge_thread.join(); - if (delta_node_attrs_thread.joinable()) delta_node_attrs_thread.join(); - if (delta_edge_attrs_thread.joinable()) delta_edge_attrs_thread.join(); + node_subscription_thread(); + edge_subscription_thread(); + node_attrs_subscription_thread(); + edge_attrs_subscription_thread(); } -void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::fastdds::dds::SampleInfo& info) { - - double milliseconds_send = static_cast(info.source_timestamp.seconds()) * 1000.0; - milliseconds_send += static_cast(info.source_timestamp.nanosec()) / 1000000.0; - - double milliseconds_recv = static_cast(info.reception_timestamp.seconds()) * 1000.0; - milliseconds_recv += static_cast(info.reception_timestamp.nanosec()) / 1000000.0; - - auto t_since_epoch = std::chrono::system_clock::now().time_since_epoch(); - auto secs_t = duration_cast(t_since_epoch); - t_since_epoch -= secs_t; +void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const DSR::Transport::ReceivedSampleInfo& info) { - double now = static_cast(secs_t.count()) * 1000.0 ; - now += static_cast(duration_cast(t_since_epoch).count()) / 1000000.0; + const double milliseconds_send = static_cast(info.source_timestamp_ns) / 1000000.0; + const double milliseconds_recv = static_cast(info.reception_timestamp_ns) / 1000000.0; + const double now = milliseconds_recv; std::ostringstream oss; oss << "SampleInfo:" << std::endl; oss << " ms diff reception: " << (milliseconds_recv - milliseconds_send) << "ms" << std::endl; oss << " ms taken from dds: " << (now - milliseconds_send) << "ms" << std::endl; + oss << " source entity: " << info.source_entity_id << std::endl; oss << " Valid Data: " << (info.valid_data ? "true" : "false") << std::endl; qDebug() << QString::fromStdString(oss.str()); } @@ -1265,102 +1152,89 @@ void print_sample_info(DSR::GraphSettings::LOGLEVEL log_level, const eprosima::f void DSRGraph::node_subscription_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::node_subscription_thread setup"); - dsrpub_call_node = make_node_subscription_functor(); - auto [res, sub, reader] = dsrsub_node.init(dsrparticipant.getParticipant(), dsrparticipant.getNodeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_node, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getNodeTopic()->get_name(), std::pair{sub, reader}); + if (sync_mode == SyncMode::LWW) { + dsrparticipant.subscribe_node(make_node_subscription_functor_impl("LWW_NODE"), mtx_entity_creation); + } else { + dsrparticipant.subscribe_node(make_node_subscription_functor_impl("DSR_NODE", true), mtx_entity_creation); + } } void DSRGraph::edge_subscription_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::edge_subscription_thread setup"); - dsrpub_call_edge = make_edge_subscription_functor(); - auto [res, sub, reader] = dsrsub_edge.init(dsrparticipant.getParticipant(), dsrparticipant.getEdgeTopic(), dsrparticipant.get_domain_id(), dsrpub_call_edge, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getEdgeTopic()->get_name(), std::pair{sub, reader}); - + if (sync_mode == SyncMode::LWW) { + dsrparticipant.subscribe_edge(make_edge_subscription_functor_impl("LWW_EDGE"), mtx_entity_creation); + } else { + dsrparticipant.subscribe_edge(make_edge_subscription_functor_impl("DSR_EDGE"), mtx_entity_creation); + } } void DSRGraph::edge_attrs_subscription_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::edge_attrs_subscription_thread setup"); - dsrpub_call_edge_attrs = make_edge_attrs_subscription_functor(); - auto [res, sub, reader] = dsrsub_edge_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttEdgeTopic(), dsrparticipant.get_domain_id(), - dsrpub_call_edge_attrs, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getAttEdgeTopic()->get_name(), std::pair{sub, reader}); - //dsrsub_edge_attrs_stream.init(dsrparticipant.getParticipant(), "DSR_EDGE_ATTRS_STREAM", dsrparticipant.getEdgeAttrTopicName(), - // dsrpub_call_edge_attrs, true); + if (sync_mode == SyncMode::LWW) { + dsrparticipant.subscribe_edge_attrs(make_edge_attrs_subscription_functor_impl("LWW_EDGE_ATTS"), mtx_entity_creation); + } else { + dsrparticipant.subscribe_edge_attrs(make_edge_attrs_subscription_functor_impl("DSR_EDGE_ATTS"), mtx_entity_creation); + } } void DSRGraph::node_attrs_subscription_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::node_attrs_subscription_thread setup"); - dsrpub_call_node_attrs = make_node_attrs_subscription_functor(); - auto [res, sub, reader] = dsrsub_node_attrs.init(dsrparticipant.getParticipant(), dsrparticipant.getAttNodeTopic(), dsrparticipant.get_domain_id(), - dsrpub_call_node_attrs, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getAttNodeTopic()->get_name(), std::pair{sub, reader}); - + if (sync_mode == SyncMode::LWW) { + dsrparticipant.subscribe_node_attrs(make_node_attrs_subscription_functor_impl("LWW_NODE_ATTS"), mtx_entity_creation); + } else { + dsrparticipant.subscribe_node_attrs(make_node_attrs_subscription_functor_impl("DSR_NODE_ATTS"), mtx_entity_creation); + } } void DSRGraph::fullgraph_server_thread() { CORTEX_PROFILE_MIN_N("DSRGraph::fullgraph_server_thread setup"); - auto lambda_graph_request = [&](eprosima::fastdds::dds::DataReader *reader, DSR::DSRGraph *graph) + auto lambda_graph_request = [&](DSR::GraphRequest&& sample, const DSR::Transport::ReceivedSampleInfo& m_info) { [[maybe_unused]] static thread_local bool _named = []{ CORTEX_PROFILE_THREAD_NAME("fg_server"); return true; }(); CORTEX_PROFILE_ZONE_N("DSRGraph::fullgraph_server_thread callback"); - while (true) + if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); + if (!m_info.valid_data) { + return; + } + if (!network_compatibility_or_fatal("GRAPH_REQUEST", sample.protocol_version, sample.sync_mode, sync_mode)) { + return; + } { - eprosima::fastdds::dds::SampleInfo m_info; - DSR::GraphRequest sample; - if (reader->take_next_sample(&sample, &m_info) == 0) { - if (log_level == GraphSettings::LOGLEVEL::DEBUGL) print_sample_info(log_level, m_info); - if (m_info.valid_data) { - if (!network_compatibility_or_fatal("GRAPH_REQUEST", sample.protocol_version, sample.sync_mode, sync_mode)) { - continue; - } - { - std::unique_lock lck(participant_set_mutex); - if (auto [it, ok] = participant_set.emplace(sample.from, true); - it->second and !ok) - { - if (it->second) { - lck.unlock(); - auto repeated_graph = graph->engine_->export_full_graph(); - std::visit([&](auto&& payload) { - using T = std::decay_t; - T empty{}; - empty.id = -1; - empty.to_id = static_cast(sample.id); - empty.protocol_version = DSR::DSR_PROTOCOL_VERSION; - empty.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_request_answer.write(empty); - }, std::move(repeated_graph)); - continue; - } else {} - } else { - it->second = true; - lck.unlock(); - } - } - if (static_cast(sample.id) != agent_id ) { - - qDebug() << " Received Full Graph request: from " - << m_info.sample_identity.writer_guid().entityId.value; - auto full_graph_message = graph->engine_->export_full_graph(); - publish_full_graph_message(std::move(full_graph_message), static_cast(graph->get_agent_id())); - - qDebug() << "Full graph written"; - - } + std::unique_lock lck(participant_set_mutex); + if (auto [it, ok] = participant_set.emplace(sample.from, true); + it->second && !ok) + { + if (it->second) { + lck.unlock(); + auto repeated_graph = engine_->export_full_graph(); + std::visit([&](auto&& payload) { + using T = std::decay_t; + T empty{}; + empty.id = -1; + empty.to_id = static_cast(sample.id); + empty.protocol_version = DSR::DSR_PROTOCOL_VERSION; + empty.sync_mode = sync_mode_wire_value(sync_mode); + dsrparticipant.publish_graph_answer(empty); + }, std::move(repeated_graph)); + return; } } else { - break; + it->second = true; + lck.unlock(); } } + if (static_cast(sample.id) != agent_id ) { + qDebug() << " Received Full Graph request: from " << m_info.source_entity_id; + auto full_graph_message = engine_->export_full_graph(); + publish_full_graph_message(std::move(full_graph_message), static_cast(get_agent_id())); + qDebug() << "Full graph written"; + } }; - dsrpub_graph_request_call = NewMessageFn(this, lambda_graph_request); - auto [res, sub, reader] = dsrsub_graph_request.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphRequestTopic(), dsrparticipant.get_domain_id(), - dsrpub_graph_request_call, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getGraphRequestTopic()->get_name(), std::pair{sub, reader}); + dsrparticipant.subscribe_graph_requests(lambda_graph_request, mtx_entity_creation); } @@ -1369,10 +1243,11 @@ std::pair DSRGraph::fullgraph_request_thread() CORTEX_PROFILE_MIN_N("DSRGraph::fullgraph_request_thread"); std::atomic sync{false}; std::atomic repeated{false}; - dsrpub_request_answer_call = make_fullgraph_request_functor(sync, repeated); - auto [res, sub, reader] = dsrsub_request_answer.init(dsrparticipant.getParticipant(), dsrparticipant.getGraphTopic(), dsrparticipant.get_domain_id(), - dsrpub_request_answer_call, mtx_entity_creation); - dsrparticipant.add_subscriber(dsrparticipant.getGraphTopic()->get_name(), std::pair{sub, reader}); + if (sync_mode == SyncMode::LWW) { + dsrparticipant.subscribe_graph_answers(make_fullgraph_request_functor_impl("LWW_GRAPH_ANSWER", sync, repeated), mtx_entity_creation); + } else { + dsrparticipant.subscribe_graph_answers(make_fullgraph_request_functor_impl("GRAPH_ANSWER", sync, repeated), mtx_entity_creation); + } { CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread initial wait"); @@ -1382,13 +1257,13 @@ std::pair DSRGraph::fullgraph_request_thread() qDebug() << " Requesting the complete graph "; DSR::GraphRequest gr; - gr.from = dsrparticipant.getParticipant()->get_qos().name().to_string(); + gr.from = dsrparticipant.participant_name(); gr.id = static_cast(agent_id); gr.protocol_version = DSR::DSR_PROTOCOL_VERSION; gr.sync_mode = sync_mode_wire_value(sync_mode); { CORTEX_PROFILE_DETAIL_N("DSRGraph::fullgraph_request_thread send request"); - dsrpub_graph_request.write(gr); + dsrparticipant.publish_graph_request(gr); } @@ -1402,12 +1277,9 @@ std::pair DSRGraph::fullgraph_request_thread() qInfo() << " Waiting for the graph ... seconds to timeout [" << std::ceil(std::chrono::duration_cast(end - begin).count() / 10) / 100.0 << "/" << TIMEOUT / 1000 * 3 << "] "; - dsrpub_graph_request.write(gr); + dsrparticipant.publish_graph_request(gr); } - dsrparticipant.delete_publisher(dsrparticipant.getGraphRequestTopic()->get_name()); - dsrparticipant.delete_subscriber(dsrparticipant.getGraphTopic()->get_name()); - return { sync, repeated }; } diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 4069d44b..72f5229b 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -530,7 +530,7 @@ namespace DSR signal.agent_id = agent_id; signal.protocol_version = DSR::DSR_PROTOCOL_VERSION; signal.sync_mode = sync_mode_wire_value(sync_mode); - dsrpub_node.write(signal); + dsrparticipant.publish_node(signal); } } @@ -763,53 +763,35 @@ namespace DSR // are destroyed, preventing use-after-free data races on shutdown. ThreadPool tp, tp_delta_attr; - //Custom function for each rtps topic - class NewMessageFn { - public: - DSRGraph *graph{}; - std::function f; - - NewMessageFn(DSRGraph *graph_, - std::function f_) - : graph(graph_), f(std::move(f_)) {} - - NewMessageFn() = default; - - void operator()(eprosima::fastdds::dds::DataReader* reader) const { f(reader, graph); }; - }; - - NewMessageFn make_node_subscription_functor(); - NewMessageFn make_edge_subscription_functor(); - NewMessageFn make_edge_attrs_subscription_functor(); - NewMessageFn make_node_attrs_subscription_functor(); - NewMessageFn make_fullgraph_request_functor(std::atomic& sync, std::atomic& repeated); + template + using SampleCallback = std::function; template - NewMessageFn make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal = false); + SampleCallback make_node_subscription_functor_impl(const char* channel, bool clear_deleted_signal = false); template - NewMessageFn make_edge_subscription_functor_impl(const char* channel); + SampleCallback make_edge_subscription_functor_impl(const char* channel); template - NewMessageFn make_edge_attrs_subscription_functor_impl(const char* channel); + SampleCallback make_edge_attrs_subscription_functor_impl(const char* channel); template - NewMessageFn make_node_attrs_subscription_functor_impl(const char* channel); + SampleCallback make_node_attrs_subscription_functor_impl(const char* channel); template - NewMessageFn make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated); + SampleCallback make_fullgraph_request_functor_impl(const char* channel, std::atomic& sync, std::atomic& repeated); //Custom function for each rtps topic class ParticipantChangeFn { public: DSRGraph *graph{}; - std::function f; + using status_type = DSR::Transport::ParticipantDiscoveryStatus; + using info_type = DSR::Transport::ParticipantDiscoveryInfo; + std::function f; ParticipantChangeFn(DSRGraph *graph_, - std::function f_) + std::function f_) : graph(graph_), f(std::move(f_)) {} ParticipantChangeFn() = default; - void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, - const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) const + void operator()(status_type status, const info_type& info) const { f(graph, status, info); }; @@ -834,31 +816,6 @@ namespace DSR std::unordered_map participant_set; mutable std::mutex participant_set_mutex; - - DSRPublisher dsrpub_node; - DSRSubscriber dsrsub_node; - NewMessageFn dsrpub_call_node; - - DSRPublisher dsrpub_edge; - DSRSubscriber dsrsub_edge; - NewMessageFn dsrpub_call_edge; - - DSRPublisher dsrpub_node_attrs; - DSRSubscriber dsrsub_node_attrs; - NewMessageFn dsrpub_call_node_attrs; - - DSRPublisher dsrpub_edge_attrs; - DSRSubscriber dsrsub_edge_attrs; - NewMessageFn dsrpub_call_edge_attrs; - - DSRSubscriber dsrsub_graph_request; - DSRPublisher dsrpub_graph_request; - NewMessageFn dsrpub_graph_request_call; - - DSRSubscriber dsrsub_request_answer; - DSRPublisher dsrpub_request_answer; - NewMessageFn dsrpub_request_answer_call; - Q_OBJECT signals: void update_node_signal(uint64_t, const std::string &type, DSR::SignalInfo info = {}); diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index d92fdb47..64661c9a 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -13,12 +13,17 @@ #include #include -class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP +class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP< + DSRParticipant, + eprosima::fastdds::dds::DomainParticipant, + std::pair, + std::pair, + std::function> { public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id=0, uint8_t sync_mode_wire = 0); + [[nodiscard]] std::tuple init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, discovery_callback_type fn, int8_t domain_id=0, uint8_t sync_mode_wire = 0); [[nodiscard]] int8_t get_domain_id() const { return domain_id_; } [[nodiscard]] uint8_t get_sync_mode_wire() const { return sync_mode_wire_; } [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; @@ -28,6 +33,7 @@ class DSRParticipant : public DSR::Transport::ParticipantTransportCRTPget_name().data();} [[nodiscard]] const char *getNodeAttrTopicName() const { return dsrNodeAttrType->get_name().data();} [[nodiscard]] const char *getEdgeAttrTopicName() const { return dsrEdgeAttrType->get_name().data();} + [[nodiscard]] std::string participant_name() const; [[nodiscard]] eprosima::fastdds::dds::Topic* getNodeTopic() { return topic_node; } [[nodiscard]] eprosima::fastdds::dds::Topic* getEdgeTopic() { return topic_edge; } @@ -37,14 +43,105 @@ class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP); - void add_publisher_impl(const std::string& id, std::pair); + void add_subscriber_impl(const std::string& id, subscriber_entry_type); + void add_publisher_impl(const std::string& id, publisher_entry_type); void delete_subscriber_impl(const std::string& id); void delete_publisher_impl(const std::string& id); + bool init_builtin_publishers(); + + template + bool subscribe_node(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("node", sub_node_, topic_node, std::forward(callback), mtx); + } + + template + bool subscribe_edge(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("edge", sub_edge_, topic_edge, std::forward(callback), mtx); + } + + template + bool subscribe_node_attrs(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("node_attrs", sub_node_attrs_, topic_node_att, std::forward(callback), mtx); + } + + template + bool subscribe_edge_attrs(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("edge_attrs", sub_edge_attrs_, topic_edge_att, std::forward(callback), mtx); + } + + template + bool subscribe_graph_requests(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("graph_request", sub_graph_request_, topic_graph_request, std::forward(callback), mtx); + } + + template + bool subscribe_graph_answers(Callback&& callback, std::mutex& mtx) + { + return subscribe_impl("graph_answer", sub_graph_answer_, topic_graph, std::forward(callback), mtx); + } + + bool publish_node(const DSR::MvregNodeMsg& object) { return pub_node_.write(object); } + bool publish_node(const DSR::LWWNodeMsg& object) { return pub_node_.write(object); } + bool publish_edge(const DSR::MvregEdgeMsg& object) { return pub_edge_.write(object); } + bool publish_edge(const DSR::LWWEdgeMsg& object) { return pub_edge_.write(object); } + bool publish_node_attrs(const DSR::MvregNodeAttrVec& object) { return pub_node_attrs_.write(object); } + bool publish_node_attrs(const DSR::LWWNodeAttrVec& object) { return pub_node_attrs_.write(object); } + bool publish_edge_attrs(const DSR::MvregEdgeAttrVec& object) { return pub_edge_attrs_.write(object); } + bool publish_edge_attrs(const DSR::LWWEdgeAttrVec& object) { return pub_edge_attrs_.write(object); } + bool publish_graph_request(const DSR::GraphRequest& object) { return pub_graph_request_.write(object); } + bool publish_graph_answer(const DSR::OrMap& object) { return pub_graph_answer_.write(object); } + bool publish_graph_answer(const DSR::LWWGraphSnapshot& object) { return pub_graph_answer_.write(object); } + void remove_participant_and_entities_impl(); private: + template + bool subscribe_impl(const char* id, + DSRSubscriber& subscriber, + eprosima::fastdds::dds::Topic* topic, + Callback&& callback, + std::mutex& mtx) + { + auto entity_id_to_u32 = [](const auto& entity_id) -> uint32_t + { + return (static_cast(entity_id.value[0]) << 24) | + (static_cast(entity_id.value[1]) << 16) | + (static_cast(entity_id.value[2]) << 8) | + static_cast(entity_id.value[3]); + }; + + auto reader_callback = [callback = std::forward(callback), entity_id_to_u32](eprosima::fastdds::dds::DataReader* reader) mutable + { + while (true) + { + eprosima::fastdds::dds::SampleInfo info; + Sample sample; + if (reader->take_next_sample(&sample, &info) != 0) { + break; + } + + callback(std::move(sample), DSR::Transport::ReceivedSampleInfo{ + .valid_data = info.valid_data, + .source_entity_id = entity_id_to_u32(info.sample_identity.writer_guid().entityId), + .source_timestamp_ns = static_cast(info.source_timestamp.seconds()) * 1000000000LL + info.source_timestamp.nanosec(), + .reception_timestamp_ns = static_cast(info.reception_timestamp.seconds()) * 1000000000LL + info.reception_timestamp.nanosec() + }); + } + }; + + auto [res, sub, reader] = subscriber.init(mp_participant, topic, domain_id_, std::move(reader_callback), mtx); + if (res && topic != nullptr) { + add_subscriber(id, std::pair{sub, reader}); + } + return res; + } + int8_t domain_id_ {0}; uint8_t sync_mode_wire_ {0}; bool cleanup_enabled_ {true}; @@ -69,11 +166,24 @@ class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP&& fn) + explicit ParticpantListener(discovery_callback_type&& fn) : eprosima::fastdds::dds::DomainParticipantListener(), f(std::move(fn)){}; ~ParticpantListener() override = default; @@ -83,13 +193,24 @@ class DSRParticipant : public DSR::Transport::ParticipantTransportCRTP f; + discovery_callback_type f; //int n_matched; }; std::unique_ptr m_listener; diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index cfd131d3..829b1c77 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -12,7 +12,10 @@ #include #include -class DSRPublisher : public DSR::Transport::PublisherTransportCRTP +class DSRPublisher : public DSR::Transport::PublisherTransportCRTP< + DSRPublisher, + eprosima::fastdds::dds::DomainParticipant, + eprosima::fastdds::dds::Topic> { public: DSRPublisher(); diff --git a/core/include/dsr/core/rtps/dsrsubscriber.h b/core/include/dsr/core/rtps/dsrsubscriber.h index a3b0b7f8..3a1d8d81 100644 --- a/core/include/dsr/core/rtps/dsrsubscriber.h +++ b/core/include/dsr/core/rtps/dsrsubscriber.h @@ -9,21 +9,27 @@ #include -class DSRSubscriber : public DSR::Transport::SubscriberTransportCRTP +class DSRSubscriber : public DSR::Transport::SubscriberTransportCRTP< + DSRSubscriber, + eprosima::fastdds::dds::DomainParticipant, + eprosima::fastdds::dds::Topic, + std::function> { public: + using subscriber_handle_type = eprosima::fastdds::dds::Subscriber; + using reader_handle_type = eprosima::fastdds::dds::DataReader; DSRSubscriber(); virtual ~DSRSubscriber(); - [[nodiscard]] std::tuple - init_impl(eprosima::fastdds::dds::DomainParticipant *mp_participant_, - eprosima::fastdds::dds::Topic *topic, + [[nodiscard]] std::tuple + init_impl(participant_handle_type *mp_participant_, + topic_handle_type *topic, int8_t domain_id, - const std::function& f_, + callback_type f_, std::mutex& mtx, bool isStreamData = false); - eprosima::fastdds::dds::Subscriber *getSubscriber_impl(); - eprosima::fastdds::dds::DataReader *getDataReader_impl(); + subscriber_handle_type *getSubscriber_impl(); + reader_handle_type *getDataReader_impl(); private: eprosima::fastdds::dds::DomainParticipant *mp_participant; @@ -40,7 +46,7 @@ class DSRSubscriber : public DSR::Transport::SubscriberTransportCRTP f; + callback_type f; } m_listener; diff --git a/core/include/dsr/core/transport/transport_crtp.h b/core/include/dsr/core/transport/transport_crtp.h index 5c3b487a..74b90b67 100644 --- a/core/include/dsr/core/transport/transport_crtp.h +++ b/core/include/dsr/core/transport/transport_crtp.h @@ -1,55 +1,71 @@ #pragma once #include -#include #include #include -#include #include -#include -#include - namespace DSR::Transport { -template +enum class ParticipantDiscoveryStatus : uint8_t +{ + discovered, + removed, + dropped, + other +}; + +struct ParticipantDiscoveryInfo +{ + std::string participant_name; +}; + +struct ReceivedSampleInfo +{ + bool valid_data{false}; + uint32_t source_entity_id{0}; + int64_t source_timestamp_ns{0}; + int64_t reception_timestamp_ns{0}; +}; + +template class ParticipantTransportCRTP { public: + using participant_handle_type = ParticipantHandle; + using subscriber_entry_type = SubscriberEntry; + using publisher_entry_type = PublisherEntry; + using discovery_callback_type = DiscoveryCallback; + auto init( uint32_t agent_id, const std::string& agent_name, int localhost, - std::function fn, + discovery_callback_type fn, int8_t domain_id = 0, uint8_t sync_mode_wire = 0) { return derived().init_impl(agent_id, agent_name, localhost, std::move(fn), domain_id, sync_mode_wire); } - template - void add_subscriber(Id&& id, SubscriberEntry&& entry) + void add_subscriber(const std::string& id, subscriber_entry_type entry) { - derived().add_subscriber_impl(std::forward(id), std::forward(entry)); + derived().add_subscriber_impl(id, std::move(entry)); } - template - void add_publisher(Id&& id, PublisherEntry&& entry) + void add_publisher(const std::string& id, publisher_entry_type entry) { - derived().add_publisher_impl(std::forward(id), std::forward(entry)); + derived().add_publisher_impl(id, std::move(entry)); } - template - void delete_subscriber(Id&& id) + void delete_subscriber(const std::string& id) { - derived().delete_subscriber_impl(std::forward(id)); + derived().delete_subscriber_impl(id); } - template - void delete_publisher(Id&& id) + void delete_publisher(const std::string& id) { - derived().delete_publisher_impl(std::forward(id)); + derived().delete_publisher_impl(id); } void remove_participant_and_entities() @@ -61,14 +77,16 @@ class ParticipantTransportCRTP Derived& derived() { return static_cast(*this); } }; -template +template class PublisherTransportCRTP { public: - template + using participant_handle_type = ParticipantHandle; + using topic_handle_type = TopicHandle; + auto init( - ParticipantHandle* participant, - TopicHandle* topic, + participant_handle_type* participant, + topic_handle_type* topic, int8_t domain_id, bool is_stream_data = false) { @@ -91,16 +109,19 @@ class PublisherTransportCRTP const Derived& derived() const { return static_cast(*this); } }; -template +template class SubscriberTransportCRTP { public: - template + using participant_handle_type = ParticipantHandle; + using topic_handle_type = TopicHandle; + using callback_type = Callback; + auto init( - ParticipantHandle* participant, - TopicHandle* topic, + participant_handle_type* participant, + topic_handle_type* topic, int8_t domain_id, - Callback&& callback, + callback_type callback, std::mutex& creation_mutex, bool is_stream_data = false) { @@ -108,7 +129,7 @@ class SubscriberTransportCRTP participant, topic, domain_id, - std::forward(callback), + std::move(callback), creation_mutex, is_stream_data); } diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 9f49417e..7c13b57f 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -109,7 +109,7 @@ DSRParticipant::~DSRParticipant() } -std::tuple DSRParticipant::init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn, int8_t domain_id, uint8_t sync_mode_wire) +std::tuple DSRParticipant::init_impl(uint32_t agent_id, const std::string& agent_name, int localhost, discovery_callback_type fn, int8_t domain_id, uint8_t sync_mode_wire) { domain_id_ = domain_id; sync_mode_wire_ = sync_mode_wire; @@ -204,6 +204,32 @@ eprosima::fastdds::dds::DomainParticipant *DSRParticipant::getParticipant() return mp_participant; } +std::string DSRParticipant::participant_name() const +{ + if (mp_participant == nullptr) { + return {}; + } + return mp_participant->get_qos().name().to_string(); +} + +bool DSRParticipant::init_builtin_publishers() +{ + auto init_one = [&](const char* id, DSRPublisher& publisher, eprosima::fastdds::dds::Topic* topic) { + auto [res, pub, writer] = publisher.init(mp_participant, topic, domain_id_); + if (res && topic != nullptr) { + add_publisher(id, std::pair{pub, writer}); + } + return res; + }; + + return init_one("node", pub_node_, topic_node) && + init_one("node_attrs", pub_node_attrs_, topic_node_att) && + init_one("edge", pub_edge_, topic_edge) && + init_one("edge_attrs", pub_edge_attrs_, topic_edge_att) && + init_one("graph_request", pub_graph_request_, topic_graph_request) && + init_one("graph_answer", pub_graph_answer_, topic_graph); +} + void DSRParticipant::remove_participant_and_entities_impl() { //if (!cleanup_enabled_) { @@ -331,12 +357,12 @@ const eprosima::fastdds::rtps::GUID_t& DSRParticipant::getID() const return mp_participant->guid(); } -void DSRParticipant::add_subscriber_impl(const std::string& id, std::pair val) +void DSRParticipant::add_subscriber_impl(const std::string& id, subscriber_entry_type val) { std::unique_lock lck (sub_mtx); subscribers.emplace(id, val); } -void DSRParticipant::add_publisher_impl(const std::string& id, std::pair val) +void DSRParticipant::add_publisher_impl(const std::string& id, publisher_entry_type val) { std::unique_lock lck (pub_mtx); publishers.emplace(id, val); diff --git a/core/rtps/dsrsubscriber.cpp b/core/rtps/dsrsubscriber.cpp index 724b32e2..2332d1be 100644 --- a/core/rtps/dsrsubscriber.cpp +++ b/core/rtps/dsrsubscriber.cpp @@ -32,11 +32,11 @@ DSRSubscriber::DSRSubscriber() : mp_participant(nullptr), mp_subscriber(nullptr) DSRSubscriber::~DSRSubscriber() = default; -std::tuple - DSRSubscriber::init_impl(eprosima::fastdds::dds::DomainParticipant *mp_participant_, - eprosima::fastdds::dds::Topic *topic, +std::tuple + DSRSubscriber::init_impl(participant_handle_type *mp_participant_, + topic_handle_type *topic, int8_t domain_id, - const std::function& f_, + callback_type f_, std::mutex& mtx, bool isStreamData) { @@ -102,11 +102,11 @@ std::tuple Date: Sat, 25 Apr 2026 17:19:31 +0200 Subject: [PATCH 31/38] refactor: add lww our of order synchronization add out of orden sync tests with fake transport --- api/dsr_lww_sync_engine.cpp | 74 +- api/include/dsr/api/dsr_lww_sync_engine.h | 9 + tests/CMakeLists.txt | 4 +- tests/synchronization/fake_network_tests.cpp | 1151 ++++++++++++++++++ tests/synchronization/lww_sync_engine.cpp | 48 +- tests/transport/fake_network.h | 289 +++++ 6 files changed, 1519 insertions(+), 56 deletions(-) create mode 100644 tests/synchronization/fake_network_tests.cpp create mode 100644 tests/transport/fake_network.h diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 4a3816de..759a7fa7 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -83,7 +83,10 @@ LWWSyncEngine::LWWSyncEngine(SyncEngineHost& host, const LWWSyncEngine& other) nodes_(other.nodes_), edges_(other.edges_), node_tombstones_(other.node_tombstones_), - edge_tombstones_(other.edge_tombstones_) + edge_tombstones_(other.edge_tombstones_), + pending_node_attrs_(other.pending_node_attrs_), + pending_edges_(other.pending_edges_), + pending_edge_attrs_(other.pending_edge_attrs_) { for (const auto& [key, state] : edges_) { LWW::edge_index_insert(from_idx_, to_idx_, type_idx_, state); @@ -131,11 +134,23 @@ void LWWSyncEngine::prune_tombstones(uint64_t now) void LWWSyncEngine::store_node_tombstone(uint64_t id, Version version, uint64_t now) { node_tombstones_[id] = LWW::make_tombstone(version, now, tombstone_window_ms_); + pending_node_attrs_.erase(id); + std::erase_if(pending_edges_, [id](const LWWEdgeMsg& e) { return e.from == id || e.to == id; }); + std::erase_if(pending_edge_attrs_, [id](const auto& kv) { return kv.first.from == id || kv.first.to == id; }); } void LWWSyncEngine::store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now) { - edge_tombstones_[edge_key(from, to, type)] = LWW::make_tombstone(version, now, tombstone_window_ms_); + auto key = edge_key(from, to, type); + edge_tombstones_[key] = LWW::make_tombstone(version, now, tombstone_window_ms_); + if (auto it = pending_edge_attrs_.find(key); it != pending_edge_attrs_.end()) { + std::erase_if(it->second, [&version](const LWWEdgeAttrMsg& a) { + return !is_newer(version_of(a.timestamp, a.agent_id), version); + }); + if (it->second.empty()) { + pending_edge_attrs_.erase(it); + } + } } void LWWSyncEngine::erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges) @@ -483,6 +498,14 @@ void LWWSyncEngine::apply_remote_node_delta(NodeDeltaMessage&& delta) host_.update_maps_node_insert(payload->id, payload->name, payload->type, collect_outgoing_edge_keys(from_idx_, payload->id)); } host_.on_remote_node_updated(payload->id, payload->type, payload->agent_id); + + if (auto pit = pending_node_attrs_.find(payload->id); pit != pending_node_attrs_.end()) { + LWWNodeAttrVec vec; + vec.vec = std::move(pit->second); + pending_node_attrs_.erase(pit); + apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage{std::move(vec)}); + } + flush_pending_edges(); } void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) @@ -501,11 +524,9 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) if (LWW::delta_is_stale(edge_tombstones_, edges_, edge_key_view(payload->from, payload->to, payload->type), version)) { return; } - if (!nodes_.contains(payload->from) || !nodes_.contains(payload->to)) { - return; - } auto key = edge_key(payload->from, payload->to, payload->type); + if (payload->deleted) { CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_delta delete"); std::optional deleted_edge; @@ -520,6 +541,11 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) return; } + if (!nodes_.contains(payload->from) || !nodes_.contains(payload->to)) { + pending_edges_.push_back(std::move(*payload)); + return; + } + { CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_delta upsert"); EdgeState state = LWW::to_edge_state(*payload); @@ -530,6 +556,14 @@ void LWWSyncEngine::apply_remote_edge_delta(EdgeDeltaMessage&& delta) edge_tombstones_.erase(key); host_.update_maps_edge_insert(payload->from, payload->to, payload->type); } + + if (auto pit = pending_edge_attrs_.find(key); pit != pending_edge_attrs_.end()) { + LWWEdgeAttrVec vec; + vec.vec = std::move(pit->second); + pending_edge_attrs_.erase(pit); + apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage{std::move(vec)}); + } + host_.on_remote_edge_updated(payload->from, payload->to, payload->type, payload->agent_id); } @@ -550,12 +584,16 @@ void LWWSyncEngine::apply_remote_node_attr_batch(NodeAttrDeltaBatchMessage&& bat std::unordered_map changes; { CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_node_attr_batch merge"); - for (const auto& item : payload->vec) { + for (auto& item : payload->vec) { + auto version = version_of(item.timestamp, item.agent_id); auto it = nodes_.find(item.node_id); if (it == nodes_.end()) { + auto ts_it = node_tombstones_.find(item.node_id); + if (ts_it == node_tombstones_.end() || is_newer(version, ts_it->second.version)) { + pending_node_attrs_[item.node_id].push_back(item); + } continue; } - auto version = version_of(item.timestamp, item.agent_id); auto attr_it = it->second.attrs.find(item.attr_name); if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { continue; @@ -598,12 +636,16 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat std::unordered_map changes; { CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); - for (const auto& item : payload->vec) { + for (auto& item : payload->vec) { + auto version = version_of(item.timestamp, item.agent_id); auto it = edges_.find(edge_key_view(item.from, item.to, item.type)); if (it == edges_.end()) { + auto ts_it = edge_tombstones_.find(edge_key_view(item.from, item.to, item.type)); + if (ts_it == edge_tombstones_.end() || is_newer(version, ts_it->second.version)) { + pending_edge_attrs_[edge_key(item.from, item.to, item.type)].push_back(item); + } continue; } - auto version = version_of(item.timestamp, item.agent_id); auto attr_it = it->second.attrs.find(item.attr_name); if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { continue; @@ -717,3 +759,17 @@ const LWW::NodeState* LWWSyncEngine::get_node_ptr(uint64_t id) const } return nullptr; } + +void LWWSyncEngine::flush_pending_edges() +{ + if (pending_edges_.empty()) return; + std::vector still_pending; + for (auto& msg : pending_edges_) { + if (!nodes_.contains(msg.from) || !nodes_.contains(msg.to)) { + still_pending.push_back(std::move(msg)); + continue; + } + apply_remote_edge_delta(EdgeDeltaMessage{std::move(msg)}); + } + pending_edges_ = std::move(still_pending); +} diff --git a/api/include/dsr/api/dsr_lww_sync_engine.h b/api/include/dsr/api/dsr_lww_sync_engine.h index 5ab6b860..a8eaa83c 100644 --- a/api/include/dsr/api/dsr_lww_sync_engine.h +++ b/api/include/dsr/api/dsr_lww_sync_engine.h @@ -79,6 +79,8 @@ class LWWSyncEngine final : public SyncEngine void store_edge_tombstone(uint64_t from, uint64_t to, const std::string& type, Version version, uint64_t now); void erase_related_edges(uint64_t node_id, Version version, uint64_t now, std::vector* removed_edges = nullptr); + void flush_pending_edges(); + SyncEngineHost& host_; uint64_t tombstone_window_ms_; uint64_t logical_clock_ms_{0}; @@ -88,6 +90,13 @@ class LWWSyncEngine final : public SyncEngine std::unordered_map node_tombstones_; std::unordered_map edge_tombstones_; + // Pending buffers for out-of-order delivery. + // Items are buffered when their parent entity doesn't exist yet. + // The only reason to discard is staleness (version ≤ stored/tombstone), never missing parent. + std::unordered_map> pending_node_attrs_; + std::vector pending_edges_; + std::unordered_map, EdgeKeyHash, EdgeKeyEqual> pending_edge_attrs_; + FromIndex from_idx_; ToIndex to_idx_; TypeIndex type_idx_; diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 20579ab8..5359102d 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -24,7 +24,7 @@ find_package(Eigen3 3.3 REQUIRED NO_MODULE) -add_executable(tests test.cpp +add_executable(tests test.cpp graph/edge_operations.cpp graph/node_operations.cpp graph/graph_operations.cpp @@ -37,6 +37,8 @@ add_executable(tests test.cpp synchronization/type_translation.cpp synchronization/lww_sync_engine.cpp synchronization/graph_signals.cpp + synchronization/fake_network_tests.cpp + transport/fake_network.h utils.h) diff --git a/tests/synchronization/fake_network_tests.cpp b/tests/synchronization/fake_network_tests.cpp new file mode 100644 index 00000000..07fed591 --- /dev/null +++ b/tests/synchronization/fake_network_tests.cpp @@ -0,0 +1,1151 @@ +#include + +#include "../transport/fake_network.h" +#include "dsr/core/types/user_types.h" +#include "dsr/core/types/internal_types.h" +#include "dsr/core/types/type_checking/dsr_edge_type.h" +#include "dsr/core/types/type_checking/dsr_node_type.h" + +using namespace DSR; +using namespace DSR::Test; + +// ────────────────────────────────────────────────────────────────────────────── +// Test helpers +// ────────────────────────────────────────────────────────────────────────────── + +namespace { + +Node make_robot(uint64_t id, uint32_t agent_id, const std::string& name, uint64_t ts = 100) +{ + auto n = Node::create(name); + n.id(id); + n.agent_id(agent_id); + n.attrs()["level"] = Attribute(0, ts, agent_id); + return n; +} + +LWWNodeAttrVec make_attr_batch(uint64_t node_id, uint32_t agent_id, int level, uint64_t ts) +{ + LWWNodeAttrMsg msg; + msg.node_id = node_id; + msg.attr_name = "level"; + msg.value = Attribute(level, ts, agent_id); + msg.agent_id = agent_id; + msg.timestamp = ts; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + LWWNodeAttrVec batch; + batch.vec.push_back(std::move(msg)); + return batch; +} + +LWWNodeMsg make_insert_msg(uint64_t node_id, uint32_t agent_id, const std::string& name, uint64_t ts) +{ + LWWNodeMsg msg; + msg.id = node_id; + msg.type = robot_node_type::attr_name; + msg.name = name; + msg.agent_id = agent_id; + msg.timestamp = ts; + msg.deleted = false; + msg.attrs["level"] = Attribute(0, ts, agent_id); + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; +} + +LWWEdgeAttrVec make_edge_attr_batch(uint64_t from, uint64_t to, uint32_t agent_id, int weight, uint64_t ts) +{ + LWWEdgeAttrMsg msg; + msg.from = from; + msg.to = to; + msg.type = std::string(RT_edge_type::attr_name); + msg.attr_name = "weight"; + msg.value = Attribute(weight, ts, agent_id); + msg.agent_id = agent_id; + msg.timestamp = ts; + msg.deleted = false; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + LWWEdgeAttrVec batch; + batch.vec.push_back(std::move(msg)); + return batch; +} + +LWWNodeMsg make_node_delete_msg(uint64_t node_id, uint32_t agent_id, uint64_t ts) +{ + LWWNodeMsg msg; + msg.id = node_id; + msg.type = robot_node_type::attr_name; + msg.name = ""; + msg.agent_id = agent_id; + msg.timestamp = ts; + msg.deleted = true; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; +} + +LWWEdgeMsg make_edge_msg(uint64_t from, uint64_t to, uint32_t agent_id, uint64_t ts, bool deleted = false) +{ + LWWEdgeMsg msg; + msg.from = from; + msg.to = to; + msg.type = std::string(RT_edge_type::attr_name); + msg.agent_id = agent_id; + msg.timestamp = ts; + msg.deleted = deleted; + msg.protocol_version = DSR_PROTOCOL_VERSION; + msg.sync_mode = sync_mode_wire_value(SyncMode::LWW); + return msg; +} + +// Extract the LWW tombstone timestamp from a node deletion effect. +// Returns 0 if the effect doesn't carry an LWW delta. +uint64_t tombstone_ts(const NodeMutationEffect& del_effect) +{ + if (!del_effect.node_delta.has_value()) return 0; + const auto* lww = std::get_if(&*del_effect.node_delta); + return lww ? lww->timestamp : 0; +} + +} // namespace + +// ────────────────────────────────────────────────────────────────────────────── +// Basic delivery +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW insert propagates to peer", "[FAKE_NET][LWW]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto effect = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(effect.applied); + net.post(1, effect); + net.deliver_all(); + + REQUIRE(A.get_node(1000).has_value()); + REQUIRE(B.get_node(1000).has_value()); +} + +TEST_CASE("FakeNetwork: CRDT insert propagates to peer", "[FAKE_NET][CRDT]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + auto effect = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(effect.applied); + net.post(1, effect); + net.deliver_all(); + + REQUIRE(A.get_node(1000).has_value()); + REQUIRE(B.get_node(1000).has_value()); +} + +TEST_CASE("FakeNetwork: LWW bidirectional inserts converge", "[FAKE_NET][LWW]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto ea = A.insert_node(make_robot(1000, 1, "robot_a")); + auto eb = B.insert_node(make_robot(2000, 2, "robot_b")); + REQUIRE(ea.applied); + REQUIRE(eb.applied); + net.post(1, ea); + net.post(2, eb); + net.deliver_all(); + + REQUIRE(A.get_node(2000).has_value()); + REQUIRE(B.get_node(1000).has_value()); + REQUIRE(A.size() == B.size()); +} + +TEST_CASE("FakeNetwork: CRDT bidirectional inserts converge", "[FAKE_NET][CRDT]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + auto ea = A.insert_node(make_robot(1000, 1, "robot_a")); + auto eb = B.insert_node(make_robot(2000, 2, "robot_b")); + REQUIRE(ea.applied); + REQUIRE(eb.applied); + net.post(1, ea); + net.post(2, eb); + net.deliver_all(); + + REQUIRE(A.get_node(2000).has_value()); + REQUIRE(B.get_node(1000).has_value()); + REQUIRE(A.size() == B.size()); +} + +TEST_CASE("FakeNetwork: LWW insert fans out to all agents in a three-node cluster", + "[FAKE_NET][LWW]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + auto& C = net.add_agent(3, SyncMode::LWW); + + auto e = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e.applied); + net.post(1, e); + net.deliver_all(); + + REQUIRE(B.get_node(1000).has_value()); + REQUIRE(C.get_node(1000).has_value()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// LWW attribute update ordering +// +// Timestamps must be anchored to the actual delta the engine emitted so that +// "newer" and "stale" are meaningful relative to the stored attr version. +// ────────────────────────────────────────────────────────────────────────────── + +// Return the LWW version timestamp from a node insertion delta. +// The engine stores all attrs with this timestamp as their LWW version, so +// any attr-batch update must use a timestamp > this to be accepted. +static uint64_t node_version_ts(const NodeMutationEffect& effect) +{ + REQUIRE(effect.node_delta.has_value()); + const auto* lww = std::get_if(&*effect.node_delta); + REQUIRE(lww != nullptr); + return lww->timestamp; +} + +// Same for edge insertion deltas. +static uint64_t edge_version_ts(const EdgeMutationEffect& effect) +{ + REQUIRE(effect.edge_delta.has_value()); + const auto* lww = std::get_if(&*effect.edge_delta); + REQUIRE(lww != nullptr); + return lww->timestamp; +} + +TEST_CASE("FakeNetwork: LWW stale attr update (older ts) is rejected", "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto effect = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(effect.applied); + const uint64_t base = node_version_ts(effect); + net.post(1, effect); + net.deliver_all(); + + // Apply newer update first (base+200 → level=9), then a stale one (base-1 → level=3). + B.engine->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 9, base + 200)}); // newer + B.engine->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 3, base - 1)}); // stale + + auto node = B.get_node(1000); + REQUIRE(node.has_value()); + REQUIRE(node->attrs().at("level").dec() == 9); // stale must not overwrite +} + +TEST_CASE("FakeNetwork: LWW out-of-order attr delivery settles on highest timestamp", + "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto effect = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(effect.applied); + const uint64_t base = node_version_ts(effect); + net.post(1, effect); + net.deliver_all(); + + // Deliver to each engine in ascending timestamp order (older first). + // Both should end up with the value at base+300. + for (auto* eng : {A.engine.get(), B.engine.get()}) { + eng->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 42, base + 200)}); + eng->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 99, base + 300)}); + } + + REQUIRE(A.get_node(1000)->attrs().at("level").dec() == 99); + REQUIRE(B.get_node(1000)->attrs().at("level").dec() == 99); +} + +TEST_CASE("FakeNetwork: LWW reverse attr delivery still converges to highest timestamp", + "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto effect = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(effect.applied); + const uint64_t base = node_version_ts(effect); + net.post(1, effect); + net.deliver_all(); + + // Newer batch arrives first at both engines, then the older one. + // Both should still settle on base+300. + for (auto* eng : {A.engine.get(), B.engine.get()}) { + eng->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 99, base + 300)}); // newer first + eng->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 42, base + 200)}); // older second + } + + REQUIRE(A.get_node(1000)->attrs().at("level").dec() == 99); + REQUIRE(B.get_node(1000)->attrs().at("level").dec() == 99); +} + +// ────────────────────────────────────────────────────────────────────────────── +// LWW delete vs. insert conflicts +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW delete (newer ts) suppresses concurrent stale insert", + "[FAKE_NET][LWW][CONFLICT]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Both agents have node 1000. + { + auto e = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e.applied); + net.post(1, e); + net.deliver_all(); + } + + // A deletes node 1000 and retrieves the tombstone timestamp. + auto del_effect = A.delete_node(1000); + REQUIRE(del_effect.applied); + REQUIRE(del_effect.node_delta.has_value()); + const uint64_t ts_del = tombstone_ts(del_effect); + REQUIRE(ts_del > 0); + + net.post(1, del_effect); + // A "remote" agent 3 sends a stale insert (ts < tombstone). + net.post_raw(3, NodeDeltaMessage{make_insert_msg(1000, 3, "ghost", ts_del - 1)}); + net.deliver_all(); + + REQUIRE_FALSE(A.get_node(1000).has_value()); + REQUIRE_FALSE(B.get_node(1000).has_value()); +} + +TEST_CASE("FakeNetwork: LWW newer remote insert (higher ts) overrides prior delete", + "[FAKE_NET][LWW][CONFLICT]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Both agents have node 1000. + { + auto e = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e.applied); + net.post(1, e); + net.deliver_all(); + } + + // A deletes node 1000 and retrieves the tombstone timestamp. + auto del_effect = A.delete_node(1000); + REQUIRE(del_effect.applied); + const uint64_t ts_del = tombstone_ts(del_effect); + REQUIRE(ts_del > 0); + + net.post(1, del_effect); + // A "remote" agent 3 sends a fresher insert (ts > tombstone). + net.post_raw(3, NodeDeltaMessage{make_insert_msg(1000, 3, "phoenix", ts_del + 10)}); + net.deliver_all(); + + auto nodeA = A.get_node(1000); + auto nodeB = B.get_node(1000); + REQUIRE(nodeA.has_value()); + REQUIRE(nodeB.has_value()); + REQUIRE(nodeA->name() == "phoenix"); + REQUIRE(nodeB->name() == "phoenix"); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Delivery controls: drop + full-graph recovery +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: dropped deltas are recovered by full-graph sync", + "[FAKE_NET][LWW][RECOVERY]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto e1 = A.insert_node(make_robot(1000, 1, "robot_a")); + auto e2 = A.insert_node(make_robot(2000, 1, "robot_b")); + REQUIRE(e1.applied); + REQUIRE(e2.applied); + net.post(1, e1); + net.post(1, e2); + + // Drop all queued deltas — B misses everything. + net.drop_next(net.pending()); + REQUIRE(net.pending() == 0); + + REQUIRE_FALSE(B.get_node(1000).has_value()); + REQUIRE_FALSE(B.get_node(2000).has_value()); + + // Full-graph sync recovers B. + net.sync_full_graph(1, 2); + + REQUIRE(B.get_node(1000).has_value()); + REQUIRE(B.get_node(2000).has_value()); + REQUIRE(A.size() == B.size()); +} + +TEST_CASE("FakeNetwork: partial drop then full-graph sync", "[FAKE_NET][LWW][RECOVERY]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // 4 inserts; drop the first 2. + for (uint64_t id = 1000; id < 1004; ++id) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + net.drop_next(2); // B misses nodes 1000 and 1001 + net.deliver_all(); // B gets nodes 1002 and 1003 + + REQUIRE_FALSE(B.get_node(1000).has_value()); + REQUIRE_FALSE(B.get_node(1001).has_value()); + REQUIRE(B.get_node(1002).has_value()); + REQUIRE(B.get_node(1003).has_value()); + + net.sync_full_graph(1, 2); // catch up + REQUIRE(A.size() == B.size()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Partition / rejoin +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: partitioned agent catches up via buffered messages", + "[FAKE_NET][LWW][PARTITION]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Initial shared state: both have node 1000. + { + auto e = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e.applied); + net.post(1, e); + net.deliver_all(); + } + REQUIRE(B.get_node(1000).has_value()); + + // Partition B. + net.partition(2); + + // A inserts nodes 2000 and 3000 while B is partitioned. + for (uint64_t id = 2000; id < 2003; ++id) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + net.deliver_all(); // B's share goes to partition buffer + + // B is still missing the new nodes. + REQUIRE_FALSE(B.get_node(2000).has_value()); + REQUIRE_FALSE(B.get_node(2001).has_value()); + REQUIRE_FALSE(B.get_node(2002).has_value()); + + // Rejoin: buffer is flushed into B. + net.unpartition(2); + + REQUIRE(B.get_node(2000).has_value()); + REQUIRE(B.get_node(2001).has_value()); + REQUIRE(B.get_node(2002).has_value()); + REQUIRE(A.size() == B.size()); +} + +TEST_CASE("FakeNetwork: cold-start agent synced via full-graph import", + "[FAKE_NET][LWW][PARTITION]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // A accumulates nodes without B ever receiving deltas. + for (uint64_t id = 1000; id < 1005; ++id) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + } + + REQUIRE(A.size() == 5); + REQUIRE(B.size() == 0); + + net.sync_full_graph(1, 2); + + REQUIRE(B.size() == 5); + REQUIRE(A.size() == B.size()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Edge synchronisation +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW edge insert propagates", "[FAKE_NET][LWW][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Sync endpoint nodes. + for (uint64_t id : {uint64_t{10}, uint64_t{11}}) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + net.deliver_all(); + + // Insert edge on A and sync. + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto ee = A.insert_edge(std::move(edge)); + REQUIRE(ee.applied); + net.post(1, ee); + net.deliver_all(); + + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +TEST_CASE("FakeNetwork: LWW edge delete propagates", "[FAKE_NET][LWW][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Setup: both agents have the edge. + for (uint64_t id : {uint64_t{10}, uint64_t{11}}) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + { + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto ee = A.insert_edge(std::move(edge)); + REQUIRE(ee.applied); + net.post(1, ee); + } + net.deliver_all(); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // A deletes edge and syncs. + auto de = A.delete_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(de.applied); + net.post(1, de); + net.deliver_all(); + + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Out-of-order delivery: edge delta before endpoint nodes +// +// apply_remote_edge_delta buffers the delta when either endpoint node is absent. +// The edge materializes automatically when the missing node arrives. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW edge delta arrives before 'to' node: buffered and applied", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto e_from = A.insert_node(make_robot(10, 1, "r_from")); + auto e_to = A.insert_node(make_robot(11, 1, "r_to")); + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge)); + REQUIRE(e_from.applied); + REQUIRE(e_to.applied); + REQUIRE(e_edge.applied); + + // Deliver the 'from' node so B knows about it. + net.post(1, e_from); + net.deliver_all(); + REQUIRE(B.get_node(10).has_value()); + + // Queue: edge first, then 'to' node. + net.post(1, e_edge); + net.post(1, e_to); + + // Edge arrives: B has 'from' but not 'to' → buffered, not yet materialized. + net.deliver_next(1); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 'to' node arrives: both endpoints now present, pending edge materializes. + net.deliver_next(1); + REQUIRE(B.get_node(11).has_value()); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +TEST_CASE("FakeNetwork: LWW edge delta arrives before 'from' node: buffered and applied", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + auto e_from = A.insert_node(make_robot(10, 1, "r_from")); + auto e_to = A.insert_node(make_robot(11, 1, "r_to")); + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge)); + REQUIRE(e_from.applied); + REQUIRE(e_to.applied); + REQUIRE(e_edge.applied); + + // Deliver the 'to' node so B has the target but not the source. + net.post(1, e_to); + net.deliver_all(); + REQUIRE(B.get_node(11).has_value()); + REQUIRE_FALSE(B.get_node(10).has_value()); + + // Queue: edge first, then 'from' node. + net.post(1, e_edge); + net.post(1, e_from); + + // Edge arrives: B has 'to' but not 'from' → buffered, not yet materialized. + net.deliver_next(1); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 'from' node arrives: both endpoints now present, pending edge materializes. + net.deliver_next(1); + REQUIRE(B.get_node(10).has_value()); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Out-of-order delivery: attr batch before parent creation +// +// apply_remote_node_attr_batch and apply_remote_edge_attr_batch buffer items +// whose parent entity does not yet exist. The buffered updates are applied +// automatically when the parent materializes. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW node attr batch arrives before node creation: buffered and applied", + "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // A inserts the node (level=0), then bumps level to 99. + auto e_ins = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e_ins.applied); + const uint64_t base = node_version_ts(e_ins); + + auto updated = make_robot(1000, 1, "robot_a"); + updated.attrs()["level"] = Attribute(99, base, 1); + auto e_upd = A.update_node(std::move(updated)); + REQUIRE(e_upd.applied); + REQUIRE(e_upd.node_attr_batch.has_value()); // metadata unchanged → attr-batch only + + // B receives the attr batch FIRST; node doesn't exist → buffered. + net.post_raw(1, *e_upd.node_attr_batch); + net.deliver_all(); + REQUIRE_FALSE(B.get_node(1000).has_value()); + + // B then receives the original node insertion delta (level=0). + // On arrival the buffered attr batch is applied: level becomes 99. + net.post(1, e_ins); + net.deliver_all(); + + auto node = B.get_node(1000); + REQUIRE(node.has_value()); + REQUIRE(node->attrs().at("level").dec() == 99); // buffered attr applied on node arrival +} + +TEST_CASE("FakeNetwork: LWW edge attr batch arrives before edge creation: buffered and applied", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Sync endpoint nodes to both agents. + for (uint64_t id : {uint64_t{10}, uint64_t{11}}) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + net.deliver_all(); + + // A inserts the edge (no attrs), then adds a 'weight' attr. + auto edge1 = Edge::create(10, 11); + edge1.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge1)); + REQUIRE(e_edge.applied); + REQUIRE(e_edge.edge_delta.has_value()); + const uint64_t base = edge_version_ts(e_edge); + + auto edge2 = Edge::create(10, 11); + edge2.agent_id(1); + edge2.attrs()["weight"] = Attribute(99, base, 1); + auto e_upd = A.insert_edge(std::move(edge2)); // update: edge already exists in A + REQUIRE(e_upd.applied); + REQUIRE(e_upd.edge_attr_batch.has_value()); // existing edge → attr-batch only + + // B receives the attr batch FIRST; edge doesn't exist → buffered. + net.post_raw(1, *e_upd.edge_attr_batch); + net.deliver_all(); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // B then receives the original edge insertion delta (no weight attr). + // On arrival the buffered attr batch is applied: weight becomes 99. + net.post(1, e_edge); + net.deliver_all(); + + auto e = B.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(e.has_value()); + REQUIRE(e->attrs().contains("weight")); // buffered attr applied on edge arrival + REQUIRE(e->attrs().at("weight").dec() == 99); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Attr updates targeting deleted entities +// +// A stale or reordered attr batch that arrives after the target node/edge has +// been deleted must be silently discarded. It must not recreate the entity. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW node attr batch for deleted node is silently ignored", + "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Both agents have node 1000. + auto e_ins = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e_ins.applied); + const uint64_t base = node_version_ts(e_ins); + net.post(1, e_ins); + net.deliver_all(); + REQUIRE(B.get_node(1000).has_value()); + + // A deletes node 1000; deletion propagates to B. + auto e_del = A.delete_node(1000); + REQUIRE(e_del.applied); + net.post(1, e_del); + net.deliver_all(); + REQUIRE_FALSE(B.get_node(1000).has_value()); + + // A stale/reordered attr batch for the now-deleted node arrives at B. + B.engine->apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 3, 99, base + 100)}); + + // Node must remain absent — the attr batch must not resurrect it. + REQUIRE_FALSE(B.get_node(1000).has_value()); +} + +TEST_CASE("FakeNetwork: LWW edge attr batch for deleted edge is silently ignored", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::LWW); + auto& B = net.add_agent(2, SyncMode::LWW); + + // Both agents have endpoint nodes and the edge. + for (uint64_t id : {uint64_t{10}, uint64_t{11}}) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge)); + REQUIRE(e_edge.applied); + const uint64_t base = edge_version_ts(e_edge); + net.post(1, e_edge); + net.deliver_all(); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // A deletes the edge; deletion propagates to B. + auto e_del = A.delete_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(e_del.applied); + net.post(1, e_del); + net.deliver_all(); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // A stale/reordered attr batch for the deleted edge arrives at B. + B.engine->apply_remote_edge_attr_batch( + EdgeAttrDeltaBatchMessage{make_edge_attr_batch(10, 11, 3, 99, base + 100)}); + + // Edge must remain absent — the attr batch must not recreate it. + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Scenario: pending items evicted by tombstone before parent materializes +// +// A buffered attr that arrives before its parent node/edge must be discarded +// if the parent is subsequently tombstoned before it ever materializes. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW pending node attr discarded when node tombstoned before creation", + "[FAKE_NET][LWW][REORDER]") +{ + FakeNetwork net; + auto& agent = net.add_agent(1, SyncMode::LWW); + auto& eng = *agent.engine; + + // T=200: attr for node 1000 → buffered (node absent, no tombstone). + eng.apply_remote_node_attr_batch( + NodeAttrDeltaBatchMessage{make_attr_batch(1000, 2, 99, 200)}); + REQUIRE_FALSE(eng.get_node(1000).has_value()); + + // T=300: delete node 1000 → tombstone evicts the pending attr. + eng.apply_remote_node_delta(NodeDeltaMessage{make_node_delete_msg(1000, 2, 300)}); + REQUIRE_FALSE(eng.get_node(1000).has_value()); + + // T=100: stale node insertion → rejected by tombstone (100 < 300). + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(1000, 2, "robot_a", 100)}); + REQUIRE_FALSE(eng.get_node(1000).has_value()); +} + +TEST_CASE("FakeNetwork: LWW pending edge attr discarded when edge tombstoned before creation", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& agent = net.add_agent(1, SyncMode::LWW); + auto& eng = *agent.engine; + + // Put endpoint nodes in place. + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(10, 1, "r_from", 50)}); + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(11, 1, "r_to", 50)}); + + // T=300: edge attr → buffered (edge absent, no tombstone). + eng.apply_remote_edge_attr_batch( + EdgeAttrDeltaBatchMessage{make_edge_attr_batch(10, 11, 2, 99, 300)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // T=400: delete edge → tombstone at 400. Pending attr (T=300 < 400) evicted. + eng.apply_remote_edge_delta(EdgeDeltaMessage{make_edge_msg(10, 11, 2, 400, true)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // T=200: stale edge insertion → rejected by tombstone (200 < 400). + eng.apply_remote_edge_delta(EdgeDeltaMessage{make_edge_msg(10, 11, 2, 200)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Scenario 5: stale edge delete + newer pending edge attr + edge creation +// +// A pending edge attr with a newer timestamp must survive an older edge delete +// tombstone and be applied once the edge materializes. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW newer edge attr survives older delete tombstone", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& agent = net.add_agent(1, SyncMode::LWW); + auto& eng = *agent.engine; + + // Endpoint nodes exist. + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(10, 1, "r_from", 50)}); + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(11, 1, "r_to", 50)}); + + // T=300: edge attr arrives first — buffered (no edge, no tombstone). + eng.apply_remote_edge_attr_batch( + EdgeAttrDeltaBatchMessage{make_edge_attr_batch(10, 11, 2, 99, 300)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // T=100: stale edge delete → tombstone at 100. + // Pending attr (T=300 > 100) is newer → KEPT in buffer. + eng.apply_remote_edge_delta(EdgeDeltaMessage{make_edge_msg(10, 11, 2, 100, true)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // T=200: edge insert → tombstone check: 200 > 100 → materializes. + // Pending attr (T=300) flushed and applied. + eng.apply_remote_edge_delta(EdgeDeltaMessage{make_edge_msg(10, 11, 2, 200)}); + auto edge = eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(edge.has_value()); + REQUIRE(edge->attrs().contains("weight")); + REQUIRE(edge->attrs().at("weight").dec() == 99); +} + +// ────────────────────────────────────────────────────────────────────────────── +// Scenario 6: chained out-of-order: edge attr → edge → node A → node B +// +// All four messages arrive in reverse dependency order. Eventual consistency +// is reached purely through pending buffers — no full-graph sync needed. +// ────────────────────────────────────────────────────────────────────────────── + +TEST_CASE("FakeNetwork: LWW chained out-of-order edge attr then edge then nodes", + "[FAKE_NET][LWW][REORDER][EDGE]") +{ + FakeNetwork net; + auto& agent = net.add_agent(1, SyncMode::LWW); + auto& eng = *agent.engine; + + // Arrival order (all out-of-order relative to dependency graph): + // 1) edge attr (weight=42) → no edge yet → buffered in pending_edge_attrs_ + eng.apply_remote_edge_attr_batch( + EdgeAttrDeltaBatchMessage{make_edge_attr_batch(10, 11, 2, 42, 400)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 2) edge (from=10, to=11) → nodes 10 and 11 absent → buffered in pending_edges_ + eng.apply_remote_edge_delta(EdgeDeltaMessage{make_edge_msg(10, 11, 2, 200)}); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 3) node 10 arrives → flush_pending_edges: edge still waiting for node 11. + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(10, 2, "r_from", 100)}); + REQUIRE(eng.get_node(10).has_value()); + REQUIRE_FALSE(eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 4) node 11 arrives → flush_pending_edges: both nodes present → edge materializes + // → pending_edge_attrs_ flushed → weight=42 applied. + eng.apply_remote_node_delta(NodeDeltaMessage{make_insert_msg(11, 2, "r_to", 100)}); + REQUIRE(eng.get_node(11).has_value()); + + auto edge = eng.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(edge.has_value()); + REQUIRE(edge->attrs().contains("weight")); + REQUIRE(edge->attrs().at("weight").dec() == 42); +} + +// ══════════════════════════════════════════════════════════════════════════════ +// CRDT backend — out-of-order delivery scenarios +// +// The CRDT engine buffers deltas in unprocessed_delta_* maps keyed on the +// missing parent. Buffered items are replayed automatically once the parent +// materialises (consume_unprocessed_deltas). The check applied is a timestamp +// comparison: buffered items are applied only when their timestamp is strictly +// greater than the materialising parent's timestamp. +// +// Scenario 5 (stale delete + newer pending attr) is NOT tested here because +// the CRDT engine evicts ALL pending edge attrs on any edge delete regardless +// of per-item timestamps — its delete semantics differ from LWW. +// ══════════════════════════════════════════════════════════════════════════════ + +TEST_CASE("FakeNetwork: CRDT edge delta arrives before 'to' node: buffered and applied", + "[FAKE_NET][CRDT][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + auto e_from = A.insert_node(make_robot(10, 1, "r_from")); + auto e_to = A.insert_node(make_robot(11, 1, "r_to")); + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge)); + REQUIRE(e_from.applied); + REQUIRE(e_to.applied); + REQUIRE(e_edge.applied); + + // Deliver the 'from' node so B knows about it. + net.post(1, e_from); + net.deliver_all(); + REQUIRE(B.get_node(10).has_value()); + + // Queue: edge first, then 'to' node. + net.post(1, e_edge); + net.post(1, e_to); + + // Edge arrives: 'to' missing → buffered in unprocessed_delta_edge_to_. + net.deliver_next(1); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 'to' node arrives → consume_unprocessed_deltas materialises the edge. + net.deliver_next(1); + REQUIRE(B.get_node(11).has_value()); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +TEST_CASE("FakeNetwork: CRDT edge delta arrives before 'from' node: buffered and applied", + "[FAKE_NET][CRDT][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + auto e_from = A.insert_node(make_robot(10, 1, "r_from")); + auto e_to = A.insert_node(make_robot(11, 1, "r_to")); + auto edge = Edge::create(10, 11); + edge.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge)); + REQUIRE(e_from.applied); + REQUIRE(e_to.applied); + REQUIRE(e_edge.applied); + + // Deliver the 'to' node so B has the target but not the source. + net.post(1, e_to); + net.deliver_all(); + REQUIRE(B.get_node(11).has_value()); + REQUIRE_FALSE(B.get_node(10).has_value()); + + // Queue: edge first, then 'from' node. + net.post(1, e_edge); + net.post(1, e_from); + + // Edge arrives: 'from' missing → buffered in unprocessed_delta_edge_from_. + net.deliver_next(1); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 'from' node arrives → consume_unprocessed_deltas materialises the edge. + net.deliver_next(1); + REQUIRE(B.get_node(10).has_value()); + REQUIRE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); +} + +TEST_CASE("FakeNetwork: CRDT node attr batch arrives before node creation: buffered and applied", + "[FAKE_NET][CRDT][REORDER]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + // A inserts node (level=0), then bumps level to 99. + auto e_ins = A.insert_node(make_robot(1000, 1, "robot_a")); + REQUIRE(e_ins.applied); + + auto updated = make_robot(1000, 1, "robot_a"); + updated.attrs()["level"] = Attribute(99, 100, 1); + auto e_upd = A.update_node(std::move(updated)); + REQUIRE(e_upd.applied); + REQUIRE(e_upd.node_attr_batch.has_value()); // update_node → attr-batch only, no node_delta + + // B receives the attr batch FIRST; node doesn't exist → buffered in + // unprocessed_delta_node_att_. post() of a NodeMutationEffect with no + // node_delta queues only the attr batch. + net.post(1, e_upd); + net.deliver_all(); + REQUIRE_FALSE(B.get_node(1000).has_value()); + + // B then receives the original node insertion delta. + // On arrival, consume_unprocessed_deltas applies the buffered level=99 attr + // (provided the attr's timestamp is strictly newer than the node's timestamp). + net.post(1, e_ins); + net.deliver_all(); + + auto node = B.get_node(1000); + REQUIRE(node.has_value()); + REQUIRE(node->attrs().at("level").dec() == 99); +} + +TEST_CASE("FakeNetwork: CRDT edge attr batch arrives before edge creation: buffered and applied", + "[FAKE_NET][CRDT][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + // Sync endpoint nodes to both agents. + for (uint64_t id : {uint64_t{10}, uint64_t{11}}) { + auto e = A.insert_node(make_robot(id, 1, "r" + std::to_string(id))); + REQUIRE(e.applied); + net.post(1, e); + } + net.deliver_all(); + + // A inserts the edge (no attrs), then adds a 'weight' attr. + auto edge1 = Edge::create(10, 11); + edge1.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge1)); + REQUIRE(e_edge.applied); + REQUIRE(e_edge.edge_delta.has_value()); + + auto edge2 = Edge::create(10, 11); + edge2.agent_id(1); + edge2.attrs()["weight"] = Attribute(99, 100, 1); + auto e_upd = A.insert_edge(std::move(edge2)); // update: edge exists in A + REQUIRE(e_upd.applied); + REQUIRE(e_upd.edge_attr_batch.has_value()); // existing edge → attr-batch only, no edge_delta + + // B receives the attr batch FIRST (post() of EdgeMutationEffect with no edge_delta + // queues only the attr batch). Edge absent → buffered in unprocessed_delta_edge_att_. + net.post(1, e_upd); + net.deliver_all(); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // B then receives the original edge insertion delta. + // On arrival, consume_unprocessed_deltas applies the buffered weight=99 attr. + net.post_raw(1, *e_edge.edge_delta); + net.deliver_all(); + + auto e = B.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(e.has_value()); + REQUIRE(e->attrs().contains("weight")); + REQUIRE(e->attrs().at("weight").dec() == 99); +} + +TEST_CASE("FakeNetwork: CRDT chained out-of-order edge attr then edge then nodes", + "[FAKE_NET][CRDT][REORDER][EDGE]") +{ + FakeNetwork net; + auto& A = net.add_agent(1, SyncMode::CRDT); + auto& B = net.add_agent(2, SyncMode::CRDT); + + // Build all state on A first. + auto e_from = A.insert_node(make_robot(10, 1, "r_from")); + auto e_to = A.insert_node(make_robot(11, 1, "r_to")); + REQUIRE(e_from.applied); + REQUIRE(e_to.applied); + + auto edge1 = Edge::create(10, 11); + edge1.agent_id(1); + auto e_edge = A.insert_edge(std::move(edge1)); + REQUIRE(e_edge.applied); + REQUIRE(e_edge.edge_delta.has_value()); + + auto edge2 = Edge::create(10, 11); + edge2.agent_id(1); + edge2.attrs()["weight"] = Attribute(42, 100, 1); + auto e_upd = A.insert_edge(std::move(edge2)); + REQUIRE(e_upd.applied); + REQUIRE(e_upd.edge_attr_batch.has_value()); + + // Arrival order at B (all out-of-order): + // 1) edge attr batch → no edge yet → buffered in unprocessed_delta_edge_att_ + net.post(1, e_upd); + net.deliver_all(); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 2) edge delta → 'from' node (10) absent → buffered in unprocessed_delta_edge_from_[10] + net.post_raw(1, *e_edge.edge_delta); + net.deliver_all(); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 3) node 10 arrives → consume_unprocessed_deltas: + // - edge is stored in nodes_[10].fano[{11, type}] + // - edge attr (weight=42) is flushed from unprocessed_delta_edge_att_ and applied + // - get_edge still returns null because nodes_.contains(11) is false + net.post(1, e_from); + net.deliver_all(); + REQUIRE(B.get_node(10).has_value()); + REQUIRE_FALSE(B.get_edge(10, 11, std::string(RT_edge_type::attr_name)).has_value()); + + // 4) node 11 arrives → get_crdt_edge_ptr now finds both endpoints. + // The edge (with weight=42 already merged) is visible. + net.post(1, e_to); + net.deliver_all(); + REQUIRE(B.get_node(11).has_value()); + + auto edge = B.get_edge(10, 11, std::string(RT_edge_type::attr_name)); + REQUIRE(edge.has_value()); + REQUIRE(edge->attrs().contains("weight")); + REQUIRE(edge->attrs().at("weight").dec() == 42); +} diff --git a/tests/synchronization/lww_sync_engine.cpp b/tests/synchronization/lww_sync_engine.cpp index f56405d1..d87f7105 100644 --- a/tests/synchronization/lww_sync_engine.cpp +++ b/tests/synchronization/lww_sync_engine.cpp @@ -3,6 +3,7 @@ #include #include "../utils.h" +#include "../transport/fake_network.h" #include "dsr/api/dsr_api.h" #include "dsr/api/dsr_lww_sync_engine.h" #include "dsr/core/types/type_checking/dsr_attr_name.h" @@ -10,56 +11,11 @@ #include "dsr/core/types/type_checking/dsr_node_type.h" using namespace DSR; +using namespace DSR::Test; using namespace std::chrono_literals; namespace { -struct FakeSyncHost final : SyncEngineHost -{ - uint32_t agent{17}; - SyncMode mode{SyncMode::LWW}; - bool copy{false}; - std::unordered_map nodes; - std::unordered_map, Edge, hash_tuple> edges; - - uint32_t local_agent_id() const override { return agent; } - SyncMode local_sync_mode() const override { return mode; } - bool is_copy_graph() const override { return copy; } - - void update_maps_node_insert(uint64_t id, std::string_view name, std::string_view type, const EdgeKeyList& outgoing_edges) override - { - Node node(agent, std::string{type}); - node.id(id); - node.name(std::string{name}); - for (const auto& [to, edge_type] : outgoing_edges) { - node.fano().emplace(std::pair{to, edge_type}, Edge(to, id, edge_type, {}, agent)); - } - nodes[id] = std::move(node); - } - - void update_maps_node_delete(uint64_t id, std::optional, const EdgeKeyList&) override - { - nodes.erase(id); - for (auto it = edges.begin(); it != edges.end(); ) { - if (std::get<0>(it->first) == id || std::get<1>(it->first) == id) { - it = edges.erase(it); - } else { - ++it; - } - } - } - - void update_maps_edge_insert(uint64_t from, uint64_t to, const std::string& type) override - { - edges[std::tuple{from, to, type}] = Edge(to, from, type, {}, agent); - } - - void update_maps_edge_delete(uint64_t from, uint64_t to, const std::string& type) override - { - edges.erase(std::tuple{from, to, type}); - } -}; - Node make_robot(uint64_t id, std::string name, int level) { auto node = Node::create(name); diff --git a/tests/transport/fake_network.h b/tests/transport/fake_network.h new file mode 100644 index 00000000..d7c4ddfe --- /dev/null +++ b/tests/transport/fake_network.h @@ -0,0 +1,289 @@ +#pragma once + +#include "dsr/api/dsr_crdt_sync_engine.h" +#include "dsr/api/dsr_lww_sync_engine.h" +#include "dsr/api/dsr_sync_engine.h" +#include "dsr/core/types/internal_types.h" +#include "dsr/core/types/user_types.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace DSR::Test { + +// Minimal SyncEngineHost for use outside DSRGraph. +// update_maps_* are no-ops; convergence is verified by querying the engine directly. +struct FakeSyncHost final : DSR::SyncEngineHost +{ + uint32_t agent{}; + DSR::SyncMode mode{DSR::SyncMode::LWW}; + + FakeSyncHost() = default; + FakeSyncHost(uint32_t a, DSR::SyncMode m) : agent(a), mode(m) {} + + uint32_t local_agent_id() const override { return agent; } + DSR::SyncMode local_sync_mode() const override { return mode; } + bool is_copy_graph() const override { return false; } + + void update_maps_node_insert(uint64_t, std::string_view, std::string_view, const EdgeKeyList&) override {} + void update_maps_node_delete(uint64_t, std::optional, const EdgeKeyList&) override {} + void update_maps_edge_insert(uint64_t, uint64_t, const std::string&) override {} + void update_maps_edge_delete(uint64_t, uint64_t, const std::string&) override {} +}; + +// Envelope for an in-flight delta between agents. +struct PendingMessage +{ + uint32_t from_agent_id; + using Payload = std::variant< + DSR::NodeDeltaMessage, + DSR::EdgeDeltaMessage, + DSR::NodeAttrDeltaBatchMessage, + DSR::EdgeAttrDeltaBatchMessage, + DSR::FullGraphMessage>; + Payload payload; +}; + +// One in-process agent: a host + a sync engine. +// FakeAgent is non-copyable and non-movable so that the engine's reference +// to host remains stable as long as the FakeAgent lives on the heap. +struct FakeAgent +{ + uint32_t id; + DSR::SyncMode mode; + FakeSyncHost host; + std::unique_ptr engine; + + explicit FakeAgent(uint32_t id_, DSR::SyncMode mode_) + : id(id_), mode(mode_), host{id_, mode_} + { + if (mode == DSR::SyncMode::LWW) + engine = std::make_unique(host); + else + engine = std::make_unique(host); + } + + FakeAgent(const FakeAgent&) = delete; + FakeAgent& operator=(const FakeAgent&) = delete; + FakeAgent(FakeAgent&&) = delete; + FakeAgent& operator=(FakeAgent&&) = delete; + + // ── Local mutations ─────────────────────────────────────────────────────── + + DSR::NodeMutationEffect insert_node(DSR::Node n) + { + return engine->insert_node_local(std::move(n)); + } + + DSR::NodeMutationEffect update_node(DSR::Node n) + { + return engine->update_node_local(std::move(n)); + } + + DSR::NodeMutationEffect delete_node(uint64_t node_id) + { + return engine->delete_node_local(node_id); + } + + DSR::EdgeMutationEffect insert_edge(DSR::Edge e) + { + return engine->insert_or_assign_edge_local(std::move(e)); + } + + DSR::EdgeMutationEffect delete_edge(uint64_t from, uint64_t to, const std::string& type) + { + return engine->delete_edge_local(from, to, type); + } + + // ── Query ───────────────────────────────────────────────────────────────── + + std::optional get_node(uint64_t node_id) const + { + return engine->get_node(node_id); + } + + std::optional get_edge(uint64_t from, uint64_t to, const std::string& type) const + { + return engine->get_edge(from, to, type); + } + + size_t size() const { return engine->size(); } + std::map snapshot() const { return engine->snapshot(); } +}; + +// ────────────────────────────────────────────────────────────────────────────── +// FakeNetwork +// +// Owns a collection of FakeAgents and an ordered queue of PendingMessages. +// Tests control delivery explicitly: deliver_all(), deliver_next(), drop_next(), +// shuffle(). Partition/unpartition simulates network splits. +// ────────────────────────────────────────────────────────────────────────────── +class FakeNetwork +{ +public: + // Add a new agent to the network. Returns a stable reference. + FakeAgent& add_agent(uint32_t id, DSR::SyncMode mode = DSR::SyncMode::LWW) + { + agents_.push_back(std::make_unique(id, mode)); + return *agents_.back(); + } + + FakeAgent* get_agent(uint32_t id) + { + for (auto& a : agents_) + if (a->id == id) return a.get(); + return nullptr; + } + + // ── Queue outgoing deltas from mutation effects ─────────────────────────── + + void post(uint32_t from_id, const DSR::NodeMutationEffect& effect) + { + if (effect.node_delta.has_value()) + queue_.push_back({from_id, *effect.node_delta}); + if (effect.node_attr_batch.has_value()) + queue_.push_back({from_id, *effect.node_attr_batch}); + for (const auto& ed : effect.edge_deltas) + queue_.push_back({from_id, ed}); + } + + void post(uint32_t from_id, const DSR::EdgeMutationEffect& effect) + { + if (effect.edge_delta.has_value()) + queue_.push_back({from_id, *effect.edge_delta}); + if (effect.edge_attr_batch.has_value()) + queue_.push_back({from_id, *effect.edge_attr_batch}); + } + + // Queue a manually crafted delta (for conflict tests with explicit timestamps). + void post_raw(uint32_t from_id, DSR::NodeDeltaMessage msg) + { + queue_.push_back({from_id, std::move(msg)}); + } + void post_raw(uint32_t from_id, DSR::EdgeDeltaMessage msg) + { + queue_.push_back({from_id, std::move(msg)}); + } + void post_raw(uint32_t from_id, DSR::NodeAttrDeltaBatchMessage msg) + { + queue_.push_back({from_id, std::move(msg)}); + } + void post_raw(uint32_t from_id, DSR::EdgeAttrDeltaBatchMessage msg) + { + queue_.push_back({from_id, std::move(msg)}); + } + + // ── Delivery controls ───────────────────────────────────────────────────── + + size_t pending() const { return queue_.size(); } + + // Deliver all queued messages in order. + void deliver_all() + { + while (!queue_.empty()) + deliver_front(); + } + + // Deliver the next n messages in queue order. + void deliver_next(size_t n = 1) + { + for (size_t i = 0; i < n && !queue_.empty(); ++i) + deliver_front(); + } + + // Discard the next n messages without delivering. + void drop_next(size_t n = 1) + { + for (size_t i = 0; i < n && !queue_.empty(); ++i) + queue_.pop_front(); + } + + // Randomise the queue order. Pass an rng for reproducibility. + void shuffle(std::mt19937& rng) + { + std::shuffle(queue_.begin(), queue_.end(), rng); + } + + void shuffle() + { + std::mt19937 rng{std::random_device{}()}; + shuffle(rng); + } + + // Stop delivering messages TO agent_id; buffer them instead. + void partition(uint32_t agent_id) + { + partitioned_.insert(agent_id); + partition_buffer_.emplace(agent_id, std::deque{}); + } + + // Resume delivery to agent_id and immediately flush its buffer. + void unpartition(uint32_t agent_id) + { + partitioned_.erase(agent_id); + if (auto it = partition_buffer_.find(agent_id); it != partition_buffer_.end()) { + FakeAgent* target = get_agent(agent_id); + if (target) { + for (const auto& msg : it->second) + apply_to(*target, msg); + } + partition_buffer_.erase(it); + } + } + + // Directly import agent `from_id`'s full graph into agent `to_id`. + // Simulates the graph-request / graph-answer handshake. + void sync_full_graph(uint32_t from_id, uint32_t to_id) + { + FakeAgent* src = get_agent(from_id); + FakeAgent* dst = get_agent(to_id); + if (!src || !dst) return; + dst->engine->import_full_graph(src->engine->export_full_graph()); + } + +private: + std::vector> agents_; + std::deque queue_; + std::unordered_set partitioned_; + std::unordered_map> partition_buffer_; + + void deliver_front() + { + PendingMessage msg = std::move(queue_.front()); + queue_.pop_front(); + for (auto& agent : agents_) { + if (agent->id == msg.from_agent_id) continue; + if (partitioned_.count(agent->id)) { + partition_buffer_[agent->id].push_back(msg); + } else { + apply_to(*agent, msg); + } + } + } + + static void apply_to(FakeAgent& agent, const PendingMessage& msg) + { + std::visit([&](const auto& payload) { + using T = std::remove_cvref_t; + if constexpr (std::is_same_v) + agent.engine->apply_remote_node_delta(T{payload}); + else if constexpr (std::is_same_v) + agent.engine->apply_remote_edge_delta(T{payload}); + else if constexpr (std::is_same_v) + agent.engine->apply_remote_node_attr_batch(T{payload}); + else if constexpr (std::is_same_v) + agent.engine->apply_remote_edge_attr_batch(T{payload}); + else if constexpr (std::is_same_v) + agent.engine->import_full_graph(T{payload}); + }, msg.payload); + } +}; + +} // namespace DSR::Test From 554d4cf4ae2c7455c208f5efb3a06085e60aa8eb Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 30 Apr 2026 20:38:11 +0200 Subject: [PATCH 32/38] optimize DSR map lookups and LWW edge attr batches --- api/dsr_api.cpp | 47 +++++++++++++++------------- api/dsr_lww_sync_engine.cpp | 24 ++++++++------ api/include/dsr/api/dsr_api.h | 59 ++++++++++++++++++++++++----------- 3 files changed, 80 insertions(+), 50 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index b58c28dd..ea317c22 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -590,12 +590,14 @@ requires (std::is_same_v, DSR::Node>) throw std::runtime_error( (std::string("Cannot update node in G, " + std::to_string(node.id()) + " is deleted") + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (( id_map.contains(node.id()) and id_map.at(node.id()) != node.name()) or - ( name_map.contains(node.name()) and name_map.at(node.name()) != node.id())) + const auto id_it = id_map.find(node.id()); + const auto name_it = name_map.find(node.name()); + if ((id_it != id_map.end() && id_it->second != node.name()) || + (name_it != name_map.end() && name_it->second != node.id())) throw std::runtime_error( (std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)).data()); - else if (id_map.contains(node.id())) { + else if (id_it != id_map.end()) { lck_cache.unlock(); effect = engine_->update_node_local(Node(node)); if (!effect.applied) { @@ -772,10 +774,10 @@ std::vector DSRGraph::get_nodes_by_type(const std::string &type) std::shared_lock lck(_mutex_cache_maps); std::vector nodes_; - if (nodeType.contains(type)) + if (const auto it = nodeType.find(type); it != nodeType.end()) { - nodes_.reserve(nodeType.at(type).size()); - for (auto &id: nodeType.at(type)) + nodes_.reserve(it->second.size()); + for (auto &id: it->second) { if (auto node = engine_->get_node(id); node.has_value()) { nodes_.emplace_back(std::move(*node)); @@ -807,14 +809,14 @@ std::vector DSRGraph::get_nodes_by_types(const std::vectorsecond.size(); nodes_.reserve(total); } for (auto &type : types) { - if (nodeType.contains(type)) + if (const auto it = nodeType.find(type); it != nodeType.end()) { - for (auto &id: nodeType.at(type)) + for (auto &id: it->second) { if (auto node = engine_->get_node(id); node.has_value()) { nodes_.emplace_back(std::move(*node)); @@ -882,8 +884,8 @@ std::vector DSRGraph::get_edges_by_type(const std::string &type) std::shared_lock lock(_mutex); std::shared_lock lock_cache(_mutex_cache_maps); std::vector edges_; - if (edgeType.contains(type)) { - edges_.reserve(edgeType.at(type).size()); + if (const auto it = edgeType.find(type); it != edgeType.end()) { + edges_.reserve(it->second.size()); } engine_->for_each_edge_of_type(type, [&](uint64_t, uint64_t, const Edge& edge) { edges_.emplace_back(edge); @@ -896,8 +898,8 @@ std::vector DSRGraph::get_edges_to_id(uint64_t id) std::shared_lock lock(_mutex); std::shared_lock lock_cache(_mutex_cache_maps); std::vector edges_; - if (to_edges.contains(id)) { - edges_.reserve(to_edges.at(id).size()); + if (const auto it = to_edges.find(id); it != to_edges.end()) { + edges_.reserve(it->second.size()); } engine_->for_each_edge_to(id, [&](uint64_t, const std::string&, const Edge& edge) { edges_.emplace_back(edge); @@ -985,19 +987,20 @@ void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::st { std::unique_lock lck(_mutex_cache_maps); - if (const auto tuple = std::pair{from, to}; edges.contains(tuple)) { - edges.at(tuple).erase(key); - if (edges.at(tuple).empty()) edges.erase(tuple); + const auto tuple = std::pair{from, to}; + if (auto edge_it = edges.find(tuple); edge_it != edges.end()) { + edge_it->second.erase(key); + if (edge_it->second.empty()) edges.erase(edge_it); } - if (to_edges.contains(to)) { - to_edges.at(to).erase({from, key}); - if (to_edges.at(to).empty()) to_edges.erase(to); + if (auto to_edge_it = to_edges.find(to); to_edge_it != to_edges.end()) { + to_edge_it->second.erase({from, key}); + if (to_edge_it->second.empty()) to_edges.erase(to_edge_it); } - if (edgeType.contains(key)) { - edgeType.at(key).erase({from, to}); - if (edgeType.at(key).empty()) edgeType.erase(key); + if (auto edge_type_it = edgeType.find(key); edge_type_it != edgeType.end()) { + edge_type_it->second.erase({from, to}); + if (edge_type_it->second.empty()) edgeType.erase(edge_type_it); } } diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 759a7fa7..9f72eee9 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -627,6 +627,12 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat if (payload == nullptr) { return; } + if (payload->vec.empty()) { + return; + } + + auto key = edge_key(payload->vec.front().from, payload->vec.front().to, payload->vec.front().type); + auto key_view = edge_key_view(key.from, key.to, key.type); struct EdgeAttrBatchChange { @@ -636,26 +642,26 @@ void LWWSyncEngine::apply_remote_edge_attr_batch(EdgeAttrDeltaBatchMessage&& bat std::unordered_map changes; { CORTEX_PROFILE_DETAIL_N("LWWSyncEngine::apply_remote_edge_attr_batch merge"); + auto edge_it = edges_.find(key_view); + auto ts_it = edge_it == edges_.end() ? edge_tombstones_.find(key_view) : edge_tombstones_.end(); for (auto& item : payload->vec) { auto version = version_of(item.timestamp, item.agent_id); - auto it = edges_.find(edge_key_view(item.from, item.to, item.type)); - if (it == edges_.end()) { - auto ts_it = edge_tombstones_.find(edge_key_view(item.from, item.to, item.type)); + if (edge_it == edges_.end()) { if (ts_it == edge_tombstones_.end() || is_newer(version, ts_it->second.version)) { - pending_edge_attrs_[edge_key(item.from, item.to, item.type)].push_back(item); + pending_edge_attrs_[key].push_back(item); } continue; } - auto attr_it = it->second.attrs.find(item.attr_name); - if (attr_it != it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { + auto attr_it = edge_it->second.attrs.find(item.attr_name); + if (attr_it != edge_it->second.attrs.end() && !is_newer(version, attr_it->second.version)) { continue; } if (item.deleted) { - it->second.attrs.erase(item.attr_name); + edge_it->second.attrs.erase(item.attr_name); } else { - it->second.attrs[item.attr_name] = AttrState{item.value, version}; + edge_it->second.attrs[item.attr_name] = AttrState{item.value, version}; } - auto& change = changes[edge_key(item.from, item.to, item.type)]; + auto& change = changes[key]; change.agent_id = item.agent_id; change.attrs.push_back(item.attr_name); } diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 72f5229b..a00a90d9 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -16,6 +16,7 @@ #include #include #include +#include #include "dsr/core/crdt/delta_crdt.h" #include "dsr/core/rtps/dsrparticipant.h" #include "dsr/core/rtps/dsrpublisher.h" @@ -663,43 +664,63 @@ namespace DSR // Cache maps /////////////////////////////////////////////////////////////////////////// + struct TransparentStringHash + { + using is_transparent = void; + + size_t operator()(std::string_view value) const noexcept + { + return std::hash{}(value); + } + }; + + struct TransparentStringEqual + { + using is_transparent = void; + + bool operator()(std::string_view lhs, std::string_view rhs) const noexcept + { + return lhs == rhs; + } + }; + std::unordered_set deleted; // deleted nodes, used to avoid insertion after remove. - std::unordered_map name_map; // mapping between name and id of nodes. + std::unordered_map name_map; // mapping between name and id of nodes. std::unordered_map id_map; // mapping between id and name of nodes. std::unordered_map, std::unordered_set, hash_tuple> edges; // collection with all graph edges. ((from, to), key) std::unordered_map,hash_tuple>> to_edges; // collection with all graph edges. (to, (from, key)) - std::unordered_map, hash_tuple>> edgeType; // collection with all edge types. - std::unordered_map> nodeType; // collection with all node types. + std::unordered_map, hash_tuple>, TransparentStringHash, TransparentStringEqual> edgeType; // collection with all edge types. + std::unordered_map, TransparentStringHash, TransparentStringEqual> nodeType; // collection with all node types. template void update_maps_node_delete_impl(uint64_t id, std::optional type, const T& outgoing_edges) { std::unique_lock lck(_mutex_cache_maps); - if (id_map.contains(id)) - { - name_map.erase(id_map.at(id)); - id_map.erase(id); + if (auto id_it = id_map.find(id); id_it != id_map.end()) { + name_map.erase(id_it->second); + id_map.erase(id_it); } deleted.insert(id); to_edges.erase(id); if (type.has_value()) { - if (nodeType.contains(std::string{*type})) { - nodeType.at(std::string{*type}).erase(id); - if (nodeType.at(std::string{*type}).empty()) nodeType.erase(std::string{*type}); + if (auto node_type_it = nodeType.find(*type); node_type_it != nodeType.end()) { + node_type_it->second.erase(id); + if (node_type_it->second.empty()) nodeType.erase(node_type_it); } for (const auto& [to, edge_type] : outgoing_edges) { - if (const auto tuple = std::pair{id, to}; edges.contains(tuple)) { - edges.at(tuple).erase(edge_type); - if (edges.at(tuple).empty()) edges.erase(tuple); + const auto tuple = std::pair{id, to}; + if (auto edge_it = edges.find(tuple); edge_it != edges.end()) { + edge_it->second.erase(edge_type); + if (edge_it->second.empty()) edges.erase(edge_it); } - if (edgeType.contains(edge_type)) { - edgeType.at(edge_type).erase({id, to}); - if (edgeType.at(edge_type).empty()) edgeType.erase(edge_type); + if (auto edge_type_it = edgeType.find(edge_type); edge_type_it != edgeType.end()) { + edge_type_it->second.erase({id, to}); + if (edge_type_it->second.empty()) edgeType.erase(edge_type_it); } - if (to_edges.contains(to)) { - to_edges.at(to).erase({id, edge_type}); - if (to_edges.at(to).empty()) to_edges.erase(to); + if (auto to_edge_it = to_edges.find(to); to_edge_it != to_edges.end()) { + to_edge_it->second.erase({id, edge_type}); + if (to_edge_it->second.empty()) to_edges.erase(to_edge_it); } } } From d00a75997fd52dfc758a3fed37d8349d13324eca Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Thu, 30 Apr 2026 22:53:48 +0200 Subject: [PATCH 33/38] fix benchmark backend reports and LWW edge upserts --- api/dsr_lww_sync_engine.cpp | 4 +- benchmarks/report.py | 221 +++++++++++++----- .../scalability/thread_scaling_bench.cpp | 184 +++++++++++++++ .../throughput/single_agent_ops_bench.cpp | 92 ++++++++ 4 files changed, 439 insertions(+), 62 deletions(-) diff --git a/api/dsr_lww_sync_engine.cpp b/api/dsr_lww_sync_engine.cpp index 9f72eee9..a1d11054 100644 --- a/api/dsr_lww_sync_engine.cpp +++ b/api/dsr_lww_sync_engine.cpp @@ -418,7 +418,9 @@ EdgeMutationEffect LWWSyncEngine::insert_or_assign_edge_local(Edge&& edge) if (ts_it != edge_tombstones_.end()) { edge_tombstones_.erase(ts_it); } - host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); + if (inserted) { + host_.update_maps_edge_insert(edge.from(), edge.to(), edge.type()); + } effect.applied = true; return effect; } diff --git a/benchmarks/report.py b/benchmarks/report.py index af719683..566721b4 100644 --- a/benchmarks/report.py +++ b/benchmarks/report.py @@ -132,11 +132,29 @@ def _to_ns(value: float, unit: str) -> float: return value * _UNIT_TO_NS.get(unit.strip(), 1) +def infer_sync_mode(bench: dict) -> str: + """Infer benchmark backend from metadata first, then filename/name suffixes.""" + metadata = bench.get("metadata", {}) or {} + sync_mode = str(metadata.get("sync_mode", "")).strip().lower() + if sync_mode in {"crdt", "lww"}: + return sync_mode + + candidates = [ + bench.get("benchmark_name", ""), + os.path.splitext(bench.get("_source_file", ""))[0], + ] + for name in candidates: + lower = str(name).lower() + for suffix in SYNC_MODE_SUFFIXES: + if lower.endswith(suffix): + return suffix[1:] + return "" + + def comparison_benchmark_name(bench: dict) -> str: """Return a stable benchmark identity for cross-sync-mode comparisons.""" name = bench.get("benchmark_name", bench.get("_source_file", "")) - metadata = bench.get("metadata", {}) or {} - sync_mode = str(metadata.get("sync_mode", "")).strip().lower() + sync_mode = infer_sync_mode(bench) suffixes = [f"_{sync_mode}"] if sync_mode else [] suffixes.extend(s for s in SYNC_MODE_SUFFIXES if s not in suffixes) for suffix in suffixes: @@ -186,6 +204,7 @@ def flatten_metrics(bench_files: list) -> tuple[list, list, list]: for bench in bench_files: bench_name = bench.get("benchmark_name", bench["_source_file"]) bench_key = comparison_benchmark_name(bench) + sync_mode = infer_sync_mode(bench) lang = bench.get("_lang", "python") for m in bench.get("metrics", []): add = m.get("additional", {}) @@ -205,6 +224,7 @@ def flatten_metrics(bench_files: list) -> tuple[list, list, list]: entry = { "benchmark": bench_name, "benchmark_key": bench_key, + "sync_mode": sync_mode, "metric": metric_name, "lang": lang, "profile": profile, @@ -275,6 +295,8 @@ def flatten_scalability(bench_files: list) -> list: for bench in bench_files: lang = bench.get("_lang", "python") bench_name = bench.get("benchmark_name", bench["_source_file"]) + bench_key = comparison_benchmark_name(bench) + sync_mode = infer_sync_mode(bench) for m in bench.get("metrics", []): tags = m.get("tags", {}) add = m.get("additional", {}) @@ -288,6 +310,8 @@ def flatten_scalability(bench_files: list) -> list: cat = m.get("category", "") rows.append({ "benchmark": bench_name, + "benchmark_key": bench_key, + "sync_mode": sync_mode, "operation": m["name"], "lang": lang, "profile": infer_profile(bench, m), @@ -320,11 +344,11 @@ def compute_efficiency(rows: list) -> list: for r in rows: if r["category"] != "throughput": continue - key = (r["benchmark"], r["operation"], r["scale_dim"]) + key = (r.get("benchmark_key") or r["benchmark"], r["operation"], r.get("sync_mode", ""), r["scale_dim"]) groups[key].append(r) result = [] - for (bench, op, dim), pts in groups.items(): + for (bench, op, sync_mode, dim), pts in groups.items(): pts_sorted = sorted(pts, key=lambda p: p["scale_val"]) if dim in ("threads", "agents"): @@ -339,6 +363,7 @@ def compute_efficiency(rows: list) -> list: efficiency = (p["ops_per_sec"] / (N * thr_1)) * 100.0 result.append({ "benchmark": bench, "operation": op, "scale_dim": dim, + "sync_mode": sync_mode, "scale_val": N, "efficiency": round(efficiency, 2), "ops_per_sec": p["ops_per_sec"], }) @@ -351,6 +376,7 @@ def compute_efficiency(rows: list) -> list: relative = (p["ops_per_sec"] / thr_min) * 100.0 result.append({ "benchmark": bench, "operation": op, "scale_dim": dim, + "sync_mode": sync_mode, "scale_val": p["scale_val"], "efficiency": round(relative, 2), "ops_per_sec": p["ops_per_sec"], }) @@ -401,6 +427,7 @@ def generate_html( summary.append({ "benchmark": b.get("benchmark_name", b["_source_file"]), "profile": infer_profile(b), + "sync_mode": infer_sync_mode(b), "timestamp": b.get("timestamp", ""), "duration": f"{b.get('total_duration_sec', 0):.1f}s", "metrics": len(b.get("metrics", [])), @@ -877,17 +904,17 @@ def generate_html( // Summary table document.getElementById('summary-table').innerHTML = SUMMARY.map(r => ` - ${{r.benchmark}} ${{profileBadge(r.profile)}}${{r.timestamp}} + ${{r.benchmark}} ${{syncBadge(r.sync_mode)}} ${{profileBadge(r.profile)}}${{r.timestamp}} ${{r.duration}}${{r.metrics}} ${{r.source}} `).join(''); // Overview latency chart if (LAT.length) {{ - const labels = LAT.map(m => m.metric); + const labels = LAT.map(metricLabel); const datasets = [{{ label: 'Mean (µs)', data: LAT.map(m => m.mean_ns/1000), backgroundColor: RUN_COLOR+'cc', borderColor: RUN_COLOR, borderWidth: 1 }}]; if (COMPARING && B_LAT.length) {{ - const bMap = Object.fromEntries(B_LAT.map(m => [m.benchmark+'/'+m.metric, m])); + const bMap = buildMetricMap(B_LAT); datasets.push({{ label: 'Baseline Mean (µs)', data: LAT.map(m => (bMap[m.benchmark+'/'+m.metric]?.mean_ns||0)/1000), backgroundColor: BASE_COLOR+'88', borderColor: BASE_COLOR, borderWidth: 1 }}); }} new Chart(document.getElementById('ov-latency'), {{ @@ -899,10 +926,10 @@ def generate_html( // Overview throughput chart if (THR.length) {{ - const labels = THR.map(m => m.metric); + const labels = THR.map(metricLabel); const datasets = [{{ label: 'Ops/sec', data: THR.map(m => m.ops_per_sec), backgroundColor: PALETTE[1]+'cc', borderColor: PALETTE[1], borderWidth: 1 }}]; if (COMPARING && B_THR.length) {{ - const bMap = Object.fromEntries(B_THR.map(m => [m.benchmark+'/'+m.metric, m])); + const bMap = buildMetricMap(B_THR); datasets.push({{ label: 'Baseline', data: THR.map(m => bMap[m.benchmark+'/'+m.metric]?.ops_per_sec||0), backgroundColor: BASE_COLOR+'88', borderColor: BASE_COLOR, borderWidth: 1 }}); }} new Chart(document.getElementById('ov-throughput'), {{ @@ -935,6 +962,70 @@ def generate_html( function langBadge(lang) {{ return `${{lang}}`; }} +function syncBadge(mode) {{ + if (!mode) return ''; + return `${{mode.toUpperCase()}}`; +}} +function neutralMetricKey(m) {{ + return (m.benchmark_key || m.benchmark) + '/' + m.metric; +}} +function backendMetricKey(m) {{ + return neutralMetricKey(m) + '/' + (m.sync_mode || ''); +}} +function metricLabel(m) {{ + return m.metric + (m.sync_mode ? ` [${{m.sync_mode.toUpperCase()}}]` : ''); +}} +function buildMetricMap(rows) {{ + const counts = {{}}; + rows.forEach(m => {{ + const k = neutralMetricKey(m); + counts[k] = (counts[k] || 0) + 1; + }}); + const exact = {{}}, neutral = {{}}; + rows.forEach(m => {{ + exact[backendMetricKey(m)] = m; + const k = neutralMetricKey(m); + if (counts[k] === 1) neutral[k] = m; + }}); + const map = {{ exact, neutral }}; + Object.assign(map, neutral); + return map; +}} +function baselineFor(map, m) {{ + if (!map) return null; + return map.exact[backendMetricKey(m)] || map.neutral[neutralMetricKey(m)] || null; +}} +function backendDeltaSection(title, data, valueField, formatValue, higherBetter) {{ + const groups = {{}}; + data.forEach(m => {{ + if (!m.sync_mode) return; + const key = neutralMetricKey(m); + if (!groups[key]) groups[key] = {{ benchmark: m.benchmark_key || m.benchmark, metric: m.metric }}; + groups[key][m.sync_mode] = m; + }}); + const rows = Object.values(groups).filter(g => g.crdt && g.lww).map(g => {{ + const crdt = g.crdt[valueField]; + const lww = g.lww[valueField]; + const pct = crdt ? ((lww - crdt) / crdt) * 100 : 0; + return ` + ${{g.benchmark}} + ${{g.metric}} + ${{formatValue(crdt)}} + ${{formatValue(lww)}} + ${{fmtDelta(pct, higherBetter)}} + `; + }}).join(''); + if (!rows) return ''; + return ` +
+ ${{title}} + LWW vs CRDT +
+ + + ${{rows}} +
BenchmarkMetricCRDTLWWDelta
`; +}} function renderLatency() {{ let data = LAT; @@ -943,9 +1034,9 @@ def generate_html( if (benchF) data = data.filter(m => m.benchmark === benchF); if (profileF) data = data.filter(m => m.profile === profileF); if (langFilter.lat) data = data.filter(m => m.lang === langFilter.lat); - const bMap = COMPARING ? Object.fromEntries(B_LAT.map(m => [m.benchmark+'/'+m.metric, m])) : {{}}; + const bMap = COMPARING ? buildMetricMap(B_LAT) : null; - const labels = data.map(m => m.metric); + const labels = data.map(metricLabel); const toUs = ns => ns/1000; if (latChart) {{ latChart.destroy(); latChart = null; }} @@ -972,7 +1063,7 @@ def generate_html( {{ label: 'p99', data: data.map(m=>toUs(m.p99_ns)), backgroundColor: PALETTE[3]+'aa' }}, ]; if (COMPARING && B_LAT.length) {{ - datasets.push({{ label: 'Baseline Mean', data: data.map(m=>toUs(bMap[m.benchmark+'/'+m.metric]?.mean_ns||0)), backgroundColor: BASE_COLOR+'55', borderColor: BASE_COLOR, borderWidth: 1, borderDash: [4,2] }}); + datasets.push({{ label: 'Baseline Mean', data: data.map(m=>toUs(baselineFor(bMap, m)?.mean_ns||0)), backgroundColor: BASE_COLOR+'55', borderColor: BASE_COLOR, borderWidth: 1, borderDash: [4,2] }}); }} latChart = new Chart(document.getElementById('lat-dist'), {{ type: 'bar', data: {{ labels, datasets }}, @@ -996,7 +1087,7 @@ def generate_html( }}); const renderLatencyRows = rows => rows.map(m => {{ - const b = bMap[m.benchmark+'/'+m.metric]; + const b = baselineFor(bMap, m); const deltaCell = b ? fmtDelta(((m.mean_ns - b.mean_ns) / b.mean_ns)*100, false) : ''; const stddev = m.additional?.stddev_ns ?? 0; const cv = m.mean_ns > 0 ? (stddev / m.mean_ns) * 100 : 0; @@ -1010,7 +1101,7 @@ def generate_html( const pmax = m.has_percentiles ? fmtNs(m.max_ns) : na; return ` ${{langBadge(m.lang)}} - ${{m.benchmark}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{m.metric}} ${{m.count > 0 ? m.count.toLocaleString() : na}} ${{fmtNs(m.mean_ns)}}${{deltaCell ? ' ' + deltaCell : ''}} @@ -1040,7 +1131,8 @@ def generate_html( ${{renderLatencyRows(rows) || 'No data'}} `; }}).join(''); - document.getElementById('lat-detail-sections').innerHTML = grouped || '

No data

'; + const backendDelta = backendDeltaSection('Backend Latency Difference', data, 'mean_ns', fmtNs, false); + document.getElementById('lat-detail-sections').innerHTML = (grouped + backendDelta) || '

No data

'; }} // ── Throughput ──────────────────────────────────────────────────────────────── @@ -1052,15 +1144,15 @@ def generate_html( if (benchF) data = data.filter(m => m.benchmark === benchF); if (profileF) data = data.filter(m => m.profile === profileF); if (langFilter.thr) data = data.filter(m => m.lang === langFilter.thr); - const bMap = COMPARING ? Object.fromEntries(B_THR.map(m => [m.benchmark+'/'+m.metric, m])) : {{}}; + const bMap = COMPARING ? buildMetricMap(B_THR) : null; if (thrChart) thrChart.destroy(); const datasets = [{{ label: 'Ops/sec', data: data.map(m=>m.ops_per_sec), backgroundColor: PALETTE[1]+'cc', borderColor: PALETTE[1], borderWidth: 1 }}]; if (COMPARING && B_THR.length) {{ - datasets.push({{ label: 'Baseline', data: data.map(m=>bMap[m.benchmark+'/'+m.metric]?.ops_per_sec||0), backgroundColor: BASE_COLOR+'55', borderColor: BASE_COLOR, borderWidth: 1 }}); + datasets.push({{ label: 'Baseline', data: data.map(m=>baselineFor(bMap, m)?.ops_per_sec||0), backgroundColor: BASE_COLOR+'55', borderColor: BASE_COLOR, borderWidth: 1 }}); }} thrChart = new Chart(document.getElementById('thr-bar'), {{ - type: 'bar', data: {{ labels: data.map(m=>m.metric), datasets }}, + type: 'bar', data: {{ labels: data.map(metricLabel), datasets }}, options: {{ ...CD, indexAxis: 'y', scales: {{ ...CD.scales, x: {{ ...CD.scales.x, title: {{ display:true, text:'ops/sec', color:'#8b8fa8' }} }} }}, plugins: {{ ...CD.plugins, tooltip: {{ ...CD.plugins.tooltip, @@ -1069,11 +1161,11 @@ def generate_html( }}); const renderThroughputRows = rows => rows.map(m => {{ - const b = bMap[m.benchmark+'/'+m.metric]; + const b = baselineFor(bMap, m); const deltaCell = b ? fmtDelta(((m.ops_per_sec - b.ops_per_sec) / b.ops_per_sec)*100, true) : ''; return ` ${{langBadge(m.lang)}} - ${{m.benchmark}} ${{profileBadge(m.profile)}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{profileBadge(m.profile)}} ${{m.metric}} ${{fmtOps(m.ops_per_sec)}}${{deltaCell ? ' ' + deltaCell : ''}} ${{m.total_ops.toLocaleString()}} @@ -1096,7 +1188,8 @@ def generate_html( ${{renderThroughputRows(rows) || 'No data'}} `; }}).join(''); - document.getElementById('thr-detail-sections').innerHTML = grouped || '

No data

'; + const backendDelta = backendDeltaSection('Backend Throughput Difference', data, 'ops_per_sec', fmtOps, true); + document.getElementById('thr-detail-sections').innerHTML = (grouped + backendDelta) || '

No data

'; }} function renderOther() {{ @@ -1106,10 +1199,10 @@ def generate_html( if (benchF) data = data.filter(m => m.benchmark === benchF); if (profileF) data = data.filter(m => m.profile === profileF); if (langFilter.oth) data = data.filter(m => m.lang === langFilter.oth); - const bMap = COMPARING ? Object.fromEntries(B_OTH.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])) : {{}}; + const bMap = COMPARING ? buildMetricMap(B_OTH) : null; const renderRows = rows => rows.map(m => {{ - const b = bMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; + const b = baselineFor(bMap, m); const deltaCell = b && typeof m.value === 'number' && typeof b.value === 'number' && b.value !== 0 ? fmtDelta(((m.value - b.value) / b.value) * 100, true) : ''; @@ -1117,7 +1210,7 @@ def generate_html( return ` ${{langBadge(m.lang)}} ${{m.category}} - ${{m.benchmark}} ${{profileBadge(m.profile)}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{profileBadge(m.profile)}} ${{m.metric}} ${{fmtValue(m.value, m.unit)}}${{deltaCell ? ' ' + deltaCell : ''}} ${{b ? fmtValue(b.value, b.unit) : ''}} @@ -1145,6 +1238,12 @@ def generate_html( // ── Scalability Tab ─────────────────────────────────────────────────────────── let sclThrChart = null, sclLatChart = null, sclEffChart = null; +function sclSeriesKey(r) {{ + return r.operation + '/' + (r.sync_mode || ''); +}} +function sclSeriesLabel(r) {{ + return r.operation + (r.sync_mode ? ` [${{r.sync_mode.toUpperCase()}}]` : ''); +}} // Show or hide an empty-state message on a canvas card. // Hides/shows the and adds/removes a sibling

. @@ -1172,7 +1271,7 @@ def generate_html( let bRows = COMPARING ? B_SCL.filter(r => r.scale_dim === dim) : []; if (opSel) bRows = bRows.filter(r => r.operation === opSel); - const ops = [...new Set(rows.map(r => r.operation))]; + const series = [...new Map(rows.map(r => [sclSeriesKey(r), r])).values()]; // ── Empty state ─────────────────────────────────────────────────────────── const noDataMsg = dim === 'agents' @@ -1180,11 +1279,11 @@ def generate_html( : `No scalability data for dimension: ${{dim}}`; // ── Throughput line chart ────────────────────────────────────────────────── - const thrData = ops.map((op, i) => {{ - const pts = rows.filter(r => r.operation === op && r.category === 'throughput') + const thrData = series.map((s, i) => {{ + const pts = rows.filter(r => r.operation === s.operation && (r.sync_mode || '') === (s.sync_mode || '') && r.category === 'throughput') .sort((a, b) => a.scale_val - b.scale_val); return {{ - label: op, + label: sclSeriesLabel(s), data: pts.map(p => ({{x: p.scale_val, y: p.ops_per_sec}})), borderColor: PALETTE[i % PALETTE.length], backgroundColor: PALETTE[i % PALETTE.length] + '33', @@ -1194,13 +1293,13 @@ def generate_html( // Add dashed baseline series when comparing if (COMPARING && bRows.length) {{ - const bOps = [...new Set(bRows.map(r => r.operation))]; - bOps.forEach((op, i) => {{ - const pts = bRows.filter(r => r.operation === op && r.category === 'throughput') + const bSeries = [...new Map(bRows.map(r => [sclSeriesKey(r), r])).values()]; + bSeries.forEach((s, i) => {{ + const pts = bRows.filter(r => r.operation === s.operation && (r.sync_mode || '') === (s.sync_mode || '') && r.category === 'throughput') .sort((a, b) => a.scale_val - b.scale_val); if (pts.length === 0) return; thrData.push({{ - label: op + ' (baseline)', + label: sclSeriesLabel(s) + ' (baseline)', data: pts.map(p => ({{x: p.scale_val, y: p.ops_per_sec}})), borderColor: PALETTE[i % PALETTE.length] + '88', backgroundColor: 'transparent', @@ -1229,11 +1328,11 @@ def generate_html( }} // ── Latency line chart ──────────────────────────────────────────────────── - const latData = ops.map((op, i) => {{ - const pts = rows.filter(r => r.operation === op && r.category === 'latency') + const latData = series.map((s, i) => {{ + const pts = rows.filter(r => r.operation === s.operation && (r.sync_mode || '') === (s.sync_mode || '') && r.category === 'latency') .sort((a, b) => a.scale_val - b.scale_val); return {{ - label: op, + label: sclSeriesLabel(s), data: pts.map(p => ({{x: p.scale_val, y: p.mean_ns / 1000}})), borderColor: PALETTE[i % PALETTE.length], backgroundColor: PALETTE[i % PALETTE.length] + '33', @@ -1243,13 +1342,13 @@ def generate_html( // Add dashed baseline latency series when comparing if (COMPARING && bRows.length) {{ - const bOps = [...new Set(bRows.map(r => r.operation))]; - bOps.forEach((op, i) => {{ - const pts = bRows.filter(r => r.operation === op && r.category === 'latency') + const bSeries = [...new Map(bRows.map(r => [sclSeriesKey(r), r])).values()]; + bSeries.forEach((s, i) => {{ + const pts = bRows.filter(r => r.operation === s.operation && (r.sync_mode || '') === (s.sync_mode || '') && r.category === 'latency') .sort((a, b) => a.scale_val - b.scale_val); if (pts.length === 0) return; latData.push({{ - label: op + ' (baseline)', + label: sclSeriesLabel(s) + ' (baseline)', data: pts.map(p => ({{x: p.scale_val, y: p.mean_ns / 1000}})), borderColor: PALETTE[i % PALETTE.length] + '88', backgroundColor: 'transparent', @@ -1288,13 +1387,13 @@ def generate_html( let effRows = EFF.filter(r => r.scale_dim === dim); if (opSel) effRows = effRows.filter(r => r.operation === opSel); - const effOps = [...new Set(effRows.map(r => r.operation))]; + const effSeries = [...new Map(effRows.map(r => [sclSeriesKey(r), r])).values()]; - const effData = effOps.map((op, i) => {{ - const pts = effRows.filter(r => r.operation === op) + const effData = effSeries.map((s, i) => {{ + const pts = effRows.filter(r => r.operation === s.operation && (r.sync_mode || '') === (s.sync_mode || '')) .sort((a, b) => a.scale_val - b.scale_val); return {{ - label: op, + label: sclSeriesLabel(s), data: pts.map(p => ({{x: p.scale_val, y: p.efficiency}})), borderColor: PALETTE[i % PALETTE.length], backgroundColor: 'transparent', @@ -1339,17 +1438,17 @@ def generate_html( // ── Detail table ────────────────────────────────────────────────────────── const effMap = {{}}; - EFF.forEach(r => {{ effMap[r.operation + '/' + r.scale_dim + '/' + r.scale_val] = r.efficiency; }}); + EFF.forEach(r => {{ effMap[r.operation + '/' + (r.sync_mode || '') + '/' + r.scale_dim + '/' + r.scale_val] = r.efficiency; }}); const tableRows = rows.map(r => {{ - const effKey = r.operation + '/' + r.scale_dim + '/' + r.scale_val; + const effKey = r.operation + '/' + (r.sync_mode || '') + '/' + r.scale_dim + '/' + r.scale_val; const eff = effMap[effKey]; const effCell = eff !== undefined ? eff.toFixed(1) + '%' : '—'; const thrCell = r.category === 'throughput' ? fmtOps(r.ops_per_sec) : '—'; const latCell = r.mean_ns > 0 ? fmtNs(r.mean_ns) : '—'; return ` ${{r.benchmark}} - ${{r.operation}} + ${{r.operation}} ${{syncBadge(r.sync_mode)}} ${{r.scale_dim}} ${{r.scale_val}} ${{thrCell}} @@ -1447,12 +1546,12 @@ def generate_html( // Deduplicate for chart (first-seen per key) const seenChart = new Set(), chartItems = []; for (const m of langLat) {{ - const key = (m.benchmark_key || m.benchmark) + '/' + m.metric; - const b = bLatMap[key]; + const key = backendMetricKey(m); + const b = baselineFor(bLatMap, m); if (b && !seenChart.has(key)) {{ seenChart.add(key); const pct = ((m.mean_ns - b.mean_ns) / b.mean_ns) * 100; - chartItems.push({{ key, label: m.metric + ' [' + m.benchmark + ']', pct }}); + chartItems.push({{ key, label: metricLabel(m) + ' [' + m.benchmark + ']', pct }}); }} }} @@ -1469,12 +1568,12 @@ def generate_html(

` : ''; const latRows = langLat.map(m => {{ - const b = bLatMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; - if (!b) return `${{m.benchmark}}${{m.metric}}no baseline`; + const b = baselineFor(bLatMap, m); + if (!b) return `${{m.benchmark}} ${{syncBadge(m.sync_mode)}}${{m.metric}}no baseline`; const pct = ((m.mean_ns - b.mean_ns) / b.mean_ns) * 100; const p99pct = (m.has_percentiles && b.has_percentiles && b.p99_ns) ? ((m.p99_ns - b.p99_ns) / b.p99_ns) * 100 : null; return ` - ${{m.benchmark}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{m.metric}} ${{fmtNs(b.mean_ns)}} ${{fmtNs(m.mean_ns)}} @@ -1484,11 +1583,11 @@ def generate_html( }}).join(''); const thrRows = langThr.map(m => {{ - const b = bThrMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; - if (!b) return `${{m.benchmark}}${{m.metric}}no baseline`; + const b = baselineFor(bThrMap, m); + if (!b) return `${{m.benchmark}} ${{syncBadge(m.sync_mode)}}${{m.metric}}no baseline`; const pct = ((m.ops_per_sec - b.ops_per_sec) / b.ops_per_sec) * 100; return ` - ${{m.benchmark}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{m.metric}} ${{fmtOps(b.ops_per_sec)}} ${{fmtOps(m.ops_per_sec)}} @@ -1521,14 +1620,14 @@ def generate_html(
` : ''; const othRows = langOth.map(m => {{ - const b = bOthMap[(m.benchmark_key || m.benchmark)+'/'+m.metric]; + const b = baselineFor(bOthMap, m); const deltaCell = b && typeof m.value === 'number' && typeof b.value === 'number' && b.value !== 0 ? fmtDelta(((m.value - b.value) / b.value) * 100, true) : ''; - if (!b) return `${{m.category}}${{m.benchmark}}${{m.metric}}no baseline`; + if (!b) return `${{m.category}}${{m.benchmark}} ${{syncBadge(m.sync_mode)}}${{m.metric}}no baseline`; return ` ${{m.category}} - ${{m.benchmark}} + ${{m.benchmark}} ${{syncBadge(m.sync_mode)}} ${{m.metric}} ${{fmtValue(b.value, b.unit)}} ${{fmtValue(m.value, m.unit)}} @@ -1564,9 +1663,9 @@ def generate_html( const el = document.getElementById('tab-compare'); if (!el || !COMPARING) return; - const bLatMap = Object.fromEntries(B_LAT.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); - const bThrMap = Object.fromEntries(B_THR.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); - const bOthMap = Object.fromEntries(B_OTH.map(m => [(m.benchmark_key || m.benchmark)+'/'+m.metric, m])); + const bLatMap = buildMetricMap(B_LAT); + const bThrMap = buildMetricMap(B_THR); + const bOthMap = buildMetricMap(B_OTH); const pySection = buildLangSection('python', LAT, bLatMap, THR, bThrMap, OTH, bOthMap); const cppSection = buildLangSection('cpp', LAT, bLatMap, THR, bThrMap, OTH, bOthMap); diff --git a/benchmarks/scalability/thread_scaling_bench.cpp b/benchmarks/scalability/thread_scaling_bench.cpp index 64d89900..1c886105 100644 --- a/benchmarks/scalability/thread_scaling_bench.cpp +++ b/benchmarks/scalability/thread_scaling_bench.cpp @@ -365,6 +365,190 @@ TEST_CASE("Edge insert thread scaling", "[SCALABILITY][threads]") { reporter.export_all(result, "edge_insert_thread_scaling"); } +TEST_CASE("Edge changed-attr reassign thread scaling", "[SCALABILITY][threads][diagnostic][edge]") { + MultiAgentFixture fixture; + GraphGenerator generator; + MetricsCollector collector("edge_reassign_attr_thread_scaling"); + + auto config_file = generator.generate_empty_graph(); + REQUIRE(fixture.create_agents(1, config_file)); + auto* graph = fixture.get_agent(0); + REQUIRE(graph != nullptr); + + auto root = graph->get_node_root(); + REQUIRE(root.has_value()); + + constexpr uint32_t POOL_SIZE = 10000; + std::vector pool; + pool.reserve(POOL_SIZE); + for (uint64_t i = 0; i < POOL_SIZE; ++i) { + auto node = GraphGenerator::create_test_node(0, graph->get_agent_id()); + auto res = graph->insert_node(node); + REQUIRE(res.has_value()); + pool.push_back(res.value()); + + auto edge = GraphGenerator::create_test_edge(root->id(), res.value(), graph->get_agent_id()); + REQUIRE(graph->insert_or_assign_edge(edge)); + } + const size_t pool_size = pool.size(); + + ankerl::nanobench::Bench bench; + bench.output(&nb_report_stream()).warmup(0).epochs(1).epochIterations(1); + + for (uint32_t N : {1u, 2u, 4u, 8u}) { + std::atomic total_ops{0}; + std::atomic failed_ops{0}; + std::atomic stop_flag{false}; + std::barrier sync_point(N); + + std::vector threads; + threads.reserve(N); + + const uint32_t stride = static_cast(pool_size / N) + 1; + auto wall_start = steady_clock::now(); + + bench.run("edge_reassign_attr_" + std::to_string(N) + "t", [&] { + for (uint32_t t = 0; t < N; ++t) { + threads.emplace_back([&, tid = t]() { + uint64_t local_ops = 0; + + sync_point.arrive_and_wait(); + + while (!stop_flag.load(std::memory_order_relaxed)) { + uint64_t idx = (local_ops + tid * stride) % pool_size; + auto edge = GraphGenerator::create_test_edge( + root->id(), pool[idx], graph->get_agent_id()); + edge.attrs().insert_or_assign("diagnostic_value", + Attribute(static_cast(local_ops), 0, graph->get_agent_id())); + bool ok = graph->insert_or_assign_edge(edge); + if (!ok) + failed_ops.fetch_add(1, std::memory_order_relaxed); + local_ops++; + } + + total_ops.fetch_add(local_ops, std::memory_order_relaxed); + }); + } + + std::this_thread::sleep_for(THREAD_DUR); + stop_flag.store(true, std::memory_order_relaxed); + for (auto& th : threads) th.join(); + + bench.batch(total_ops.load()); + ankerl::nanobench::doNotOptimizeAway(total_ops.load()); + }); + + if (failed_ops.load() > 0) + std::cerr << "[BENCH edge_reassign_attr threads=" << N << "] " + << failed_ops.load() << " insert_or_assign_edge calls failed\n"; + + auto dur = duration_cast(steady_clock::now() - wall_start); + + const std::string n_str = std::to_string(N); + collector.record_throughput("edge_reassign_changed_attr", total_ops.load(), dur, {{"threads", n_str}}); + + double ops_per_sec = static_cast(total_ops.load()) / + (static_cast(dur.count()) / 1000.0); + collector.record_scalability("edge_reassign_changed_attr", N, ops_per_sec, "ops/sec", + {{"threads", n_str}, {"scale_dim", "threads"}}); + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "edge_reassign_attr_thread_scaling"); +} + +TEST_CASE("Edge same-empty reassign thread scaling", "[SCALABILITY][threads][diagnostic][edge]") { + MultiAgentFixture fixture; + GraphGenerator generator; + MetricsCollector collector("edge_reassign_empty_thread_scaling"); + + auto config_file = generator.generate_empty_graph(); + REQUIRE(fixture.create_agents(1, config_file)); + auto* graph = fixture.get_agent(0); + REQUIRE(graph != nullptr); + + auto root = graph->get_node_root(); + REQUIRE(root.has_value()); + + constexpr uint32_t POOL_SIZE = 10000; + std::vector pool; + pool.reserve(POOL_SIZE); + for (uint64_t i = 0; i < POOL_SIZE; ++i) { + auto node = GraphGenerator::create_test_node(0, graph->get_agent_id()); + auto res = graph->insert_node(node); + REQUIRE(res.has_value()); + pool.push_back(res.value()); + + auto edge = GraphGenerator::create_test_edge(root->id(), res.value(), graph->get_agent_id()); + REQUIRE(graph->insert_or_assign_edge(edge)); + } + const size_t pool_size = pool.size(); + + ankerl::nanobench::Bench bench; + bench.output(&nb_report_stream()).warmup(0).epochs(1).epochIterations(1); + + for (uint32_t N : {1u, 2u, 4u, 8u}) { + std::atomic total_ops{0}; + std::atomic failed_ops{0}; + std::atomic stop_flag{false}; + std::barrier sync_point(N); + + std::vector threads; + threads.reserve(N); + + const uint32_t stride = static_cast(pool_size / N) + 1; + auto wall_start = steady_clock::now(); + + bench.run("edge_reassign_empty_" + std::to_string(N) + "t", [&] { + for (uint32_t t = 0; t < N; ++t) { + threads.emplace_back([&, tid = t]() { + uint64_t local_ops = 0; + + sync_point.arrive_and_wait(); + + while (!stop_flag.load(std::memory_order_relaxed)) { + uint64_t idx = (local_ops + tid * stride) % pool_size; + auto edge = GraphGenerator::create_test_edge( + root->id(), pool[idx], graph->get_agent_id()); + bool ok = graph->insert_or_assign_edge(edge); + if (!ok) + failed_ops.fetch_add(1, std::memory_order_relaxed); + local_ops++; + } + + total_ops.fetch_add(local_ops, std::memory_order_relaxed); + }); + } + + std::this_thread::sleep_for(THREAD_DUR); + stop_flag.store(true, std::memory_order_relaxed); + for (auto& th : threads) th.join(); + + bench.batch(total_ops.load()); + ankerl::nanobench::doNotOptimizeAway(total_ops.load()); + }); + + if (failed_ops.load() > 0) + std::cerr << "[BENCH edge_reassign_empty threads=" << N << "] " + << failed_ops.load() << " insert_or_assign_edge calls failed\n"; + + auto dur = duration_cast(steady_clock::now() - wall_start); + + const std::string n_str = std::to_string(N); + collector.record_throughput("edge_reassign_same_empty", total_ops.load(), dur, {{"threads", n_str}}); + + double ops_per_sec = static_cast(total_ops.load()) / + (static_cast(dur.count()) / 1000.0); + collector.record_scalability("edge_reassign_same_empty", N, ops_per_sec, "ops/sec", + {{"threads", n_str}, {"scale_dim", "threads"}}); + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "edge_reassign_empty_thread_scaling"); +} + // ── Edge read ───────────────────────────────────────────────────────────────── TEST_CASE("Edge read thread scaling", "[SCALABILITY][threads]") { diff --git a/benchmarks/throughput/single_agent_ops_bench.cpp b/benchmarks/throughput/single_agent_ops_bench.cpp index 3fb79e42..7aee3b8d 100644 --- a/benchmarks/throughput/single_agent_ops_bench.cpp +++ b/benchmarks/throughput/single_agent_ops_bench.cpp @@ -7,6 +7,9 @@ #include "../fixtures/multi_agent_fixture.h" #include "../fixtures/graph_generator.h" +#include +#include + using namespace DSR; using namespace DSR::Benchmark; @@ -168,6 +171,95 @@ TEST_CASE("Edge insertion throughput", "[THROUGHPUT][single]") { reporter.export_all(result, "edge_insert_throughput"); } +TEST_CASE("Edge upsert mode diagnostics", "[THROUGHPUT][LATENCY][diagnostic][edge]") { + GraphGenerator generator; + MetricsCollector collector("edge_upsert_modes"); + + auto make_graph_with_targets = [&](uint64_t target_count, bool preinsert_edges) { + auto fixture = std::make_unique(); + auto config_file = generator.generate_empty_graph(); + REQUIRE(fixture->create_agents(1, config_file)); + auto* graph = fixture->get_agent(0); + REQUIRE(graph != nullptr); + + auto root = graph->get_node_root(); + REQUIRE(root.has_value()); + + std::vector targets; + targets.reserve(target_count); + for (uint64_t i = 0; i < target_count; ++i) { + auto node = GraphGenerator::create_test_node(0, graph->get_agent_id()); + auto result = graph->insert_node(node); + REQUIRE(result.has_value()); + targets.push_back(result.value()); + if (preinsert_edges) { + auto edge = GraphGenerator::create_test_edge(root->id(), result.value(), graph->get_agent_id()); + REQUIRE(graph->insert_or_assign_edge(edge)); + } + } + + return std::tuple{std::move(fixture), root->id(), std::move(targets)}; + }; + + { + auto [fixture, root_id, targets] = make_graph_with_targets(12000, false); + auto* graph = fixture->get_agent(0); + size_t idx = 0; + auto sampled = run_sampled_benchmark( + 50, + 10000, + [&] { + auto edge = GraphGenerator::create_test_edge(root_id, targets[idx++], graph->get_agent_id()); + REQUIRE(graph->insert_or_assign_edge(edge)); + }, + [&] { fixture->process_events(1); }, + 8); + collector.record_latency_stats("edge_fresh_insert", sampled.latency); + collector.record_throughput("edge_fresh_insert", sampled.latency.count, sampled.wall_time); + } + + { + auto [fixture, root_id, targets] = make_graph_with_targets(10000, true); + auto* graph = fixture->get_agent(0); + size_t idx = 0; + auto sampled = run_sampled_benchmark( + 50, + 10000, + [&] { + auto edge = GraphGenerator::create_test_edge(root_id, targets[idx++ % targets.size()], graph->get_agent_id()); + REQUIRE(graph->insert_or_assign_edge(edge)); + }, + [&] { fixture->process_events(1); }, + 8); + collector.record_latency_stats("edge_reassign_same_empty", sampled.latency); + collector.record_throughput("edge_reassign_same_empty", sampled.latency.count, sampled.wall_time); + } + + { + auto [fixture, root_id, targets] = make_graph_with_targets(10000, true); + auto* graph = fixture->get_agent(0); + size_t idx = 0; + int32_t value = 0; + auto sampled = run_sampled_benchmark( + 50, + 10000, + [&] { + auto edge = GraphGenerator::create_test_edge(root_id, targets[idx++ % targets.size()], graph->get_agent_id()); + edge.attrs().insert_or_assign("diagnostic_value", + Attribute(static_cast(value++), 0, graph->get_agent_id())); + REQUIRE(graph->insert_or_assign_edge(edge)); + }, + [&] { fixture->process_events(1); }, + 8); + collector.record_latency_stats("edge_reassign_changed_attr", sampled.latency); + collector.record_throughput("edge_reassign_changed_attr", sampled.latency.count, sampled.wall_time); + } + + auto result = collector.finalize(); + ReportGenerator reporter("results"); + reporter.export_all(result, "edge_upsert_modes"); +} + TEST_CASE("Edge read throughput", "[THROUGHPUT][single]") { MultiAgentFixture fixture; GraphGenerator generator; From 478a3953e5619abdf733883dfc2723be7678305f Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 1 May 2026 11:49:49 +0200 Subject: [PATCH 34/38] refactor: erase deleted nodes from node map --- api/dsr_crdt_sync_engine.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/api/dsr_crdt_sync_engine.cpp b/api/dsr_crdt_sync_engine.cpp index 963abf6d..bb8e4b9c 100644 --- a/api/dsr_crdt_sync_engine.cpp +++ b/api/dsr_crdt_sync_engine.cpp @@ -748,6 +748,7 @@ void CRDTSyncEngine::join_delta_node(MvregNodeMsg&& mvreg) maybe_deleted_node.has_value() ? std::optional{maybe_deleted_node->type} : std::nullopt, maybe_deleted_node.has_value() ? collect_outgoing_edge_keys(maybe_deleted_node->fano) : SyncEngineHost::EdgeKeyList{}); delete_unprocessed_deltas(); + nodes_.erase(id); } else { const auto& reg = nodes_.at(id).read_reg(); current_type = reg.type; From 3f47273de6419e9cbffa5ff19b66f4f7a550a132 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 15 May 2026 18:46:17 +0200 Subject: [PATCH 35/38] test DDS serialization payload sizing --- tests/synchronization/type_translation.cpp | 181 +++++++++++++++++++++ 1 file changed, 181 insertions(+) diff --git a/tests/synchronization/type_translation.cpp b/tests/synchronization/type_translation.cpp index 683282b5..a3b0bb14 100644 --- a/tests/synchronization/type_translation.cpp +++ b/tests/synchronization/type_translation.cpp @@ -20,6 +20,7 @@ #include #include +#include using namespace DSR; @@ -39,6 +40,24 @@ T roundtrip(const T& src) return dst; } +template +T pubsub_roundtrip(const T& src, const std::string& type_name) +{ + CRDTPubSubType type(type_name); + const auto representation = eprosima::fastdds::dds::DataRepresentationId_t::XCDR_DATA_REPRESENTATION; + const uint32_t calculated_size = type.calculate_serialized_size(&src, representation); + REQUIRE(calculated_size >= eprosima::fastdds::rtps::SerializedPayload_t::representation_header_size); + + eprosima::fastdds::rtps::SerializedPayload_t payload(calculated_size); + REQUIRE(type.serialize(&src, payload, representation)); + REQUIRE(payload.length <= calculated_size); + REQUIRE(payload.length > eprosima::fastdds::rtps::SerializedPayload_t::representation_header_size); + + T dst; + REQUIRE(type.deserialize(payload, &dst)); + return dst; +} + TEST_CASE("NODE: from DSR representation to CRDT and back via serialization", "[TRANSLATION][NODE]"){ @@ -253,6 +272,168 @@ TEST_CASE("Wire metadata round-trip preserves sync mode", "[TRANSLATION][SYNC_MO } } +TEST_CASE("CRDTPubSubType serializes representative wire messages", "[TRANSLATION][SERIALIZATION][DDS]") +{ + const Attribute level_attr(7, 1000, 2); + const Attribute name_attr(std::string("camera"), 1001, 2); + const Attribute vector_attr(std::vector{1.0F, 2.0F, 3.0F}, 1002, 2); + + auto node = Node::create( + std::map{ + {"level", level_attr}, + {"name", name_attr}, + {"pose", vector_attr}, + }, + {}); + node.id(10); + node.name("robot"); + node.agent_id(2); + + mvreg node_reg; + auto node_delta = node_reg.write(user_node_to_crdt(node)); + auto node_msg = CRDTNode_to_Msg(node.agent_id(), node.id(), std::move(node_delta)); + node_msg.sync_mode = sync_mode_wire_value(SyncMode::CRDT); + + auto node_rt = pubsub_roundtrip(node_msg, "MvregNodeMsg"); + REQUIRE(node_rt.id == node_msg.id); + REQUIRE(node_rt.agent_id == node_msg.agent_id); + REQUIRE(node_rt.dk.read_reg().attrs == node_msg.dk.read_reg().attrs); + + CRDT::Edge crdt_edge; + crdt_edge.from = 10; + crdt_edge.to = 20; + crdt_edge.type = "RT"; + crdt_edge.agent_id = 2; + mvreg weight_attr; + crdt_edge.attrs.emplace("weight", weight_attr.write(Attribute(3.5F, 1003, 2))); + mvreg edge_reg; + auto edge_msg = CRDTEdge_to_Msg(2, crdt_edge.from, crdt_edge.to, crdt_edge.type, edge_reg.write(crdt_edge)); + + auto edge_rt = pubsub_roundtrip(edge_msg, "MvregEdgeMsg"); + REQUIRE(edge_rt.from == edge_msg.from); + REQUIRE(edge_rt.to == edge_msg.to); + REQUIRE(edge_rt.type == edge_msg.type); + REQUIRE(edge_rt.dk.read_reg().attrs == edge_msg.dk.read_reg().attrs); + + mvreg attr_reg; + auto node_attr_msg = CRDTNodeAttr_to_Msg(2, 1, node.id(), "status", attr_reg.write(Attribute(true, 1004, 2))); + MvregNodeAttrVec node_attr_vec; + node_attr_vec.vec.push_back(std::move(node_attr_msg)); + + auto node_attr_rt = pubsub_roundtrip(node_attr_vec, "MvregNodeAttrVec"); + REQUIRE(node_attr_rt.vec.size() == node_attr_vec.vec.size()); + REQUIRE(node_attr_rt.vec.front().node == node.id()); + REQUIRE(node_attr_rt.vec.front().attr_name == "status"); + + mvreg edge_attr_reg; + auto edge_attr_msg = CRDTEdgeAttr_to_Msg( + 2, 10, crdt_edge.from, crdt_edge.to, crdt_edge.type, "confidence", + edge_attr_reg.write(Attribute(0.75, 1005, 2))); + MvregEdgeAttrVec edge_attr_vec; + edge_attr_vec.vec.push_back(std::move(edge_attr_msg)); + + auto edge_attr_rt = pubsub_roundtrip(edge_attr_vec, "MvregEdgeAttrVec"); + REQUIRE(edge_attr_rt.vec.size() == edge_attr_vec.vec.size()); + REQUIRE(edge_attr_rt.vec.front().from_node == crdt_edge.from); + REQUIRE(edge_attr_rt.vec.front().to_node == crdt_edge.to); + REQUIRE(edge_attr_rt.vec.front().attr_name == "confidence"); + + OrMap graph; + graph.id = 2; + graph.to_id = 3; + graph.sync_mode = sync_mode_wire_value(SyncMode::CRDT); + graph.m.emplace(node_msg.id, node_msg); + + auto graph_rt = pubsub_roundtrip(graph, "OrMap"); + REQUIRE(graph_rt.id == graph.id); + REQUIRE(graph_rt.to_id == graph.to_id); + REQUIRE(graph_rt.m.size() == graph.m.size()); + REQUIRE(graph_rt.m.at(node_msg.id).dk.read_reg().attrs == node_msg.dk.read_reg().attrs); + + GraphRequest request; + request.from = "agent"; + request.id = 9; + request.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto request_rt = pubsub_roundtrip(request, "GraphRequest"); + REQUIRE(request_rt.from == request.from); + REQUIRE(request_rt.id == request.id); + REQUIRE(request_rt.sync_mode == request.sync_mode); + + LWWNodeMsg lww_node; + lww_node.id = 30; + lww_node.type = "camera"; + lww_node.name = "front_camera"; + lww_node.attrs.emplace("serial", Attribute(std::string("abc123"), 2000, 4)); + lww_node.agent_id = 4; + lww_node.timestamp = 2000; + lww_node.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto lww_node_rt = pubsub_roundtrip(lww_node, "LWWNodeMsg"); + REQUIRE(lww_node_rt.id == lww_node.id); + REQUIRE(lww_node_rt.attrs == lww_node.attrs); + REQUIRE(lww_node_rt.sync_mode == lww_node.sync_mode); + + LWWEdgeMsg lww_edge; + lww_edge.from = 30; + lww_edge.to = 10; + lww_edge.type = "sees"; + lww_edge.attrs.emplace("probability", Attribute(0.9F, 2001, 4)); + lww_edge.agent_id = 4; + lww_edge.timestamp = 2001; + lww_edge.sync_mode = sync_mode_wire_value(SyncMode::LWW); + + auto lww_edge_rt = pubsub_roundtrip(lww_edge, "LWWEdgeMsg"); + REQUIRE(lww_edge_rt.from == lww_edge.from); + REQUIRE(lww_edge_rt.to == lww_edge.to); + REQUIRE(lww_edge_rt.attrs == lww_edge.attrs); + + LWWNodeAttrVec lww_node_attrs; + lww_node_attrs.vec.push_back(LWWNodeAttrMsg{ + .node_id = lww_node.id, + .attr_name = "serial", + .value = Attribute(std::string("xyz789"), 2002, 4), + .agent_id = 4, + .timestamp = 2002, + .deleted = false, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW)}); + + auto lww_node_attrs_rt = pubsub_roundtrip(lww_node_attrs, "LWWNodeAttrVec"); + REQUIRE(lww_node_attrs_rt.vec.size() == 1); + REQUIRE(lww_node_attrs_rt.vec.front().attr_name == "serial"); + + LWWEdgeAttrVec lww_edge_attrs; + lww_edge_attrs.vec.push_back(LWWEdgeAttrMsg{ + .from = lww_edge.from, + .to = lww_edge.to, + .type = lww_edge.type, + .attr_name = "probability", + .value = Attribute(0.95F, 2003, 4), + .agent_id = 4, + .timestamp = 2003, + .deleted = false, + .protocol_version = DSR_PROTOCOL_VERSION, + .sync_mode = sync_mode_wire_value(SyncMode::LWW)}); + + auto lww_edge_attrs_rt = pubsub_roundtrip(lww_edge_attrs, "LWWEdgeAttrVec"); + REQUIRE(lww_edge_attrs_rt.vec.size() == 1); + REQUIRE(lww_edge_attrs_rt.vec.front().attr_name == "probability"); + + LWWGraphSnapshot lww_graph; + lww_graph.id = 4; + lww_graph.to_id = 5; + lww_graph.tombstone_window_ms = 300000; + lww_graph.sync_mode = sync_mode_wire_value(SyncMode::LWW); + lww_graph.nodes.push_back(lww_node); + lww_graph.edges.push_back(lww_edge); + + auto lww_graph_rt = pubsub_roundtrip(lww_graph, "LWWGraphSnapshot"); + REQUIRE(lww_graph_rt.id == lww_graph.id); + REQUIRE(lww_graph_rt.nodes.size() == 1); + REQUIRE(lww_graph_rt.edges.size() == 1); +} + TEST_CASE("Sync engine interface message aliases compile", "[SYNC_ENGINE][COMPILE]") { NodeDeltaMessage node_delta = MvregNodeMsg{}; From b87b48299c934bf824d0c6ba8d472ef2f92c6843 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Fri, 15 May 2026 19:19:50 +0200 Subject: [PATCH 36/38] feat: allow env overrides for some dds configurations --- core/CMakeLists.txt | 1 + core/include/dsr/core/rtps/env_overrides.h | 44 +++++++++++ core/rtps/dsrparticipant.cpp | 85 ++++++++++++++++++++-- core/rtps/dsrpublisher.cpp | 44 +++++++++-- core/rtps/dsrsubscriber.cpp | 37 +++++++++- 5 files changed, 198 insertions(+), 13 deletions(-) create mode 100644 core/include/dsr/core/rtps/env_overrides.h diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 09164253..222233b2 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -33,6 +33,7 @@ target_sources(dsr_core include/dsr/core/rtps/dsrparticipant.h include/dsr/core/rtps/dsrpublisher.h include/dsr/core/rtps/dsrsubscriber.h + include/dsr/core/rtps/env_overrides.h include/dsr/core/rtps/CRDTPubSubTypes.h include/dsr/core/serialization/serializable.h diff --git a/core/include/dsr/core/rtps/env_overrides.h b/core/include/dsr/core/rtps/env_overrides.h new file mode 100644 index 00000000..071513f8 --- /dev/null +++ b/core/include/dsr/core/rtps/env_overrides.h @@ -0,0 +1,44 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace DSR::RTPS::Env { + +struct UInt32Override +{ + const char* raw {nullptr}; + std::optional value; + + [[nodiscard]] bool present() const noexcept + { + return raw != nullptr && raw[0] != '\0'; + } +}; + +inline UInt32Override read_u32( + const char* name) +{ + UInt32Override result; + result.raw = std::getenv(name); + if (!result.present()) + { + return result; + } + + errno = 0; + char* end = nullptr; + const auto parsed = std::strtoull(result.raw, &end, 10); + if (errno == 0 && end != result.raw && *end == '\0' && + parsed <= std::numeric_limits::max()) + { + result.value = static_cast(parsed); + } + + return result; +} + +} // namespace DSR::RTPS::Env diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 7c13b57f..ac6ba1f5 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -7,8 +7,14 @@ #include #include #include +#include #include +#include +#include +#include +#include + using namespace eprosima::fastdds::dds; using namespace eprosima::fastdds::rtps; @@ -33,6 +39,65 @@ bool is_lww_mode(uint8_t sync_mode_wire) return sync_mode_wire == 1; } +uint32_t env_u32_or(const char* name, uint32_t fallback, uint32_t minimum = 0) +{ + const auto value = DSR::RTPS::Env::read_u32(name); + if (!value.present()) { + return fallback; + } + if (!value.value.has_value() || *value.value < minimum) { + qWarning() << "Ignoring invalid" << name << "value" << value.raw; + return fallback; + } + qInfo() << "Using" << name << "override" << *value.value; + return *value.value; +} + +template +void apply_u32_env(const char* name, uint32_t minimum, Apply&& apply) +{ + const auto value = DSR::RTPS::Env::read_u32(name); + if (!value.present()) { + return; + } + if (!value.value.has_value() || *value.value < minimum) { + qWarning() << "Ignoring invalid" << name << "value" << value.raw; + return; + } + qInfo() << "Using" << name << "override" << *value.value; + apply(*value.value); +} + +eprosima::fastdds::dds::Log::Kind fastdds_log_verbosity_from_env( + eprosima::fastdds::dds::Log::Kind fallback) +{ + const char* raw = std::getenv("DSR_FASTDDS_LOG_VERBOSITY"); + if (raw == nullptr || raw[0] == '\0') { + return fallback; + } + + std::string value(raw); + std::transform(value.begin(), value.end(), value.begin(), [](unsigned char c) { + return static_cast(std::toupper(c)); + }); + + if (value == "ERROR" || value == "0") { + qInfo() << "Using DSR_FASTDDS_LOG_VERBOSITY override ERROR"; + return eprosima::fastdds::dds::Log::Error; + } + if (value == "WARNING" || value == "WARN" || value == "1") { + qInfo() << "Using DSR_FASTDDS_LOG_VERBOSITY override WARNING"; + return eprosima::fastdds::dds::Log::Warning; + } + if (value == "INFO" || value == "2") { + qInfo() << "Using DSR_FASTDDS_LOG_VERBOSITY override INFO"; + return eprosima::fastdds::dds::Log::Info; + } + + qWarning() << "Ignoring invalid DSR_FASTDDS_LOG_VERBOSITY value" << raw; + return fallback; +} + struct TransportFamily { const char* node_topic_name; @@ -127,23 +192,32 @@ std::tuple DSRParticipant::init_ // Same-host deployments should prefer shared memory. Keep loopback UDP // as a discovery/data fallback for environments where SHM is limited. auto shm_transport = std::make_shared(); + apply_u32_env("DSR_SHM_SEGMENT_SIZE", 0, [&](uint32_t value) { + shm_transport->segment_size(value); + }); + apply_u32_env("DSR_SHM_PORT_QUEUE_CAPACITY", 1, [&](uint32_t value) { + shm_transport->port_queue_capacity(value); + }); + apply_u32_env("DSR_SHM_HEALTHY_CHECK_TIMEOUT_MS", 0, [&](uint32_t value) { + shm_transport->healthy_check_timeout_ms(value); + }); PParam.transport().user_transports.push_back(shm_transport); auto udp_transport = std::make_shared(); - udp_transport->maxMessageSize = 65500; + udp_transport->maxMessageSize = env_u32_or("DSR_UDP_MAX_MESSAGE_SIZE", 65500, 1); udp_transport->interface_allowlist.emplace_back("127.0.0.1"); PParam.transport().user_transports.push_back(udp_transport); } else { auto udp_transport = std::make_shared(); - udp_transport->maxMessageSize = 65500; + udp_transport->maxMessageSize = env_u32_or("DSR_UDP_MAX_MESSAGE_SIZE", 65500, 1); for (const auto& ip : host_ipv4_interfaces()) { udp_transport->interface_allowlist.emplace_back(ip); } PParam.transport().user_transports.push_back(udp_transport); } - PParam.transport().send_socket_buffer_size = 33554432; - PParam.transport().listen_socket_buffer_size = 33554432; + PParam.transport().send_socket_buffer_size = env_u32_or("DSR_SOCKET_SEND_BUFFER_SIZE", 33554432); + PParam.transport().listen_socket_buffer_size = env_u32_or("DSR_SOCKET_LISTEN_BUFFER_SIZE", 33554432); //Discovery @@ -155,7 +229,8 @@ std::tuple DSRParticipant::init_ PParam.wire_protocol().builtin.discovery_config.leaseDuration_announcementperiod = eprosima::fastdds::dds::Duration_t(3, 0); - eprosima::fastdds::dds::Log::SetVerbosity(eprosima::fastdds::dds::Log::Error); + eprosima::fastdds::dds::Log::SetVerbosity( + fastdds_log_verbosity_from_env(eprosima::fastdds::dds::Log::Error)); m_listener = std::make_unique(std::move(fn)); diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index c555c08f..8db58ae1 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -6,10 +6,12 @@ #include #include +#include #include #include +#include using namespace eprosima::fastdds; using namespace eprosima::fastdds::rtps; @@ -26,6 +28,27 @@ Locator_t domain_multicast_locator(int8_t domain_id) ("239.255." + std::to_string(domain / 250) + "." + std::to_string(1 + (domain % 250))).c_str()); return locator; } + +uint32_t env_u32_or(const char* name, uint32_t fallback, uint32_t minimum = 0) +{ + const auto value = DSR::RTPS::Env::read_u32(name); + if (!value.present()) { + return fallback; + } + if (!value.value.has_value() || *value.value < minimum) { + qWarning() << "Ignoring invalid" << name << "value" << value.raw; + return fallback; + } + qInfo() << "Using" << name << "override" << *value.value; + return *value.value; +} + +eprosima::fastdds::dds::Duration_t duration_from_ms(uint32_t ms) +{ + return eprosima::fastdds::dds::Duration_t( + static_cast(ms / 1000U), + static_cast((ms % 1000U) * 1000000U)); +} } DSRPublisher::DSRPublisher() : mp_participant(nullptr), mp_publisher(nullptr), mp_writer(nullptr) @@ -68,20 +91,29 @@ std::tuple(env_u32_or("DSR_STREAM_HISTORY_DEPTH", 50, 1)); + dataWriterQos.history().depth = depth; + dataWriterQos.resource_limits().max_samples = std::max(dataWriterQos.resource_limits().max_samples, depth); + dataWriterQos.resource_limits().allocated_samples = + std::max(dataWriterQos.resource_limits().allocated_samples, depth); dataWriterQos.reliable_writer_qos().disable_positive_acks.enabled = true; + } else { + const auto max_samples = static_cast(env_u32_or("DSR_RELIABLE_MAX_SAMPLES", 300, 1)); + dataWriterQos.resource_limits().max_samples = max_samples; + dataWriterQos.resource_limits().allocated_samples = max_samples; } // Check ACK for sended messages. - dataWriterQos.reliable_writer_qos().times.heartbeat_period.seconds = 0; - dataWriterQos.reliable_writer_qos().times.heartbeat_period.nanosec = 20000000; //20 ms. This value should be more or less close to the sending frequency. + dataWriterQos.reliable_writer_qos().times.heartbeat_period = + duration_from_ms(env_u32_or("DSR_WRITER_HEARTBEAT_PERIOD_MS", 20)); //Check latency - dataWriterQos.latency_budget().duration = {0,10000000}; //10ms; + dataWriterQos.latency_budget().duration = + duration_from_ms(env_u32_or("DSR_WRITER_LATENCY_BUDGET_MS", 10)); //Invalidate data after 1 second. If we dont receive it after this time we probably won't get it. - dataWriterQos.lifespan().duration = 1; + dataWriterQos.lifespan().duration = + duration_from_ms(env_u32_or("DSR_WRITER_LIFESPAN_MS", 1000)); int retry = 0; diff --git a/core/rtps/dsrsubscriber.cpp b/core/rtps/dsrsubscriber.cpp index 2332d1be..2c9aab1d 100644 --- a/core/rtps/dsrsubscriber.cpp +++ b/core/rtps/dsrsubscriber.cpp @@ -6,10 +6,13 @@ #include #include +#include #include #include +#include + using namespace eprosima; using namespace eprosima::fastdds; using namespace eprosima::fastdds::rtps; @@ -25,6 +28,27 @@ Locator_t domain_multicast_locator(int8_t domain_id) ("239.255." + std::to_string(domain / 250) + "." + std::to_string(1 + (domain % 250))).c_str()); return locator; } + +uint32_t env_u32_or(const char* name, uint32_t fallback, uint32_t minimum = 0) +{ + const auto value = DSR::RTPS::Env::read_u32(name); + if (!value.present()) { + return fallback; + } + if (!value.value.has_value() || *value.value < minimum) { + qWarning() << "Ignoring invalid" << name << "value" << value.raw; + return fallback; + } + qInfo() << "Using" << name << "override" << *value.value; + return *value.value; +} + +eprosima::fastdds::dds::Duration_t duration_from_ms(uint32_t ms) +{ + return eprosima::fastdds::dds::Duration_t( + static_cast(ms / 1000U), + static_cast((ms % 1000U) * 1000000U)); +} } DSRSubscriber::DSRSubscriber() : mp_participant(nullptr), mp_subscriber(nullptr), mp_reader(nullptr) {} @@ -70,13 +94,22 @@ std::tuple(env_u32_or("DSR_STREAM_HISTORY_DEPTH", 50, 1)); + dataReaderQos.history().depth = depth; + dataReaderQos.resource_limits().max_samples = std::max(dataReaderQos.resource_limits().max_samples, depth); + dataReaderQos.resource_limits().allocated_samples = + std::max(dataReaderQos.resource_limits().allocated_samples, depth); dataReaderQos.reliable_reader_qos().disable_positive_acks.enabled = true; + } else { + const auto max_samples = static_cast(env_u32_or("DSR_RELIABLE_MAX_SAMPLES", 400, 1)); + dataReaderQos.resource_limits().max_samples = max_samples; + dataReaderQos.resource_limits().allocated_samples = max_samples; } From 816af1ebc15af64f1f5cdf87935d9aea4b230503 Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sat, 23 May 2026 18:13:42 +0200 Subject: [PATCH 37/38] fix RT API rebase integration --- api/dsr_rt_api.cpp | 338 ++++++++++++--------------------- tests/graph/inner_gaussian.cpp | 5 +- tests/graph/rt_timestamp.cpp | 2 +- 3 files changed, 125 insertions(+), 220 deletions(-) diff --git a/api/dsr_rt_api.cpp b/api/dsr_rt_api.cpp index 0c7c3c87..bfe82de0 100644 --- a/api/dsr_rt_api.cpp +++ b/api/dsr_rt_api.cpp @@ -28,10 +28,7 @@ namespace Mat::RTMat make_rtmat(const Eigen::Vector3d &translation, const Eigen::Quaterniond &rotation) { - auto rtmat = Mat::RTMat::Identity(); - rtmat.translate(translation); - rtmat.rotate(rotation); - return rtmat; + return Mat::RTMat(Eigen::Translation3d(translation) * rotation); } Mat::RTMat rtmat_at(const std::vector &translation_pack, const std::vector &rotation_pack, std::size_t block_index) @@ -394,233 +391,140 @@ void RT_API::insert_or_assign_edge_RT_impl(Node &n, uint64_t to, std::vectorsize() != RT_COVARIANCE_BLOCK_SIZE) throw std::runtime_error("RT covariance must contain exactly 36 float values"); - bool r1 = false; - bool r2 = false; - bool no_send = true; const bool with_covariance = covariance.has_value(); - std::optional node1_insert; - std::optional node1_update; - std::optional node2; - std::optional to_n_mut; - std::optional to_n_id; - std::optional to_n_type; + auto edge = G->get_edge(n.id(), to, "RT").value_or(Edge::create(n.id(), to)); + if (HISTORY_SIZE <= 0) { - std::unique_lock lock(G->_mutex); - if (const auto* to_n = G->crdt_engine().get_node_ptr(to); to_n != nullptr) - { - to_n_id = to_n->id(); - to_n_type = to_n->type(); - CRDTEdge e; - if (HISTORY_SIZE <= 0) - { - e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); - CRDTAttribute tr(std::move(trans), get_unix_timestamp(), 0); - CRDTAttribute rot(std::move(rot_euler), get_unix_timestamp(), 0); - - auto [it, new_el] = e.attrs().emplace("rt_rotation_euler_xyz", mvreg ()); - it->second.write(std::move(rot)); - auto [it2, new_el2] = e.attrs().emplace("rt_translation", mvreg ()); - it2->second.write(std::move(tr)); - if (with_covariance) - { - CRDTAttribute cov(std::move(covariance.value()), get_unix_timestamp(), 0); - auto [cov_it, cov_new] = e.attrs().emplace("rt_covariance", mvreg ()); - cov_it->second.write(std::move(cov)); - } - } else { - - e = G->crdt_engine().get_crdt_edge(n.id(), to, "RT").value_or(CRDTEdge()); - e.to(to); e.from(n.id()); e.type("RT"); e.agent_id(G->agent_id); - auto head_o = G->get_attrib_by_name(e); - std::optional> tstamps_o = G->get_attrib_by_name(e); - std::optional> tr_pack_o = G->get_attrib_by_name(e); - std::optional> rot_pack_o = G->get_attrib_by_name(e); - std::optional> cov_pack_o; - auto time_stamps = tstamps_o.value_or(std::vector(HISTORY_SIZE, 0)); - auto tr_pack = tr_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); - auto rot_pack = rot_pack_o.value_or(std::vector (BLOCK_SIZE * HISTORY_SIZE, 0.f)); - std::vector cov_pack; - if (with_covariance) - cov_pack_o = G->get_attrib_by_name(e); - - if (time_stamps.size() < BLOCK_SIZE * HISTORY_SIZE) time_stamps.resize(HISTORY_SIZE); - if (tr_pack.size() < BLOCK_SIZE * HISTORY_SIZE) tr_pack.resize(BLOCK_SIZE * HISTORY_SIZE); - if (rot_pack.size() < BLOCK_SIZE * HISTORY_SIZE) rot_pack.resize(BLOCK_SIZE * HISTORY_SIZE); - if (with_covariance) - { - cov_pack = cov_pack_o.value_or(std::vector(RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE, 0.f)); - if (cov_pack.size() < RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE) - cov_pack.resize(RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE); - } - - bool update_index = true; - auto timestamp_index = 0; - if (!head_o.has_value()) { - timestamp_index = 0; - } else { - timestamp_index = (int)(head_o.value_or(0)/BLOCK_SIZE) % HISTORY_SIZE; - } - int index = timestamp_index * BLOCK_SIZE; - auto timestamp_v = (timestamp.has_value()) ? *timestamp : static_cast( - std::chrono::duration_cast( - std::chrono::system_clock::now().time_since_epoch()).count()); - - - if (timestamp_v < time_stamps[prev(timestamp_index, HISTORY_SIZE)]) { - std::vector diffs; - std::transform(time_stamps.begin(), time_stamps.end(), std::back_inserter(diffs), - [t = *timestamp](auto &val) { - return ((int64_t)t - (int64_t)val > 0) ? ((int64_t)t - (int64_t)val) : std::numeric_limits::min(); - }); - - auto pos = (((std::min_element(diffs.begin(), diffs.end())) - diffs.begin())) % HISTORY_SIZE; - - // too old to insert it - if (pos == timestamp_index && timestamp_v < time_stamps[pos]) {return;} - if (pos >= timestamp_index) { - update_index = false; - } - - time_stamps.erase(time_stamps.begin() + timestamp_index); - tr_pack.erase(tr_pack.begin() + index, tr_pack.begin() + index + 3); - rot_pack.erase(rot_pack.begin() + index, rot_pack.begin() + index + 3); - if (with_covariance) - { - const auto covariance_index = timestamp_index * RT_COVARIANCE_BLOCK_SIZE; - cov_pack.erase(cov_pack.begin() + covariance_index, cov_pack.begin() + covariance_index + RT_COVARIANCE_BLOCK_SIZE); - } - - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE, trans[0]); - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 1, trans[1]); - tr_pack.insert(tr_pack.begin() + pos*BLOCK_SIZE + 2, trans[2]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE, rot_euler[0]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 1, rot_euler[1]); - rot_pack.insert(rot_pack.begin() + pos*BLOCK_SIZE + 2, rot_euler[2]); - if (with_covariance) - cov_pack.insert(cov_pack.begin() + pos * RT_COVARIANCE_BLOCK_SIZE, covariance->begin(), covariance->end()); - time_stamps.insert(time_stamps.begin() + pos, *timestamp); - - } else { - - tr_pack[index] = trans[0]; - tr_pack[index + 1] = trans[1]; - tr_pack[index + 2] = trans[2]; - rot_pack[index] = rot_euler[0]; - rot_pack[index + 1] = rot_euler[1]; - rot_pack[index + 2] = rot_euler[2]; - if (with_covariance) - std::copy(covariance->begin(), covariance->end(), cov_pack.begin() + timestamp_index * RT_COVARIANCE_BLOCK_SIZE); - time_stamps[timestamp_index] = timestamp_v; - } - - - CRDTAttribute tr(std::move(tr_pack), get_unix_timestamp(), 0); - CRDTAttribute rot(std::move(rot_pack), get_unix_timestamp(), 0); - CRDTAttribute head_index(index+3, get_unix_timestamp(), 0); - CRDTAttribute timestamps(std::move(time_stamps), get_unix_timestamp(), 0); - std::optional covariance_attr; - if (with_covariance) - covariance_attr.emplace(std::move(cov_pack), get_unix_timestamp(), 0); + G->add_or_modify_attrib_local(edge, std::move(trans)); + G->add_or_modify_attrib_local(edge, std::move(rot_euler)); + if (with_covariance) + G->add_or_modify_attrib_local(edge, std::move(covariance.value())); + } + else + { + auto head_o = G->get_attrib_by_name(edge); + std::optional> tstamps_o = G->get_attrib_by_name(edge); + std::optional> tr_pack_o = G->get_attrib_by_name(edge); + std::optional> rot_pack_o = G->get_attrib_by_name(edge); + std::optional> cov_pack_o; + auto time_stamps = tstamps_o.value_or(std::vector(HISTORY_SIZE, 0)); + auto tr_pack = tr_pack_o.value_or(std::vector(BLOCK_SIZE * HISTORY_SIZE, 0.f)); + auto rot_pack = rot_pack_o.value_or(std::vector(BLOCK_SIZE * HISTORY_SIZE, 0.f)); + std::vector cov_pack; + if (with_covariance) + cov_pack_o = G->get_attrib_by_name(edge); - auto [it, new_el] = e.attrs().insert_or_assign("rt_rotation_euler_xyz", mvreg ()); - it->second.write(std::move(rot)); - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_translation", mvreg ()); - it->second.write(std::move(tr)); - if (covariance_attr.has_value()) - { - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_covariance", mvreg ()); - it->second.write(std::move(covariance_attr.value())); - } - if (update_index) { - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_head_index", mvreg ()); - it->second.write(std::move(head_index)); - } - std::tie(it, new_el) = e.attrs().insert_or_assign("rt_timestamps", mvreg ()); - it->second.write(std::move(timestamps)); - } + if (time_stamps.size() < HISTORY_SIZE) time_stamps.resize(HISTORY_SIZE); + if (tr_pack.size() < BLOCK_SIZE * HISTORY_SIZE) tr_pack.resize(BLOCK_SIZE * HISTORY_SIZE); + if (rot_pack.size() < BLOCK_SIZE * HISTORY_SIZE) rot_pack.resize(BLOCK_SIZE * HISTORY_SIZE); + if (with_covariance) + { + cov_pack = cov_pack_o.value_or(std::vector(RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE, 0.f)); + if (cov_pack.size() < RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE) + cov_pack.resize(RT_COVARIANCE_BLOCK_SIZE * HISTORY_SIZE); + } - const auto ensure_mutable_to_n = [&]() -> CRDTNode& { - if (!to_n_mut.has_value()) to_n_mut = *to_n; - return to_n_mut.value(); - }; + bool update_index = true; + int timestamp_index = 0; + if (head_o.has_value()) + timestamp_index = static_cast(head_o.value_or(0) / BLOCK_SIZE) % HISTORY_SIZE; + const int index = timestamp_index * BLOCK_SIZE; + const auto timestamp_v = timestamp.has_value() ? *timestamp : static_cast( + std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count()); - if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) - { - if (x.value() != n.id()) - { - no_send = !G->modify_attrib_local(ensure_mutable_to_n(), n.id()); - } - } - else + if (timestamp_v < time_stamps[prev(timestamp_index, HISTORY_SIZE)]) + { + std::vector diffs; + std::transform(time_stamps.begin(), time_stamps.end(), std::back_inserter(diffs), + [timestamp_v](auto val) { + return ((int64_t)timestamp_v - (int64_t)val > 0) + ? ((int64_t)timestamp_v - (int64_t)val) + : std::numeric_limits::min(); + }); + + const auto pos = static_cast(std::min_element(diffs.begin(), diffs.end()) - diffs.begin()) % HISTORY_SIZE; + + if (pos == timestamp_index && timestamp_v < time_stamps[pos]) return; + if (pos >= timestamp_index) update_index = false; + + time_stamps.erase(time_stamps.begin() + timestamp_index); + tr_pack.erase(tr_pack.begin() + index, tr_pack.begin() + index + BLOCK_SIZE); + rot_pack.erase(rot_pack.begin() + index, rot_pack.begin() + index + BLOCK_SIZE); + if (with_covariance) { - no_send = !G->add_attrib_local(ensure_mutable_to_n(), n.id()); + const auto covariance_index = timestamp_index * RT_COVARIANCE_BLOCK_SIZE; + cov_pack.erase(cov_pack.begin() + covariance_index, cov_pack.begin() + covariance_index + RT_COVARIANCE_BLOCK_SIZE); } - if (auto x = G->get_crdt_attrib_by_name(*to_n); x.has_value()) - { - if (x.value() != G->get_node_level(n).value() + 1) - { - no_send = !G->modify_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); - } - } - else - { - no_send = !G->add_attrib_local(ensure_mutable_to_n(), G->get_node_level(n).value() + 1 ); - } + const auto insert_index = pos * BLOCK_SIZE; + tr_pack.insert(tr_pack.begin() + insert_index, trans[0]); + tr_pack.insert(tr_pack.begin() + insert_index + 1, trans[1]); + tr_pack.insert(tr_pack.begin() + insert_index + 2, trans[2]); + rot_pack.insert(rot_pack.begin() + insert_index, rot_euler[0]); + rot_pack.insert(rot_pack.begin() + insert_index + 1, rot_euler[1]); + rot_pack.insert(rot_pack.begin() + insert_index + 2, rot_euler[2]); + if (with_covariance) + cov_pack.insert(cov_pack.begin() + pos * RT_COVARIANCE_BLOCK_SIZE, covariance->begin(), covariance->end()); + time_stamps.insert(time_stamps.begin() + pos, timestamp_v); + } + else + { + tr_pack[index] = trans[0]; + tr_pack[index + 1] = trans[1]; + tr_pack[index + 2] = trans[2]; + rot_pack[index] = rot_euler[0]; + rot_pack[index + 1] = rot_euler[1]; + rot_pack[index + 2] = rot_euler[2]; + if (with_covariance) + std::copy(covariance->begin(), covariance->end(), cov_pack.begin() + timestamp_index * RT_COVARIANCE_BLOCK_SIZE); + time_stamps[timestamp_index] = timestamp_v; + } - //Check if RT edge exist. - if (!n.fano().contains({to, "RT"})) - { - //Create -> insert edge, update to-node attrs - std::tie(r1, node1_insert, std::ignore) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); + G->add_or_modify_attrib_local(edge, std::move(rot_pack)); + G->add_or_modify_attrib_local(edge, std::move(tr_pack)); + if (with_covariance) + G->add_or_modify_attrib_local(edge, std::move(cov_pack)); + if (update_index) + G->add_or_modify_attrib_local(edge, index + BLOCK_SIZE); + G->add_or_modify_attrib_local(edge, std::move(time_stamps)); + } - } - else - { - //Update -> update edge attrs, update to-node attrs - std::tie(r1, std::ignore, node1_update) = G->crdt_engine().insert_or_assign_edge_raw(std::move(e), n.id(), to); - if (!no_send) std::tie(r2, node2) = G->crdt_engine().update_node_raw(std::move(to_n_mut.value())); + auto to_n = G->get_node(to); + if (!to_n.has_value()) + throw std::runtime_error( + "Destination node " + std::to_string(to) + " not found in G in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - if (!r1) - { - throw std::runtime_error( - "Could not insert Node " + std::to_string(n.id()) + " in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - if (!r2 and !no_send) - { - throw std::runtime_error( - "Could not insert Node " + std::to_string(to_n_id.value()) + " in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - } else - throw std::runtime_error( - "Destination node " + std::to_string(to) + " not found in G in insert_or_assign_edge_RT() " + - __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); - } - if (!G->copy) + bool node_changed = false; + if (auto x = G->get_attrib_by_name(*to_n); !x.has_value() || x.value() != n.id()) { - std::vector updated_attributes{"rt_rotation_euler_xyz", "rt_translation"}; - if (with_covariance) - updated_attributes.emplace_back("rt_covariance"); - - if (node1_insert.has_value()) - { - G->dsrpub_edge.write(node1_insert.value()); - } - if (node1_update.has_value()) G->dsrpub_edge_attrs.write(node1_update.value()); + G->add_or_modify_attrib_local(*to_n, n.id()); + node_changed = true; + } - if (!no_send and node2.has_value()) G->dsrpub_node_attrs.write(node2.value()); + const auto n_level = G->get_node_level(n); + if (!n_level.has_value()) + throw std::runtime_error( + "Source node " + std::to_string(n.id()) + " has no level in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); + const auto next_level = n_level.value() + 1; + if (auto x = G->get_attrib_by_name(*to_n); !x.has_value() || x.value() != next_level) + { + G->add_or_modify_attrib_local(*to_n, next_level); + node_changed = true; + } - G->emitter.update_edge_attr_signal(n.id(), to, "RT", updated_attributes, SignalInfo{ G->agent_id }); - G->emitter.update_edge_signal(n.id(), to, "RT", SignalInfo{ G->agent_id }); - if (!no_send) - { - G->emitter.update_node_signal(to_n_id.value(), to_n_type.value(), SignalInfo{ G->agent_id }); - G->emitter.update_node_attr_signal(to_n_id.value(), {"level", "parent"}, SignalInfo{ G->agent_id }); - } + if (node_changed && !G->update_node(*to_n)) + { + throw std::runtime_error( + "Could not update destination node " + std::to_string(to) + " in insert_or_assign_edge_RT() " + + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); } + + if (!G->insert_or_assign_edge(std::move(edge))) + throw std::runtime_error( + "Could not insert RT edge " + std::to_string(n.id()) + " -> " + std::to_string(to) + + " in insert_or_assign_edge_RT() " + __FILE__ + " " + __FUNCTION__ + " " + std::to_string(__LINE__)); } diff --git a/tests/graph/inner_gaussian.cpp b/tests/graph/inner_gaussian.cpp index 96deac8e..8a5477b0 100644 --- a/tests/graph/inner_gaussian.cpp +++ b/tests/graph/inner_gaussian.cpp @@ -410,8 +410,9 @@ TEST_CASE("InnerGaussian point transform matches Monte Carlo covariance", "[GRAP CHECK(empirical_mean_delta.norm() < 0.15); + constexpr double covariance_tolerance = 0.025; for (int diagonal = 0; diagonal < 3; ++diagonal) - CHECK(std::abs(empirical_covariance(diagonal, diagonal) - analytical->covariance(diagonal, diagonal)) < 0.02); + CHECK(std::abs(empirical_covariance(diagonal, diagonal) - analytical->covariance(diagonal, diagonal)) < covariance_tolerance); } TEST_CASE("InnerGaussian pose2d transform matches Monte Carlo covariance", "[GRAPH][RT][GAUSSIAN][MONTE_CARLO]") @@ -491,4 +492,4 @@ TEST_CASE("InnerGaussian pose2d transform matches Monte Carlo covariance", "[GRA for (int diagonal = 0; diagonal < 3; ++diagonal) CHECK(std::abs(empirical_covariance(diagonal, diagonal) - analytical->covariance(diagonal, diagonal)) < 0.02); -} \ No newline at end of file +} diff --git a/tests/graph/rt_timestamp.cpp b/tests/graph/rt_timestamp.cpp index bad5b774..30219f70 100644 --- a/tests/graph/rt_timestamp.cpp +++ b/tests/graph/rt_timestamp.cpp @@ -192,7 +192,7 @@ TEST_CASE("RT api interpolation mode", "[GRAPH][RT]") { REQUIRE(interpolated_rt.has_value()); CHECK(std::abs(interpolated_rt->matrix()(0, 3) - 5.0) < 1e-9); - const auto rotated_x = interpolated_rt->rotation() * Eigen::Vector3d::UnitX(); + const Eigen::Vector3d rotated_x = interpolated_rt->rotation() * Eigen::Vector3d::UnitX(); CHECK(std::abs(rotated_x.x() - std::sqrt(0.5)) < 1e-7); CHECK(std::abs(rotated_x.y() - std::sqrt(0.5)) < 1e-7); } From c31233c49a13d9d7101e53b77665d1d39553db1d Mon Sep 17 00:00:00 2001 From: JuanCarlosgg Date: Sat, 23 May 2026 18:36:07 +0200 Subject: [PATCH 38/38] fix core link dependencies for CI --- core/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 222233b2..a72d66ca 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -52,7 +52,7 @@ target_sources(dsr_core target_link_libraries(dsr_core PRIVATE - Qt6::Core fastcdr fastdds osgDB OpenThreads Eigen3::Eigen + Qt6::Core fastcdr fastdds Eigen3::Eigen cortex_profiling)