From b7739f924b74a8f7e9e67db852d92856341fb21f Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Thu, 11 Jul 2024 12:00:33 +0200 Subject: [PATCH 1/8] [DSR] fix breaking changes for FastDDS 3.0 --- api/GHistorySaver.cpp | 2 +- api/dsr_api.cpp | 26 +- api/include/dsr/api/dsr_api.h | 10 +- api/include/dsr/api/dsr_camera_api.h | 4 +- api/include/dsr/api/dsr_exceptions.h | 3 +- api/include/dsr/api/dsr_inner_eigen_api.h | 7 +- api/include/dsr/api/dsr_rt_api.h | 2 +- api/include/dsr/api/dsr_utils.h | 4 +- core/CMakeLists.txt | 8 +- core/include/dsr/core/crdt/delta_crdt.h | 13 +- core/include/dsr/core/rtps/dsrparticipant.h | 22 +- core/include/dsr/core/rtps/dsrpublisher.h | 10 +- core/include/dsr/core/rtps/dsrsubscriber.h | 2 +- core/include/dsr/core/topics/IDLGraph.h | 3107 --------- core/include/dsr/core/topics/IDLGraph.hpp | 5573 +++++++++++++++++ .../dsr/core/topics/IDLGraphCdrAux.hpp | 36 +- ...hPubSubTypes.h => IDLGraphPubSubTypes.hpp} | 441 +- core/include/dsr/core/types/common_types.h | 7 +- core/include/dsr/core/types/crdt_types.h | 5 +- core/rtps/dsrparticipant.cpp | 77 +- core/rtps/dsrpublisher.cpp | 26 +- core/rtps/dsrsubscriber.cpp | 14 +- core/topics/IDLGraph.cxx | 4539 -------------- core/topics/IDLGraphCdrAux.ipp | 489 +- core/topics/IDLGraphPubSubTypes.cxx | 1328 +++- 25 files changed, 7275 insertions(+), 8480 deletions(-) delete mode 100644 core/include/dsr/core/topics/IDLGraph.h create mode 100644 core/include/dsr/core/topics/IDLGraph.hpp rename core/include/dsr/core/topics/{IDLGraphPubSubTypes.h => IDLGraphPubSubTypes.hpp} (74%) delete mode 100644 core/topics/IDLGraph.cxx diff --git a/api/GHistorySaver.cpp b/api/GHistorySaver.cpp index 78b777eb..173bd840 100644 --- a/api/GHistorySaver.cpp +++ b/api/GHistorySaver.cpp @@ -832,4 +832,4 @@ void GSerializer::add_change(ChangeInfo && c) total_size+=ser.size; used_size+=ser.p; -} \ No newline at end of file +} diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index be76b97e..942d4d07 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -10,8 +10,8 @@ #include #include -#include -#include +#include +#include #include @@ -41,16 +41,16 @@ DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_f // RTPS Create participant auto[suc, participant_handle] = dsrparticipant.init(agent_id, agent_name, all_same_host, ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph, - eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&& info) + eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info) { - if (info.status == eprosima::fastrtps::rtps::ParticipantDiscoveryInfo::DISCOVERED_PARTICIPANT) + if (info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::DISCOVERED_PARTICIPANT) { std::unique_lock lck(participant_set_mutex); std::cout << "Participant matched [" <participant_set.insert({info.info.m_participantName.to_string(), false}); } - else if (info.status == eprosima::fastrtps::rtps::ParticipantDiscoveryInfo::REMOVED_PARTICIPANT || - info.status == eprosima::fastrtps::rtps::ParticipantDiscoveryInfo::DROPPED_PARTICIPANT) + else if (info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::REMOVED_PARTICIPANT || + info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::DROPPED_PARTICIPANT) { std::unique_lock lck(participant_set_mutex); graph->participant_set.erase(info.info.m_participantName.to_string()); @@ -1532,7 +1532,7 @@ void DSRGraph::node_subscription_thread(bool showReceived) { eprosima::fastdds::dds::SampleInfo m_info; IDL::MvregNode sample; - if (reader->take_next_sample(&sample, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&sample, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { if (sample.agent_id() != agent_id) { if (showReceived) { @@ -1565,7 +1565,7 @@ void DSRGraph::edge_subscription_thread(bool showReceived) { eprosima::fastdds::dds::SampleInfo m_info; IDL::MvregEdge sample; - if (reader->take_next_sample(&sample, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&sample, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { if (sample.agent_id() != agent_id) { if (showReceived) { @@ -1599,7 +1599,7 @@ void DSRGraph::edge_attrs_subscription_thread(bool showReceived) { eprosima::fastdds::dds::SampleInfo m_info; IDL::MvregEdgeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&samples, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { if (showReceived) { qDebug() << name << " Received:" << samples.vec().size() << " edge attr from: " @@ -1666,7 +1666,7 @@ void DSRGraph::node_attrs_subscription_thread(bool showReceived) { eprosima::fastdds::dds::SampleInfo m_info; IDL::MvregNodeAttrVec samples; - if (reader->take_next_sample(&samples, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&samples, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { if (showReceived) { qDebug() << name << " Received:" << samples.vec().size() << " node attrs from: " @@ -1730,7 +1730,7 @@ void DSRGraph::fullgraph_server_thread() { eprosima::fastdds::dds::SampleInfo m_info; IDL::GraphRequest sample; - if (reader->take_next_sample(&sample, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&sample, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { { std::unique_lock lck(participant_set_mutex); @@ -1785,7 +1785,7 @@ std::pair DSRGraph::fullgraph_request_thread() { eprosima::fastdds::dds::SampleInfo m_info; IDL::OrMap sample; - if (reader->take_next_sample(&sample, &m_info) == ReturnCode_t::RETCODE_OK) { + if (reader->take_next_sample(&sample, &m_info) == 0) { if (m_info.instance_state == eprosima::fastdds::dds::ALIVE_INSTANCE_STATE) { if (sample.id() != graph->get_agent_id()) { if (sample.id() != static_cast(-1)) { @@ -1870,4 +1870,4 @@ std::unique_ptr DSRGraph::G_copy() bool DSRGraph::is_copy() const { return copy; -} \ No newline at end of file +} diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 870ee4b4..7508671b 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -25,7 +25,7 @@ #include "dsr/core/rtps/dsrparticipant.h" #include "dsr/core/rtps/dsrpublisher.h" #include "dsr/core/rtps/dsrsubscriber.h" -#include "dsr/core/topics/IDLGraphPubSubTypes.h" +#include "dsr/core/topics/IDLGraphPubSubTypes.hpp" #include "dsr/core/types/crdt_types.h" #include "dsr/core/types/user_types.h" #include "dsr/core/types/translator.h" @@ -631,17 +631,17 @@ namespace DSR class ParticipantChangeFunctor { public: DSRGraph *graph{}; - std::function f; + std::function f; ParticipantChangeFunctor(DSRGraph *graph_, - std::function f_) + std::function f_) : graph(graph_), f(std::move(f_)) {} ParticipantChangeFunctor() = default; - void operator()(eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&& info) const + void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info) const { - f(graph, std::forward(info)); + f(graph, std::forward(info)); }; }; diff --git a/api/include/dsr/api/dsr_camera_api.h b/api/include/dsr/api/dsr_camera_api.h index 434d4ee8..50152023 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 @@ -68,4 +68,4 @@ namespace DSR }; } -#endif \ No newline at end of file +#endif diff --git a/api/include/dsr/api/dsr_exceptions.h b/api/include/dsr/api/dsr_exceptions.h index acd452fd..763be0dc 100644 --- a/api/include/dsr/api/dsr_exceptions.h +++ b/api/include/dsr/api/dsr_exceptions.h @@ -7,6 +7,7 @@ #define DSR_EXCEPTIONS #include +#include #include ///////////////////////////////////////////////////////////////// @@ -27,4 +28,4 @@ namespace DSR std::string msg_; }; } -#endif \ No newline at end of file +#endif diff --git a/api/include/dsr/api/dsr_inner_eigen_api.h b/api/include/dsr/api/dsr_inner_eigen_api.h index 509884fb..0a8b3220 100644 --- a/api/include/dsr/api/dsr_inner_eigen_api.h +++ b/api/include/dsr/api/dsr_inner_eigen_api.h @@ -2,10 +2,13 @@ #define INNER_EIGEN_API #include -#include +#include #include #include #include +#include +#include +#include namespace DSR { @@ -52,4 +55,4 @@ namespace DSR }; } -#endif \ No newline at end of file +#endif diff --git a/api/include/dsr/api/dsr_rt_api.h b/api/include/dsr/api/dsr_rt_api.h index 5ef2458f..efbae377 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 207a1b0b..77eacaa4 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 @@ -37,4 +37,4 @@ namespace DSR }; } -#endif \ No newline at end of file +#endif diff --git a/core/CMakeLists.txt b/core/CMakeLists.txt index 07f07e3f..94389c46 100644 --- a/core/CMakeLists.txt +++ b/core/CMakeLists.txt @@ -33,10 +33,10 @@ target_sources(dsr_core include/dsr/core/rtps/dsrsubscriber.h topics/IDLGraphPubSubTypes.cxx - topics/IDLGraph.cxx + #topics/IDLGraph.cxx topics/IDLGraphCdrAux.ipp - include/dsr/core/topics/IDLGraph.h - include/dsr/core/topics/IDLGraphPubSubTypes.h + include/dsr/core/topics/IDLGraph.hpp + include/dsr/core/topics/IDLGraphPubSubTypes.hpp include/dsr/core/topics/IDLGraphCdrAux.hpp include/dsr/core/crdt/delta_crdt.h @@ -51,7 +51,7 @@ target_sources(dsr_core target_link_libraries(dsr_core PRIVATE - Qt6::Core fastcdr fastrtps osgDB OpenThreads Eigen3::Eigen) + Qt6::Core fastcdr fastdds osgDB OpenThreads Eigen3::Eigen) 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 5503c456..2101647a 100644 --- a/core/include/dsr/core/crdt/delta_crdt.h +++ b/core/include/dsr/core/crdt/delta_crdt.h @@ -5,16 +5,11 @@ Reimplementation from https://github.com/CBaquero/delta-enabled-crdts #ifndef DELTA_CRDT #define DELTA_CRDT -#include -#include -#include -#include -#include -#include -#include #include -#include #include +#include +#include +#include using key_type = uint64_t; @@ -468,4 +463,4 @@ class mvreg // Multi-value register, Optimized }; -#endif \ No newline at end of file +#endif diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index 4d658857..82bf57ae 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -1,15 +1,14 @@ #ifndef _PARTICIPANT_H_ #define _PARTICIPANT_H_ -#include -#include -#include +#include +#include #include #include #include #include -#include +#include #include #include @@ -18,8 +17,8 @@ class DSRParticipant public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn); - [[nodiscard]] const eprosima::fastrtps::rtps::GUID_t& getID() const; + [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn); + [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; [[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->getName();} [[nodiscard]] const char *getRequestTopicName() const { return graphrequestType->getName();} [[nodiscard]] const char *getAnswerTopicName() const { return graphRequestAnswerType->getName();} @@ -67,23 +66,24 @@ class DSRParticipant class ParticpantListener : public eprosima::fastdds::dds::DomainParticipantListener { public: - explicit ParticpantListener(std::function&& fn) + explicit ParticpantListener(std::function&& fn) : eprosima::fastdds::dds::DomainParticipantListener(), f(std::move(fn)){}; ~ParticpantListener() override = default; void on_participant_discovery ( eprosima::fastdds::dds::DomainParticipant* participant, - eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&& info) override + eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info, + bool& should_be_ignored) override { //Callback - f(std::forward(info)); + f(std::forward(info)); } - std::function f; + std::function f; //int n_matched; }; std::unique_ptr m_listener; }; -#endif // _Participant_H_ \ No newline at end of file +#endif // _Participant_H_ diff --git a/core/include/dsr/core/rtps/dsrpublisher.h b/core/include/dsr/core/rtps/dsrpublisher.h index fea6d347..e542e6b0 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -4,15 +4,15 @@ #include #include -#include +#include #include #include #include #include #include -#include +#include -#include "../topics/IDLGraphPubSubTypes.h" +#include class DSRPublisher { @@ -20,7 +20,7 @@ class DSRPublisher DSRPublisher(); virtual ~DSRPublisher(); [[nodiscard]] std::tuple init(eprosima::fastdds::dds::DomainParticipant *mp_participant_, eprosima::fastdds::dds::Topic *topic, bool isStreamData = false); - [[nodiscard]] eprosima::fastrtps::rtps::GUID_t getParticipantID() const; + [[nodiscard]] eprosima::fastdds::rtps::GUID_t getParticipantID() const; bool write(IDL::GraphRequest *object); bool write(IDL::MvregNode *object); bool write(IDL::OrMap *object); @@ -45,4 +45,4 @@ class DSRPublisher }; -#endif // _PUBLISHER_H_ \ No newline at end of file +#endif // _PUBLISHER_H_ diff --git a/core/include/dsr/core/rtps/dsrsubscriber.h b/core/include/dsr/core/rtps/dsrsubscriber.h index 0803f571..fc7dc255 100644 --- a/core/include/dsr/core/rtps/dsrsubscriber.h +++ b/core/include/dsr/core/rtps/dsrsubscriber.h @@ -46,4 +46,4 @@ class DSRSubscriber }; -#endif // _SUBSCRIBER_H_ \ No newline at end of file +#endif // _SUBSCRIBER_H_ diff --git a/core/include/dsr/core/topics/IDLGraph.h b/core/include/dsr/core/topics/IDLGraph.h deleted file mode 100644 index c73702bf..00000000 --- a/core/include/dsr/core/topics/IDLGraph.h +++ /dev/null @@ -1,3107 +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.h - * 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_H_ -#define _FAST_DDS_GENERATED_IDLGRAPH_H_ - -#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 eprosima { -namespace fastcdr { -class Cdr; -class CdrSizeCalculator; -} // namespace fastcdr -} // namespace eprosima - -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(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val( - const Val& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val( - Val&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val& operator =( - const Val& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object Val that will be copied. - */ - eProsima_user_DllExport Val& operator =( - Val&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x Val object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Val& x) const; - - /*! - * @brief Comparison operator. - * @param x Val object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Val& x) const; - - /*! - * @brief This function sets the discriminator value. - * @param __d New value for the discriminator. - * @exception eprosima::fastcdr::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); - - /*! - * @brief This function returns the value of the discriminator. - * @return Value of the discriminator - */ - eProsima_user_DllExport int32_t _d() const; - - /*! - * @brief This function returns a reference to the discriminator. - * @return Reference to the discriminator. - */ - eProsima_user_DllExport int32_t& _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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member str - * @return Constant reference to member str - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::string& str() const; - - /*! - * @brief This function returns a reference to member str - * @return Reference to member str - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @brief This function returns the value of member dec - * @return Value of member dec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport int32_t dec() const; - - /*! - * @brief This function returns a reference to member dec - * @return Reference to member dec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport int32_t& dec(); - - - /*! - * @brief This function sets a value in member fl - * @param _fl New value for member fl - */ - eProsima_user_DllExport void fl( - float _fl); - - /*! - * @brief This function returns the value of member fl - * @return Value of member fl - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport float fl() const; - - /*! - * @brief This function returns a reference to member fl - * @return Reference to member fl - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport float& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member float_vec - * @return Constant reference to member float_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& float_vec() const; - - /*! - * @brief This function returns a reference to member float_vec - * @return Reference to member float_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& 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); - - /*! - * @brief This function returns the value of member bl - * @return Value of member bl - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport bool bl() const; - - /*! - * @brief This function returns a reference to member bl - * @return Reference to member bl - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport bool& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member byte_vec - * @return Constant reference to member byte_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& byte_vec() const; - - /*! - * @brief This function returns a reference to member byte_vec - * @return Reference to member byte_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& 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); - - /*! - * @brief This function returns the value of member uint - * @return Value of member uint - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint32_t uint() const; - - /*! - * @brief This function returns a reference to member uint - * @return Reference to member uint - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member u64 - * @return Value of member u64 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint64_t u64() const; - - /*! - * @brief This function returns a reference to member u64 - * @return Reference to member u64 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport uint64_t& u64(); - - - /*! - * @brief This function sets a value in member dob - * @param _dob New value for member dob - */ - eProsima_user_DllExport void dob( - double _dob); - - /*! - * @brief This function returns the value of member dob - * @return Value of member dob - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport double dob() const; - - /*! - * @brief This function returns a reference to member dob - * @return Reference to member dob - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport double& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member uint64_vec - * @return Constant reference to member uint64_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::vector& uint64_vec() const; - - /*! - * @brief This function returns a reference to member uint64_vec - * @return Reference to member uint64_vec - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::vector& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec_float2 - * @return Constant reference to member vec_float2 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float2() const; - - /*! - * @brief This function returns a reference to member vec_float2 - * @return Reference to member vec_float2 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec_float3 - * @return Constant reference to member vec_float3 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float3() const; - - /*! - * @brief This function returns a reference to member vec_float3 - * @return Reference to member vec_float3 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec_float4 - * @return Constant reference to member vec_float4 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float4() const; - - /*! - * @brief This function returns a reference to member vec_float4 - * @return Reference to member vec_float4 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec_float6 - * @return Constant reference to member vec_float6 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport const std::array& vec_float6() const; - - /*! - * @brief This function returns a reference to member vec_float6 - * @return Reference to member vec_float6 - * @exception eprosima::fastcdr::BadParamException This exception is thrown if the requested union member is not the current selection. - */ - eProsima_user_DllExport std::array& vec_float6(); - -private: - - int32_t m__d; - - std::string m_str; - int32_t m_dec{0}; - float m_fl{0.0}; - std::vector m_float_vec; - bool m_bl{false}; - std::vector m_byte_vec; - uint32_t m_uint{0}; - uint64_t m_u64{0}; - double m_dob{0.0}; - std::vector m_uint64_vec; - std::array m_vec_float2{0.0}; - std::array m_vec_float3{0.0}; - std::array m_vec_float4{0.0}; - std::array m_vec_float6{0.0}; -}; -/*! - * @brief This class represents the enumeration Types defined by the user in the IDL file. - * @ingroup IDLGraph - */ -enum Types : uint32_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); - - /*! - * @brief Move constructor. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib( - Attrib&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib& operator =( - const Attrib& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object Attrib that will be copied. - */ - eProsima_user_DllExport Attrib& operator =( - Attrib&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x Attrib object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Attrib& x) const; - - /*! - * @brief Comparison operator. - * @param x Attrib object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Attrib& x) const; - - /*! - * @brief This function sets a value in member type - * @param _type New value for member type - */ - eProsima_user_DllExport void type( - uint32_t _type); - - /*! - * @brief This function returns the value of member type - * @return Value of member type - */ - eProsima_user_DllExport uint32_t type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member value - * @return Constant reference to member value - */ - eProsima_user_DllExport const Val& value() const; - - /*! - * @brief This function returns a reference to member value - * @return Reference to member value - */ - eProsima_user_DllExport Val& 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); - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const; - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt( - PairInt&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt& operator =( - const PairInt& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object PairInt that will be copied. - */ - eProsima_user_DllExport PairInt& operator =( - PairInt&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x PairInt object to compare. - */ - eProsima_user_DllExport bool operator ==( - const PairInt& x) const; - - /*! - * @brief Comparison operator. - * @param x PairInt object to compare. - */ - eProsima_user_DllExport bool operator !=( - const PairInt& x) const; - - 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); - - /*! - * @brief This function returns the value of member first - * @return Value of member first - */ - eProsima_user_DllExport uint64_t first() const; - - /*! - * @brief This function returns a reference to member first - * @return Reference to member first - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member second - * @return Value of member second - */ - eProsima_user_DllExport int32_t second() const; - - /*! - * @brief This function returns a reference to member second - * @return Reference to member second - */ - eProsima_user_DllExport int32_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext( - DotContext&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext& operator =( - const DotContext& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object DotContext that will be copied. - */ - eProsima_user_DllExport DotContext& operator =( - DotContext&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x DotContext object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotContext& x) const; - - /*! - * @brief Comparison operator. - * @param x DotContext object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotContext& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member cc - * @return Constant reference to member cc - */ - eProsima_user_DllExport const std::map& cc() const; - - /*! - * @brief This function returns a reference to member cc - * @return Reference to member cc - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member dc - * @return Constant reference to member dc - */ - eProsima_user_DllExport const std::vector& dc() const; - - /*! - * @brief This function returns a reference to member dc - * @return Reference to member dc - */ - eProsima_user_DllExport std::vector& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr( - DotKernelAttr&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr& operator =( - const DotKernelAttr& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernelAttr that will be copied. - */ - eProsima_user_DllExport DotKernelAttr& operator =( - DotKernelAttr&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x DotKernelAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernelAttr& x) const; - - /*! - * @brief Comparison operator. - * @param x DotKernelAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernelAttr& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const; - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const; - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr( - MvregEdgeAttr&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr& operator =( - const MvregEdgeAttr& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdgeAttr that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttr& operator =( - MvregEdgeAttr&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdgeAttr& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdgeAttr& x) const; - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const; - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const; - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @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); - - /*! - * @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; - - /*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelAttr& dk() const; - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelAttr& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const; - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge( - IDLEdge&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge& operator =( - const IDLEdge& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object IDLEdge that will be copied. - */ - eProsima_user_DllExport IDLEdge& operator =( - IDLEdge&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x IDLEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const IDLEdge& x) const; - - /*! - * @brief Comparison operator. - * @param x IDLEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const IDLEdge& x) const; - - /*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ - eProsima_user_DllExport void to( - uint64_t _to); - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const; - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const; - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member attrs - * @return Constant reference to member attrs - */ - eProsima_user_DllExport const std::map& attrs() const; - - /*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey( - EdgeKey&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey& operator =( - const EdgeKey& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object EdgeKey that will be copied. - */ - eProsima_user_DllExport EdgeKey& operator =( - EdgeKey&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x EdgeKey object to compare. - */ - eProsima_user_DllExport bool operator ==( - const EdgeKey& x) const; - - /*! - * @brief Comparison operator. - * @param x EdgeKey object to compare. - */ - eProsima_user_DllExport bool operator !=( - const EdgeKey& x) const; - - 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); - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const; - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr( - MvregNodeAttr&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr& operator =( - const MvregNodeAttr& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNodeAttr that will be copied. - */ - eProsima_user_DllExport MvregNodeAttr& operator =( - MvregNodeAttr&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttr object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNodeAttr& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttr object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNodeAttr& x) const; - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member node - * @return Value of member node - */ - eProsima_user_DllExport uint64_t node() const; - - /*! - * @brief This function returns a reference to member node - * @return Reference to member node - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @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; - - /*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelAttr& dk() const; - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelAttr& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const; - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge( - DotKernelEdge&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge& operator =( - const DotKernelEdge& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernelEdge that will be copied. - */ - eProsima_user_DllExport DotKernelEdge& operator =( - DotKernelEdge&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x DotKernelEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernelEdge& x) const; - - /*! - * @brief Comparison operator. - * @param x DotKernelEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernelEdge& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const; - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const; - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge( - MvregEdge&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge& operator =( - const MvregEdge& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdge that will be copied. - */ - eProsima_user_DllExport MvregEdge& operator =( - MvregEdge&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregEdge object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdge& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregEdge object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdge& x) const; - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member from - * @return Value of member from - */ - eProsima_user_DllExport uint64_t from() const; - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member to - * @return Value of member to - */ - eProsima_user_DllExport uint64_t to() const; - - /*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernelEdge& dk() const; - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernelEdge& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const; - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode( - IDLNode&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode& operator =( - const IDLNode& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object IDLNode that will be copied. - */ - eProsima_user_DllExport IDLNode& operator =( - IDLNode&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x IDLNode object to compare. - */ - eProsima_user_DllExport bool operator ==( - const IDLNode& x) const; - - /*! - * @brief Comparison operator. - * @param x IDLNode object to compare. - */ - eProsima_user_DllExport bool operator !=( - const IDLNode& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member type - * @return Constant reference to member type - */ - eProsima_user_DllExport const std::string& type() const; - - /*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member name - * @return Constant reference to member name - */ - eProsima_user_DllExport const std::string& name() const; - - /*! - * @brief This function returns a reference to member name - * @return Reference to member name - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member attrs - * @return Constant reference to member attrs - */ - eProsima_user_DllExport const std::map& attrs() const; - - /*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member fano - * @return Constant reference to member fano - */ - eProsima_user_DllExport const std::map& fano() const; - - /*! - * @brief This function returns a reference to member fano - * @return Reference to member fano - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest( - GraphRequest&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest& operator =( - const GraphRequest& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object GraphRequest that will be copied. - */ - eProsima_user_DllExport GraphRequest& operator =( - GraphRequest&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x GraphRequest object to compare. - */ - eProsima_user_DllExport bool operator ==( - const GraphRequest& x) const; - - /*! - * @brief Comparison operator. - * @param x GraphRequest object to compare. - */ - eProsima_user_DllExport bool operator !=( - const GraphRequest& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member from - * @return Constant reference to member from - */ - eProsima_user_DllExport const std::string& from() const; - - /*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ - eProsima_user_DllExport std::string& 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); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport int32_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport int32_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel( - DotKernel&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel& operator =( - const DotKernel& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object DotKernel that will be copied. - */ - eProsima_user_DllExport DotKernel& operator =( - DotKernel&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x DotKernel object to compare. - */ - eProsima_user_DllExport bool operator ==( - const DotKernel& x) const; - - /*! - * @brief Comparison operator. - * @param x DotKernel object to compare. - */ - eProsima_user_DllExport bool operator !=( - const DotKernel& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member ds - * @return Constant reference to member ds - */ - eProsima_user_DllExport const std::map& ds() const; - - /*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const; - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode( - MvregNode&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode& operator =( - const MvregNode& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNode that will be copied. - */ - eProsima_user_DllExport MvregNode& operator =( - MvregNode&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregNode object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNode& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregNode object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNode& x) const; - - /*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ - eProsima_user_DllExport void id( - uint64_t _id); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint64_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ - eProsima_user_DllExport const DotKernel& dk() const; - - /*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ - eProsima_user_DllExport DotKernel& 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); - - /*! - * @brief This function returns the value of member agent_id - * @return Value of member agent_id - */ - eProsima_user_DllExport uint32_t agent_id() const; - - /*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ - eProsima_user_DllExport uint64_t timestamp() const; - - /*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ - eProsima_user_DllExport uint64_t& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap( - OrMap&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap& operator =( - const OrMap& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object OrMap that will be copied. - */ - eProsima_user_DllExport OrMap& operator =( - OrMap&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x OrMap object to compare. - */ - eProsima_user_DllExport bool operator ==( - const OrMap& x) const; - - /*! - * @brief Comparison operator. - * @param x OrMap object to compare. - */ - eProsima_user_DllExport bool operator !=( - const OrMap& x) const; - -/*! - * @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); - - /*! - * @brief This function returns the value of member to_id - * @return Value of member to_id - */ - eProsima_user_DllExport uint32_t to_id() const; - - /*! - * @brief This function returns a reference to member to_id - * @return Reference to member to_id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @brief This function returns the value of member id - * @return Value of member id - */ - eProsima_user_DllExport uint32_t id() const; - - /*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ - eProsima_user_DllExport uint32_t& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member m - * @return Constant reference to member m - */ - eProsima_user_DllExport const std::map& m() const; - - /*! - * @brief This function returns a reference to member m - * @return Reference to member m - */ - eProsima_user_DllExport std::map& 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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ - eProsima_user_DllExport const DotContext& cbase() const; - - /*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ - eProsima_user_DllExport DotContext& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec( - MvregEdgeAttrVec&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec& operator =( - const MvregEdgeAttrVec& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregEdgeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregEdgeAttrVec& operator =( - MvregEdgeAttrVec&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregEdgeAttrVec& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregEdgeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregEdgeAttrVec& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec - * @return Constant reference to member vec - */ - eProsima_user_DllExport const std::vector& vec() const; - - /*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ - eProsima_user_DllExport std::vector& 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); - - /*! - * @brief Move constructor. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec( - MvregNodeAttrVec&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec& operator =( - const MvregNodeAttrVec& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object MvregNodeAttrVec that will be copied. - */ - eProsima_user_DllExport MvregNodeAttrVec& operator =( - MvregNodeAttrVec&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator ==( - const MvregNodeAttrVec& x) const; - - /*! - * @brief Comparison operator. - * @param x MvregNodeAttrVec object to compare. - */ - eProsima_user_DllExport bool operator !=( - const MvregNodeAttrVec& x) const; - - /*! - * @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); - - /*! - * @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); - - /*! - * @brief This function returns a constant reference to member vec - * @return Constant reference to member vec - */ - eProsima_user_DllExport const std::vector& vec() const; - - /*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ - eProsima_user_DllExport std::vector& vec(); - -private: - - std::vector m_vec; - -}; - -} - -#endif // _FAST_DDS_GENERATED_IDLGRAPH_H_ - diff --git a/core/include/dsr/core/topics/IDLGraph.hpp b/core/include/dsr/core/topics/IDLGraph.hpp new file mode 100644 index 00000000..c3b65391 --- /dev/null +++ b/core/include/dsr/core/topics/IDLGraph.hpp @@ -0,0 +1,5573 @@ +// 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 (m__d == x.m__d && + selected_member_ == x.selected_member_) + { + switch (selected_member_) + { + case 0x00000001: + ret_value = (m_str == x.m_str); + break; + + case 0x00000002: + ret_value = (m_dec == x.m_dec); + break; + + case 0x00000003: + ret_value = (m_fl == x.m_fl); + break; + + case 0x00000004: + ret_value = (m_float_vec == x.m_float_vec); + break; + + case 0x00000005: + ret_value = (m_bl == x.m_bl); + break; + + case 0x00000006: + ret_value = (m_byte_vec == x.m_byte_vec); + break; + + case 0x00000007: + ret_value = (m_uint == x.m_uint); + break; + + case 0x00000008: + ret_value = (m_u64 == x.m_u64); + break; + + case 0x00000009: + ret_value = (m_dob == x.m_dob); + break; + + case 0x0000000a: + ret_value = (m_uint64_vec == x.m_uint64_vec); + break; + + case 0x0000000b: + ret_value = (m_vec_float2 == x.m_vec_float2); + break; + + case 0x0000000c: + ret_value = (m_vec_float3 == x.m_vec_float3); + break; + + case 0x0000000d: + ret_value = (m_vec_float4 == x.m_vec_float4); + break; + + case 0x0000000e: + ret_value = (m_vec_float6 == x.m_vec_float6); + break; + + } + } + + 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 index de7124bd..f47ead2d 100644 --- a/core/include/dsr/core/topics/IDLGraphCdrAux.hpp +++ b/core/include/dsr/core/topics/IDLGraphCdrAux.hpp @@ -19,61 +19,61 @@ * This file was generated by the tool fastddsgen. */ -#ifndef _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_HPP_ -#define _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_HPP_ +#ifndef FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP +#define FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP -#include "IDLGraph.h" +#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 {3212UL}; +constexpr uint32_t DotContext_max_cdr_typesize {16UL}; constexpr uint32_t DotContext_max_key_cdr_typesize {0UL}; -constexpr uint32_t DotKernelAttr_max_cdr_typesize {88028UL}; +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 {888514736UL}; +constexpr uint32_t MvregEdge_max_cdr_typesize {336UL}; constexpr uint32_t MvregEdge_max_key_cdr_typesize {0UL}; -constexpr uint64_t DotKernel_max_cdr_typesize {8886035980820UL}; +constexpr uint32_t DotKernel_max_cdr_typesize {28UL}; constexpr uint32_t DotKernel_max_key_cdr_typesize {0UL}; -constexpr uint32_t Attrib_max_cdr_typesize {836UL}; +constexpr uint32_t Attrib_max_cdr_typesize {292UL}; constexpr uint32_t Attrib_max_key_cdr_typesize {0UL}; -constexpr uint32_t MvregEdgeAttr_max_cdr_typesize {88592UL}; +constexpr uint32_t MvregEdgeAttr_max_cdr_typesize {592UL}; constexpr uint32_t MvregEdgeAttr_max_key_cdr_typesize {0UL}; -constexpr uint32_t IDLEdge_max_cdr_typesize {8885100UL}; +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 uint64_t IDLNode_max_cdr_typesize {88860359760UL}; +constexpr uint32_t IDLNode_max_cdr_typesize {556UL}; constexpr uint32_t IDLNode_max_key_cdr_typesize {0UL}; -constexpr uint64_t OrMap_max_cdr_typesize {888603598088836UL}; +constexpr uint32_t OrMap_max_cdr_typesize {36UL}; constexpr uint32_t OrMap_max_key_cdr_typesize {0UL}; -constexpr uint32_t MvregNodeAttr_max_cdr_typesize {88328UL}; +constexpr uint32_t MvregNodeAttr_max_cdr_typesize {328UL}; constexpr uint32_t MvregNodeAttr_max_key_cdr_typesize {0UL}; -constexpr uint32_t DotKernelEdge_max_cdr_typesize {888514428UL}; +constexpr uint32_t DotKernelEdge_max_cdr_typesize {28UL}; constexpr uint32_t DotKernelEdge_max_key_cdr_typesize {0UL}; -constexpr uint64_t MvregNode_max_cdr_typesize {8886035980848UL}; +constexpr uint32_t MvregNode_max_cdr_typesize {56UL}; constexpr uint32_t MvregNode_max_key_cdr_typesize {0UL}; -constexpr uint32_t MvregEdgeAttrVec_max_cdr_typesize {8859208UL}; +constexpr uint32_t MvregEdgeAttrVec_max_cdr_typesize {12UL}; constexpr uint32_t MvregEdgeAttrVec_max_key_cdr_typesize {0UL}; -constexpr uint32_t MvregNodeAttrVec_max_cdr_typesize {8832808UL}; +constexpr uint32_t MvregNodeAttrVec_max_cdr_typesize {12UL}; constexpr uint32_t MvregNodeAttrVec_max_key_cdr_typesize {0UL}; @@ -155,5 +155,5 @@ eProsima_user_DllExport void serialize_key( } // namespace fastcdr } // namespace eprosima -#endif // _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_HPP_ +#endif // FAST_DDS_GENERATED__IDLGRAPHCDRAUX_HPP diff --git a/core/include/dsr/core/topics/IDLGraphPubSubTypes.h b/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp similarity index 74% rename from core/include/dsr/core/topics/IDLGraphPubSubTypes.h rename to core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp index 591612c1..56b613a3 100644 --- a/core/include/dsr/core/topics/IDLGraphPubSubTypes.h +++ b/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp @@ -13,23 +13,23 @@ // limitations under the License. /*! - * @file IDLGraphPubSubTypes.h + * @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_H_ -#define _FAST_DDS_GENERATED_IDLGRAPH_PUBSUBTYPES_H_ +#ifndef FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP +#define FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP #include #include -#include -#include -#include +#include +#include +#include -#include "IDLGraph.h" +#include "IDLGraph.hpp" #if !defined(GEN_API_VER) || (GEN_API_VER != 2) @@ -53,34 +53,34 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~AttribPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -88,6 +88,9 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -103,7 +106,7 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -121,7 +124,7 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -141,34 +144,34 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~PairIntPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -176,6 +179,9 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -191,7 +197,7 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -209,7 +215,7 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -229,34 +235,34 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~DotContextPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -264,6 +270,9 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -279,7 +288,7 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -297,7 +306,7 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -317,34 +326,34 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~DotKernelAttrPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -352,6 +361,9 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -367,7 +379,7 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -385,7 +397,7 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -405,34 +417,34 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregEdgeAttrPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -440,6 +452,9 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -455,7 +470,7 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -473,7 +488,7 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -493,34 +508,34 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~IDLEdgePubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -528,6 +543,9 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -543,7 +561,7 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -561,7 +579,7 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -581,34 +599,34 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~EdgeKeyPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -616,6 +634,9 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -631,7 +652,7 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -649,7 +670,7 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -669,34 +690,34 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregNodeAttrPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -704,6 +725,9 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -719,7 +743,7 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -737,7 +761,7 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -757,34 +781,34 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~DotKernelEdgePubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -792,6 +816,9 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -807,7 +834,7 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -825,7 +852,7 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -845,34 +872,34 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregEdgePubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -880,6 +907,9 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -895,7 +925,7 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -913,7 +943,7 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -933,34 +963,34 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~IDLNodePubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -968,6 +998,9 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -983,7 +1016,7 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1001,7 +1034,7 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1021,34 +1054,34 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~GraphRequestPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1056,6 +1089,9 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1071,7 +1107,7 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1089,7 +1125,7 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1109,34 +1145,34 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~DotKernelPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1144,6 +1180,9 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1159,7 +1198,7 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1177,7 +1216,7 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1197,34 +1236,34 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregNodePubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1232,6 +1271,9 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1247,7 +1289,7 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1265,7 +1307,7 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1285,34 +1327,34 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~OrMapPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1320,6 +1362,9 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1335,7 +1380,7 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1353,7 +1398,7 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1373,34 +1418,34 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregEdgeAttrVecPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1408,6 +1453,9 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1423,7 +1471,7 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1441,7 +1489,7 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; @@ -1461,34 +1509,34 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport ~MvregNodeAttrVecPubSubType() override; eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload) override { return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport bool serialize( - void* data, - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + const void* const data, + eprosima::fastdds::rtps::SerializedPayload_t* payload, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool deserialize( - eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::rtps::SerializedPayload_t* payload, void* data) override; eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data) override + const void* const data) override { return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); } eProsima_user_DllExport std::function getSerializedSizeProvider( - void* data, + const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; eProsima_user_DllExport bool getKey( - void* data, - eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + const void* const data, + eprosima::fastdds::rtps::InstanceHandle_t* ihandle, bool force_md5 = false) override; eProsima_user_DllExport void* createData() override; @@ -1496,6 +1544,9 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport void deleteData( 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 { @@ -1511,7 +1562,7 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType } eProsima_user_DllExport inline bool is_plain( - eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override { static_cast(data_representation); return false; @@ -1529,10 +1580,10 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - MD5 m_md5; + eprosima::fastdds::MD5 m_md5; unsigned char* m_keyBuffer; }; -#endif // _FAST_DDS_GENERATED_IDLGRAPH_PUBSUBTYPES_H_ +#endif // FAST_DDS_GENERATED__IDLGRAPH_PUBSUBTYPES_HPP diff --git a/core/include/dsr/core/types/common_types.h b/core/include/dsr/core/types/common_types.h index 38b4e157..fdaf45dd 100644 --- a/core/include/dsr/core/types/common_types.h +++ b/core/include/dsr/core/types/common_types.h @@ -5,13 +5,12 @@ #ifndef DSR_COMMON_TYPES_H #define DSR_COMMON_TYPES_H -#include "../topics/IDLGraph.h" -#include "../utils.h" +#include "../topics/IDLGraph.hpp" #include -#include -#include #include +#include + namespace DSR { static constexpr std::array TYPENAMES_UNION = diff --git a/core/include/dsr/core/types/crdt_types.h b/core/include/dsr/core/types/crdt_types.h index d69879ac..0542a8f2 100644 --- a/core/include/dsr/core/types/crdt_types.h +++ b/core/include/dsr/core/types/crdt_types.h @@ -7,13 +7,10 @@ #include -#include -#include #include #include "../crdt/delta_crdt.h" -#include "../topics/IDLGraph.h" -#include "../utils.h" +#include "../topics/IDLGraph.hpp" #include "common_types.h" namespace DSR { diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index f383e3de..95bf6dbf 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -1,10 +1,9 @@ #include -#include -#include +#include +#include +#include +#include -#include - -#include #include #include @@ -31,7 +30,7 @@ DSRParticipant::~DSRParticipant() } -std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn) +std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn) { // Create RTPSParticipant DomainParticipantQos PParam; @@ -55,11 +54,11 @@ std::tuple DSRParticipant::ini if (not localhost) { - std::vector ips; - eprosima::fastrtps::rtps::IPFinder::getIPs(&ips, false); + std::vector ips; + eprosima::fastdds::rtps::IPFinder::getIPs(&ips, false); for (auto &ip : ips) { - if (ip.type == eprosima::fastrtps::rtps::IPFinder::IP4 ) { + if (ip.type == eprosima::fastdds::rtps::IPFinder::IP4 ) { //custom_transport->interfaceWhiteList.emplace_back(ip.name); } } @@ -76,14 +75,14 @@ std::tuple DSRParticipant::ini //Discovery PParam.wire_protocol().builtin.discovery_config.ignoreParticipantFlags = - static_cast( - eprosima::fastrtps::rtps::ParticipantFilteringFlags_t::FILTER_SAME_PROCESS); + static_cast( + eprosima::fastdds::rtps::ParticipantFilteringFlags::FILTER_SAME_PROCESS); - PParam.wire_protocol().builtin.discovery_config.leaseDuration = /*eprosima::fastrtps::c_TimeInfinite;*/ Duration_t(6); + PParam.wire_protocol().builtin.discovery_config.leaseDuration = /*eprosima::fastdds::c_TimeInfinite;*/ Duration_t(6); PParam.wire_protocol().builtin.discovery_config.leaseDuration_announcementperiod = - eprosima::fastrtps::Duration_t(3, 0); + eprosima::fastdds::Duration_t(3, 0); - eprosima::fastrtps::Log::SetVerbosity(eprosima::fastdds::dds::Log::Info); + eprosima::fastdds::dds::Log::SetVerbosity(eprosima::fastdds::dds::Log::Info); m_listener = std::make_unique(std::move(fn)); @@ -145,15 +144,15 @@ void DSRParticipant::remove_participant_and_entities() writer->set_listener(nullptr); pub->set_listener(nullptr); - if (auto res = pub->delete_datawriter(writer); res == ReturnCode_t::RETCODE_OK) + if (auto res = pub->delete_datawriter(writer); res == 0) { - if (res = mp_participant->delete_publisher(pub); res != ReturnCode_t::RETCODE_OK) + if (res = mp_participant->delete_publisher(pub); res != 0) { - std::cout << "DELETE PUBLISHER " << topic_name << " RETURNED: " << res() << std::endl; + std::cout << "DELETE PUBLISHER " << topic_name << " RETURNED: " << res << std::endl; } } else { - std::cout << "DELETE DATAWRITER " << topic_name << " RETURNED: " << res() << std::endl; + std::cout << "DELETE DATAWRITER " << topic_name << " RETURNED: " << res << std::endl; } } } @@ -173,15 +172,15 @@ void DSRParticipant::remove_participant_and_entities() reader->set_listener(nullptr); sub->set_listener(nullptr); - if (auto res = sub->delete_datareader(reader); res == ReturnCode_t::RETCODE_OK) + if (auto res = sub->delete_datareader(reader); res == 0) { - if (res = mp_participant->delete_subscriber(sub); res != ReturnCode_t::RETCODE_OK) + if (res = mp_participant->delete_subscriber(sub); res != 0) { - std::cout << "DELETE SUBSCRIBER " << topic_name << " RETURNED: " << res() << std::endl; + std::cout << "DELETE SUBSCRIBER " << topic_name << " RETURNED: " << res << std::endl; } } else { - std::cout << "DELETE DATAREADER " << topic_name << " RETURNED: " << res() << std::endl; + std::cout << "DELETE DATAREADER " << topic_name << " RETURNED: " << res << std::endl; } } } @@ -191,7 +190,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_node) { topic_node->close(); - if(mp_participant->delete_topic(topic_node) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_node) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_node->get_name() << std::endl; } @@ -199,7 +198,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_edge) { topic_edge->close(); - if(mp_participant->delete_topic(topic_edge) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_edge) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_edge->get_name() << std::endl; } @@ -207,7 +206,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_graph) { topic_graph->close(); - if(mp_participant->delete_topic(topic_graph) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_graph) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_graph->get_name() << std::endl; } @@ -215,7 +214,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_graph_request) { topic_graph_request->close(); - if(mp_participant->delete_topic(topic_graph_request) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_graph_request) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_graph_request->get_name() << std::endl; } @@ -223,7 +222,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_node_att) { topic_node_att->close(); - if(mp_participant->delete_topic(topic_node_att) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_node_att) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_node_att->get_name() << std::endl; } @@ -231,7 +230,7 @@ void DSRParticipant::remove_participant_and_entities() if (topic_edge_att) { topic_edge_att->close(); - if(mp_participant->delete_topic(topic_edge_att) == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) + if(mp_participant->delete_topic(topic_edge_att) == RETCODE_PRECONDITION_NOT_MET) { std::cout << " Remove topic error " << topic_edge_att->get_name() << std::endl; } @@ -239,14 +238,14 @@ void DSRParticipant::remove_participant_and_entities() } auto res = eprosima::fastdds::dds::DomainParticipantFactory::get_instance()->delete_participant(mp_participant); - if (res == ReturnCode_t::RETCODE_PRECONDITION_NOT_MET) { + if (res == RETCODE_PRECONDITION_NOT_MET) { std::cout << "Error removing participant. There are entities in use." <guid(); } @@ -276,17 +275,17 @@ void DSRParticipant::delete_subscriber(const std::string& id) reader->set_listener(nullptr); sub->set_listener(nullptr); - if (auto res = sub->delete_datareader(reader); res == ReturnCode_t::RETCODE_OK) + if (auto res = sub->delete_datareader(reader); res == 0) { - if (res = mp_participant->delete_subscriber(sub); res != ReturnCode_t::RETCODE_OK) + if (res = mp_participant->delete_subscriber(sub); res != 0) { - std::cout << "DELETE SUBSCRIBER " << id << " RETURNED: " << res() << std::endl; + std::cout << "DELETE SUBSCRIBER " << id << " RETURNED: " << res << std::endl; } else { subscribers.erase(id); } } else { - std::cout << "DELETE DATAREADER " << id << " RETURNED: " << res() << std::endl; + std::cout << "DELETE DATAREADER " << id << " RETURNED: " << res << std::endl; } } } @@ -310,21 +309,21 @@ void DSRParticipant::delete_publisher(const std::string& id) writer->set_listener(nullptr); pub->set_listener(nullptr); - if (auto res = pub->delete_datawriter(writer); res == ReturnCode_t::RETCODE_OK) + if (auto res = pub->delete_datawriter(writer); res == 0) { - if (res = mp_participant->delete_publisher(pub); res != ReturnCode_t::RETCODE_OK) + if (res = mp_participant->delete_publisher(pub); res != 0) { - std::cout << "DELETE PUBLISHER " << id << " RETURNED: " << res() << std::endl; + std::cout << "DELETE PUBLISHER " << id << " RETURNED: " << res << std::endl; } else { publishers.erase(id); } } else { - std::cout << "DELETE DATAWRITER " << id << " RETURNED: " << res() << std::endl; + std::cout << "DELETE DATAWRITER " << id << " RETURNED: " << res << std::endl; } } } } catch (...) { std::cout << "delete pub error: " << id << std::endl; } -} \ No newline at end of file +} diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index 0c580485..bc2e9bec 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -1,17 +1,19 @@ -#include -#include -#include -#include -#include -#include +#include +//#include +#include +#include +#include +#include +#include #include #include -using namespace eprosima::fastrtps; -using namespace eprosima::fastrtps::rtps; +using namespace eprosima::fastdds; +using namespace eprosima::fastdds::rtps; +using namespace eprosima::fastdds::dds; DSRPublisher::DSRPublisher() : mp_participant(nullptr), mp_publisher(nullptr), mp_writer(nullptr) {} @@ -44,10 +46,10 @@ std::tupleguid(); } @@ -170,7 +172,7 @@ bool DSRPublisher::write(std::vector *object) { void DSRPublisher::PubListener::on_publication_matched(eprosima::fastdds::dds::DataWriter* writer, const eprosima::fastdds::dds::PublicationMatchedStatus& info) { - if (info.current_count == eprosima::fastrtps::rtps::MATCHED_MATCHING) { + if (info.current_count == eprosima::fastdds::rtps::MatchingStatus::MATCHED_MATCHING) { n_matched++; qInfo() << "Subscriber [" << writer->get_topic()->get_name().data() <<"] matched " << info.last_subscription_handle.value;// << " self: " << info.remoteEndpointGuid.is_on_same_process_as(pub->getGuid()); } else { diff --git a/core/rtps/dsrsubscriber.cpp b/core/rtps/dsrsubscriber.cpp index 5842e70b..5ab6eadd 100644 --- a/core/rtps/dsrsubscriber.cpp +++ b/core/rtps/dsrsubscriber.cpp @@ -2,8 +2,9 @@ #include #include #include -#include -#include +#include +#include +#include #include @@ -12,7 +13,6 @@ using namespace eprosima; using namespace eprosima::fastdds; using namespace eprosima::fastdds::rtps; -using namespace eprosima::fastrtps::rtps; DSRSubscriber::DSRSubscriber() : mp_participant(nullptr), mp_subscriber(nullptr), mp_reader(nullptr) {} @@ -53,10 +53,10 @@ std::tupleget_qos().transport().user_transports.end(); if (not local) { - eprosima::fastrtps::rtps::Locator_t locator; + Locator_t locator; locator.port = 7900; locator.kind = LOCATOR_KIND_UDPv4; - eprosima::fastrtps::rtps::IPLocator::setIPv4(locator, "239.255.1.33"); + IPLocator::setIPv4(locator, "239.255.1.33"); dataReaderQos.endpoint().multicast_locator_list.push_back(locator); } @@ -67,7 +67,7 @@ std::tupleget_topicdescription()->get_name().data() <<"] matched " << info.last_publication_handle.value;// << " self: " << info..is_on_same_process_as(sub->getGuid()); diff --git a/core/topics/IDLGraph.cxx b/core/topics/IDLGraph.cxx deleted file mode 100644 index 4314cfe4..00000000 --- a/core/topics/IDLGraph.cxx +++ /dev/null @@ -1,4539 +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.cpp - * This source file contains the implementation of the described types in the IDL file. - * - * This file was generated by the tool fastddsgen. - */ - -#ifdef _WIN32 -// Remove linker warning LNK4221 on Visual Studio -namespace { -char dummy; -} // namespace -#endif // _WIN32 - -#include -#include - - -#include -using namespace eprosima::fastcdr::exception; - -#include - -namespace IDL { - -Val::Val() -{ - m__d = 0; -} - -Val::~Val() -{ -} - -Val::Val( - const Val& x) -{ - m__d = x.m__d; - - switch (m__d) - { - case 0: - m_str = x.m_str; - break; - - - case 1: - m_dec = x.m_dec; - break; - - - case 2: - m_fl = x.m_fl; - break; - - - case 3: - m_float_vec = x.m_float_vec; - break; - - - case 4: - m_bl = x.m_bl; - break; - - - case 5: - m_byte_vec = x.m_byte_vec; - break; - - - case 6: - m_uint = x.m_uint; - break; - - - case 7: - m_u64 = x.m_u64; - break; - - - case 8: - m_dob = x.m_dob; - break; - - - case 9: - m_uint64_vec = x.m_uint64_vec; - break; - - - case 10: - m_vec_float2 = x.m_vec_float2; - break; - - - case 11: - m_vec_float3 = x.m_vec_float3; - break; - - - case 12: - m_vec_float4 = x.m_vec_float4; - break; - - - case 13: - m_vec_float6 = x.m_vec_float6; - break; - - default: - break; - } -} - -Val::Val( - Val&& x) noexcept -{ - m__d = x.m__d; - - switch (m__d) - { - case 0: - m_str = std::move(x.m_str); - - break; - - - case 1: - m_dec = x.m_dec; - break; - - - case 2: - m_fl = x.m_fl; - break; - - - case 3: - m_float_vec = std::move(x.m_float_vec); - - break; - - - case 4: - m_bl = x.m_bl; - break; - - - case 5: - m_byte_vec = std::move(x.m_byte_vec); - - break; - - - case 6: - m_uint = x.m_uint; - break; - - - case 7: - m_u64 = x.m_u64; - break; - - - case 8: - m_dob = x.m_dob; - break; - - - case 9: - m_uint64_vec = std::move(x.m_uint64_vec); - - break; - - - case 10: - m_vec_float2 = std::move(x.m_vec_float2); - - break; - - - case 11: - m_vec_float3 = std::move(x.m_vec_float3); - - break; - - - case 12: - m_vec_float4 = std::move(x.m_vec_float4); - - break; - - - case 13: - m_vec_float6 = std::move(x.m_vec_float6); - - break; - - default: - break; - } -} - -Val& Val::operator =( - const Val& x) -{ - m__d = x.m__d; - - switch (m__d) - { - case 0: - m_str = x.m_str; - break; - - - case 1: - m_dec = x.m_dec; - break; - - - case 2: - m_fl = x.m_fl; - break; - - - case 3: - m_float_vec = x.m_float_vec; - break; - - - case 4: - m_bl = x.m_bl; - break; - - - case 5: - m_byte_vec = x.m_byte_vec; - break; - - - case 6: - m_uint = x.m_uint; - break; - - - case 7: - m_u64 = x.m_u64; - break; - - - case 8: - m_dob = x.m_dob; - break; - - - case 9: - m_uint64_vec = x.m_uint64_vec; - break; - - - case 10: - m_vec_float2 = x.m_vec_float2; - break; - - - case 11: - m_vec_float3 = x.m_vec_float3; - break; - - - case 12: - m_vec_float4 = x.m_vec_float4; - break; - - - case 13: - m_vec_float6 = x.m_vec_float6; - break; - - default: - break; - } - - return *this; -} - -Val& Val::operator =( - Val&& x) noexcept -{ - m__d = x.m__d; - - switch (m__d) - { - case 0: - m_str = std::move(x.m_str); - - break; - - - case 1: - m_dec = x.m_dec; - break; - - - case 2: - m_fl = x.m_fl; - break; - - - case 3: - m_float_vec = std::move(x.m_float_vec); - - break; - - - case 4: - m_bl = x.m_bl; - break; - - - case 5: - m_byte_vec = std::move(x.m_byte_vec); - - break; - - - case 6: - m_uint = x.m_uint; - break; - - - case 7: - m_u64 = x.m_u64; - break; - - - case 8: - m_dob = x.m_dob; - break; - - - case 9: - m_uint64_vec = std::move(x.m_uint64_vec); - - break; - - - case 10: - m_vec_float2 = std::move(x.m_vec_float2); - - break; - - - case 11: - m_vec_float3 = std::move(x.m_vec_float3); - - break; - - - case 12: - m_vec_float4 = std::move(x.m_vec_float4); - - break; - - - case 13: - m_vec_float6 = std::move(x.m_vec_float6); - - break; - - default: - break; - } - - return *this; -} - -bool Val::operator ==( - const Val& x) const -{ - if (m__d != x.m__d) - { - return false; - } - - switch (m__d) - { - case 0: - return (m_str == x.m_str); - break; - - - case 1: - return (m_dec == x.m_dec); - break; - - - case 2: - return (m_fl == x.m_fl); - break; - - - case 3: - return (m_float_vec == x.m_float_vec); - break; - - - case 4: - return (m_bl == x.m_bl); - break; - - - case 5: - return (m_byte_vec == x.m_byte_vec); - break; - - - case 6: - return (m_uint == x.m_uint); - break; - - - case 7: - return (m_u64 == x.m_u64); - break; - - - case 8: - return (m_dob == x.m_dob); - break; - - - case 9: - return (m_uint64_vec == x.m_uint64_vec); - break; - - - case 10: - return (m_vec_float2 == x.m_vec_float2); - break; - - - case 11: - return (m_vec_float3 == x.m_vec_float3); - break; - - - case 12: - return (m_vec_float4 == x.m_vec_float4); - break; - - - case 13: - return (m_vec_float6 == x.m_vec_float6); - break; - - default: - break; - } - return false; -} - -bool Val::operator !=( - const Val& x) const -{ - return !(*this == x); -} - -void Val::_d( - int32_t __d) -{ - bool b = false; - - switch (m__d) - { - case 0: - switch (__d) - { - case 0: - b = true; - break; - default: - break; - } - break; - - - case 1: - switch (__d) - { - case 1: - b = true; - break; - default: - break; - } - break; - - - case 2: - switch (__d) - { - case 2: - b = true; - break; - default: - break; - } - break; - - - case 3: - switch (__d) - { - case 3: - b = true; - break; - default: - break; - } - break; - - - case 4: - switch (__d) - { - case 4: - b = true; - break; - default: - break; - } - break; - - - case 5: - switch (__d) - { - case 5: - b = true; - break; - default: - break; - } - break; - - - case 6: - switch (__d) - { - case 6: - b = true; - break; - default: - break; - } - break; - - - case 7: - switch (__d) - { - case 7: - b = true; - break; - default: - break; - } - break; - - - case 8: - switch (__d) - { - case 8: - b = true; - break; - default: - break; - } - break; - - - case 9: - switch (__d) - { - case 9: - b = true; - break; - default: - break; - } - break; - - - case 10: - switch (__d) - { - case 10: - b = true; - break; - default: - break; - } - break; - - - case 11: - switch (__d) - { - case 11: - b = true; - break; - default: - break; - } - break; - - - case 12: - switch (__d) - { - case 12: - b = true; - break; - default: - break; - } - break; - - - case 13: - switch (__d) - { - case 13: - b = true; - break; - default: - break; - } - break; - - default: - break; - } - - if (!b) - { - throw BadParamException("Discriminator doesn't correspond with the selected union member"); - } - - m__d = __d; -} - -int32_t Val::_d() const -{ - return m__d; -} - -int32_t& Val::_d() -{ - return m__d; -} - -void Val::str( - const std::string& _str) -{ - m_str = _str; - m__d = 0; - -} - -void Val::str( - std::string&& _str) -{ - m_str = std::move(_str); - m__d = 0; - -} - -const std::string& Val::str() const -{ - bool b = false; - - switch (m__d) - { - case 0: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_str; -} - -std::string& Val::str() -{ - bool b = false; - - switch (m__d) - { - case 0: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_str; -} - - -void Val::dec( - int32_t _dec) -{ - m_dec = _dec; - m__d = 1; - -} - -int32_t Val::dec() const -{ - bool b = false; - - switch (m__d) - { - case 1: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_dec; -} - -int32_t& Val::dec() -{ - bool b = false; - - switch (m__d) - { - case 1: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_dec; -} - - -void Val::fl( - float _fl) -{ - m_fl = _fl; - m__d = 2; - -} - -float Val::fl() const -{ - bool b = false; - - switch (m__d) - { - case 2: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_fl; -} - -float& Val::fl() -{ - bool b = false; - - switch (m__d) - { - case 2: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_fl; -} - - -void Val::float_vec( - const std::vector& _float_vec) -{ - m_float_vec = _float_vec; - m__d = 3; - -} - -void Val::float_vec( - std::vector&& _float_vec) -{ - m_float_vec = std::move(_float_vec); - m__d = 3; - -} - -const std::vector& Val::float_vec() const -{ - bool b = false; - - switch (m__d) - { - case 3: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_float_vec; -} - -std::vector& Val::float_vec() -{ - bool b = false; - - switch (m__d) - { - case 3: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_float_vec; -} - - -void Val::bl( - bool _bl) -{ - m_bl = _bl; - m__d = 4; - -} - -bool Val::bl() const -{ - bool b = false; - - switch (m__d) - { - case 4: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_bl; -} - -bool& Val::bl() -{ - bool b = false; - - switch (m__d) - { - case 4: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_bl; -} - - -void Val::byte_vec( - const std::vector& _byte_vec) -{ - m_byte_vec = _byte_vec; - m__d = 5; - -} - -void Val::byte_vec( - std::vector&& _byte_vec) -{ - m_byte_vec = std::move(_byte_vec); - m__d = 5; - -} - -const std::vector& Val::byte_vec() const -{ - bool b = false; - - switch (m__d) - { - case 5: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_byte_vec; -} - -std::vector& Val::byte_vec() -{ - bool b = false; - - switch (m__d) - { - case 5: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_byte_vec; -} - - -void Val::uint( - uint32_t _uint) -{ - m_uint = _uint; - m__d = 6; - -} - -uint32_t Val::uint() const -{ - bool b = false; - - switch (m__d) - { - case 6: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_uint; -} - -uint32_t& Val::uint() -{ - bool b = false; - - switch (m__d) - { - case 6: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_uint; -} - - -void Val::u64( - uint64_t _u64) -{ - m_u64 = _u64; - m__d = 7; - -} - -uint64_t Val::u64() const -{ - bool b = false; - - switch (m__d) - { - case 7: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_u64; -} - -uint64_t& Val::u64() -{ - bool b = false; - - switch (m__d) - { - case 7: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_u64; -} - - -void Val::dob( - double _dob) -{ - m_dob = _dob; - m__d = 8; - -} - -double Val::dob() const -{ - bool b = false; - - switch (m__d) - { - case 8: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_dob; -} - -double& Val::dob() -{ - bool b = false; - - switch (m__d) - { - case 8: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_dob; -} - - -void Val::uint64_vec( - const std::vector& _uint64_vec) -{ - m_uint64_vec = _uint64_vec; - m__d = 9; - -} - -void Val::uint64_vec( - std::vector&& _uint64_vec) -{ - m_uint64_vec = std::move(_uint64_vec); - m__d = 9; - -} - -const std::vector& Val::uint64_vec() const -{ - bool b = false; - - switch (m__d) - { - case 9: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_uint64_vec; -} - -std::vector& Val::uint64_vec() -{ - bool b = false; - - switch (m__d) - { - case 9: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_uint64_vec; -} - - -void Val::vec_float2( - const std::array& _vec_float2) -{ - m_vec_float2 = _vec_float2; - m__d = 10; - -} - -void Val::vec_float2( - std::array&& _vec_float2) -{ - m_vec_float2 = std::move(_vec_float2); - m__d = 10; - -} - -const std::array& Val::vec_float2() const -{ - bool b = false; - - switch (m__d) - { - case 10: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float2; -} - -std::array& Val::vec_float2() -{ - bool b = false; - - switch (m__d) - { - case 10: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float2; -} - - -void Val::vec_float3( - const std::array& _vec_float3) -{ - m_vec_float3 = _vec_float3; - m__d = 11; - -} - -void Val::vec_float3( - std::array&& _vec_float3) -{ - m_vec_float3 = std::move(_vec_float3); - m__d = 11; - -} - -const std::array& Val::vec_float3() const -{ - bool b = false; - - switch (m__d) - { - case 11: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float3; -} - -std::array& Val::vec_float3() -{ - bool b = false; - - switch (m__d) - { - case 11: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float3; -} - - -void Val::vec_float4( - const std::array& _vec_float4) -{ - m_vec_float4 = _vec_float4; - m__d = 12; - -} - -void Val::vec_float4( - std::array&& _vec_float4) -{ - m_vec_float4 = std::move(_vec_float4); - m__d = 12; - -} - -const std::array& Val::vec_float4() const -{ - bool b = false; - - switch (m__d) - { - case 12: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float4; -} - -std::array& Val::vec_float4() -{ - bool b = false; - - switch (m__d) - { - case 12: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float4; -} - - -void Val::vec_float6( - const std::array& _vec_float6) -{ - m_vec_float6 = _vec_float6; - m__d = 13; - -} - -void Val::vec_float6( - std::array&& _vec_float6) -{ - m_vec_float6 = std::move(_vec_float6); - m__d = 13; - -} - -const std::array& Val::vec_float6() const -{ - bool b = false; - - switch (m__d) - { - case 13: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float6; -} - -std::array& Val::vec_float6() -{ - bool b = false; - - switch (m__d) - { - case 13: - b = true; - break; - default: - break; - } - - if (!b) - { - throw BadParamException("This member has not been selected"); - } - - return m_vec_float6; -} - - - -Attrib::Attrib() -{ - -} - -Attrib::~Attrib() -{ -} - -Attrib::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; -} - -Attrib::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; -} - -Attrib& 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; -} - -Attrib& 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; -} - -bool Attrib::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); -} - -bool Attrib::operator !=( - const Attrib& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member type - * @param _type New value for member type - */ -void Attrib::type( - uint32_t _type) -{ - m_type = _type; -} - -/*! - * @brief This function returns the value of member type - * @return Value of member type - */ -uint32_t Attrib::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -uint32_t& Attrib::type() -{ - return m_type; -} - - -/*! - * @brief This function copies the value in member value - * @param _value New value to be copied in member value - */ -void Attrib::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 - */ -void Attrib::value( - Val&& _value) -{ - m_value = std::move(_value); -} - -/*! - * @brief This function returns a constant reference to member value - * @return Constant reference to member value - */ -const Val& Attrib::value() const -{ - return m_value; -} - -/*! - * @brief This function returns a reference to member value - * @return Reference to member value - */ -Val& Attrib::value() -{ - return m_value; -} - - -/*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ -void Attrib::timestamp( - uint64_t _timestamp) -{ - m_timestamp = _timestamp; -} - -/*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ -uint64_t Attrib::timestamp() const -{ - return m_timestamp; -} - -/*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ -uint64_t& Attrib::timestamp() -{ - return m_timestamp; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void Attrib::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 - */ -uint32_t Attrib::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& Attrib::agent_id() -{ - return m_agent_id; -} - - -PairInt::PairInt() -{ - -} - -PairInt::~PairInt() -{ -} - -PairInt::PairInt( - const PairInt& x) -{ - m_first = x.m_first; - m_second = x.m_second; -} - -PairInt::PairInt( - PairInt&& x) noexcept -{ - m_first = x.m_first; - m_second = x.m_second; -} - -PairInt& PairInt::operator =( - const PairInt& x) -{ - - m_first = x.m_first; - m_second = x.m_second; - return *this; -} - -PairInt& PairInt::operator =( - PairInt&& x) noexcept -{ - - m_first = x.m_first; - m_second = x.m_second; - return *this; -} - -bool PairInt::operator ==( - const PairInt& x) const -{ - return (m_first == x.m_first && - m_second == x.m_second); -} - -bool PairInt::operator !=( - const PairInt& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member first - * @param _first New value for member first - */ -void PairInt::first( - uint64_t _first) -{ - m_first = _first; -} - -/*! - * @brief This function returns the value of member first - * @return Value of member first - */ -uint64_t PairInt::first() const -{ - return m_first; -} - -/*! - * @brief This function returns a reference to member first - * @return Reference to member first - */ -uint64_t& PairInt::first() -{ - return m_first; -} - - -/*! - * @brief This function sets a value in member second - * @param _second New value for member second - */ -void PairInt::second( - int32_t _second) -{ - m_second = _second; -} - -/*! - * @brief This function returns the value of member second - * @return Value of member second - */ -int32_t PairInt::second() const -{ - return m_second; -} - -/*! - * @brief This function returns a reference to member second - * @return Reference to member second - */ -int32_t& PairInt::second() -{ - return m_second; -} - - -DotContext::DotContext() -{ - -} - -DotContext::~DotContext() -{ -} - -DotContext::DotContext( - const DotContext& x) -{ - m_cc = x.m_cc; - m_dc = x.m_dc; -} - -DotContext::DotContext( - DotContext&& x) noexcept -{ - m_cc = std::move(x.m_cc); - m_dc = std::move(x.m_dc); -} - -DotContext& DotContext::operator =( - const DotContext& x) -{ - - m_cc = x.m_cc; - m_dc = x.m_dc; - return *this; -} - -DotContext& DotContext::operator =( - DotContext&& x) noexcept -{ - - m_cc = std::move(x.m_cc); - m_dc = std::move(x.m_dc); - return *this; -} - -bool DotContext::operator ==( - const DotContext& x) const -{ - return (m_cc == x.m_cc && - m_dc == x.m_dc); -} - -bool DotContext::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 - */ -void DotContext::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 - */ -void DotContext::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 - */ -const std::map& DotContext::cc() const -{ - return m_cc; -} - -/*! - * @brief This function returns a reference to member cc - * @return Reference to member cc - */ -std::map& DotContext::cc() -{ - return m_cc; -} - - -/*! - * @brief This function copies the value in member dc - * @param _dc New value to be copied in member dc - */ -void DotContext::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 - */ -void DotContext::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 - */ -const std::vector& DotContext::dc() const -{ - return m_dc; -} - -/*! - * @brief This function returns a reference to member dc - * @return Reference to member dc - */ -std::vector& DotContext::dc() -{ - return m_dc; -} - - -DotKernelAttr::DotKernelAttr() -{ - -} - -DotKernelAttr::~DotKernelAttr() -{ -} - -DotKernelAttr::DotKernelAttr( - const DotKernelAttr& x) -{ - m_ds = x.m_ds; - m_cbase = x.m_cbase; -} - -DotKernelAttr::DotKernelAttr( - DotKernelAttr&& x) noexcept -{ - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); -} - -DotKernelAttr& DotKernelAttr::operator =( - const DotKernelAttr& x) -{ - - m_ds = x.m_ds; - m_cbase = x.m_cbase; - return *this; -} - -DotKernelAttr& DotKernelAttr::operator =( - DotKernelAttr&& x) noexcept -{ - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; -} - -bool DotKernelAttr::operator ==( - const DotKernelAttr& x) const -{ - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); -} - -bool DotKernelAttr::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 - */ -void DotKernelAttr::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 - */ -void DotKernelAttr::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 - */ -const std::map& DotKernelAttr::ds() const -{ - return m_ds; -} - -/*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ -std::map& DotKernelAttr::ds() -{ - return m_ds; -} - - -/*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ -void DotKernelAttr::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 - */ -void DotKernelAttr::cbase( - DotContext&& _cbase) -{ - m_cbase = std::move(_cbase); -} - -/*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ -const DotContext& DotKernelAttr::cbase() const -{ - return m_cbase; -} - -/*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ -DotContext& DotKernelAttr::cbase() -{ - return m_cbase; -} - - -MvregEdgeAttr::MvregEdgeAttr() -{ - -} - -MvregEdgeAttr::~MvregEdgeAttr() -{ -} - -MvregEdgeAttr::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; -} - -MvregEdgeAttr::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; -} - -MvregEdgeAttr& 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; -} - -MvregEdgeAttr& 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; -} - -bool MvregEdgeAttr::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); -} - -bool MvregEdgeAttr::operator !=( - const MvregEdgeAttr& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void MvregEdgeAttr::id( - uint64_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint64_t MvregEdgeAttr::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint64_t& MvregEdgeAttr::id() -{ - return m_id; -} - - -/*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ -void MvregEdgeAttr::from( - uint64_t _from) -{ - m_from = _from; -} - -/*! - * @brief This function returns the value of member from - * @return Value of member from - */ -uint64_t MvregEdgeAttr::from() const -{ - return m_from; -} - -/*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ -uint64_t& MvregEdgeAttr::from() -{ - return m_from; -} - - -/*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ -void MvregEdgeAttr::to( - uint64_t _to) -{ - m_to = _to; -} - -/*! - * @brief This function returns the value of member to - * @return Value of member to - */ -uint64_t MvregEdgeAttr::to() const -{ - return m_to; -} - -/*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ -uint64_t& MvregEdgeAttr::to() -{ - return m_to; -} - - -/*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ -void MvregEdgeAttr::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 - */ -void MvregEdgeAttr::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 - */ -const std::string& MvregEdgeAttr::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -std::string& MvregEdgeAttr::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 - */ -void MvregEdgeAttr::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 - */ -void MvregEdgeAttr::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 - */ -const std::string& MvregEdgeAttr::attr_name() const -{ - return m_attr_name; -} - -/*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ -std::string& MvregEdgeAttr::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 - */ -void MvregEdgeAttr::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 - */ -void MvregEdgeAttr::dk( - DotKernelAttr&& _dk) -{ - m_dk = std::move(_dk); -} - -/*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ -const DotKernelAttr& MvregEdgeAttr::dk() const -{ - return m_dk; -} - -/*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ -DotKernelAttr& MvregEdgeAttr::dk() -{ - return m_dk; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void MvregEdgeAttr::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 - */ -uint32_t MvregEdgeAttr::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& MvregEdgeAttr::agent_id() -{ - return m_agent_id; -} - - -/*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ -void MvregEdgeAttr::timestamp( - uint64_t _timestamp) -{ - m_timestamp = _timestamp; -} - -/*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ -uint64_t MvregEdgeAttr::timestamp() const -{ - return m_timestamp; -} - -/*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ -uint64_t& MvregEdgeAttr::timestamp() -{ - return m_timestamp; -} - - -IDLEdge::IDLEdge() -{ - -} - -IDLEdge::~IDLEdge() -{ -} - -IDLEdge::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; -} - -IDLEdge::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; -} - -IDLEdge& 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; -} - -IDLEdge& 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; -} - -bool IDLEdge::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); -} - -bool IDLEdge::operator !=( - const IDLEdge& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ -void IDLEdge::to( - uint64_t _to) -{ - m_to = _to; -} - -/*! - * @brief This function returns the value of member to - * @return Value of member to - */ -uint64_t IDLEdge::to() const -{ - return m_to; -} - -/*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ -uint64_t& IDLEdge::to() -{ - return m_to; -} - - -/*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ -void IDLEdge::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 - */ -void IDLEdge::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 - */ -const std::string& IDLEdge::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -std::string& IDLEdge::type() -{ - return m_type; -} - - -/*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ -void IDLEdge::from( - uint64_t _from) -{ - m_from = _from; -} - -/*! - * @brief This function returns the value of member from - * @return Value of member from - */ -uint64_t IDLEdge::from() const -{ - return m_from; -} - -/*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ -uint64_t& IDLEdge::from() -{ - return m_from; -} - - -/*! - * @brief This function copies the value in member attrs - * @param _attrs New value to be copied in member attrs - */ -void IDLEdge::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 - */ -void IDLEdge::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 - */ -const std::map& IDLEdge::attrs() const -{ - return m_attrs; -} - -/*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ -std::map& IDLEdge::attrs() -{ - return m_attrs; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void IDLEdge::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 - */ -uint32_t IDLEdge::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& IDLEdge::agent_id() -{ - return m_agent_id; -} - - -EdgeKey::EdgeKey() -{ - -} - -EdgeKey::~EdgeKey() -{ -} - -EdgeKey::EdgeKey( - const EdgeKey& x) -{ - m_to = x.m_to; - m_type = x.m_type; -} - -EdgeKey::EdgeKey( - EdgeKey&& x) noexcept -{ - m_to = x.m_to; - m_type = std::move(x.m_type); -} - -EdgeKey& EdgeKey::operator =( - const EdgeKey& x) -{ - - m_to = x.m_to; - m_type = x.m_type; - return *this; -} - -EdgeKey& EdgeKey::operator =( - EdgeKey&& x) noexcept -{ - - m_to = x.m_to; - m_type = std::move(x.m_type); - return *this; -} - -bool EdgeKey::operator ==( - const EdgeKey& x) const -{ - return (m_to == x.m_to && - m_type == x.m_type); -} - -bool EdgeKey::operator !=( - const EdgeKey& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ -void EdgeKey::to( - uint64_t _to) -{ - m_to = _to; -} - -/*! - * @brief This function returns the value of member to - * @return Value of member to - */ -uint64_t EdgeKey::to() const -{ - return m_to; -} - -/*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ -uint64_t& EdgeKey::to() -{ - return m_to; -} - - -/*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ -void EdgeKey::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 - */ -void EdgeKey::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 - */ -const std::string& EdgeKey::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -std::string& EdgeKey::type() -{ - return m_type; -} - - -MvregNodeAttr::MvregNodeAttr() -{ - -} - -MvregNodeAttr::~MvregNodeAttr() -{ -} - -MvregNodeAttr::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; -} - -MvregNodeAttr::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; -} - -MvregNodeAttr& 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; -} - -MvregNodeAttr& 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; -} - -bool MvregNodeAttr::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); -} - -bool MvregNodeAttr::operator !=( - const MvregNodeAttr& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void MvregNodeAttr::id( - uint64_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint64_t MvregNodeAttr::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint64_t& MvregNodeAttr::id() -{ - return m_id; -} - - -/*! - * @brief This function sets a value in member node - * @param _node New value for member node - */ -void MvregNodeAttr::node( - uint64_t _node) -{ - m_node = _node; -} - -/*! - * @brief This function returns the value of member node - * @return Value of member node - */ -uint64_t MvregNodeAttr::node() const -{ - return m_node; -} - -/*! - * @brief This function returns a reference to member node - * @return Reference to member node - */ -uint64_t& MvregNodeAttr::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 - */ -void MvregNodeAttr::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 - */ -void MvregNodeAttr::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 - */ -const std::string& MvregNodeAttr::attr_name() const -{ - return m_attr_name; -} - -/*! - * @brief This function returns a reference to member attr_name - * @return Reference to member attr_name - */ -std::string& MvregNodeAttr::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 - */ -void MvregNodeAttr::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 - */ -void MvregNodeAttr::dk( - DotKernelAttr&& _dk) -{ - m_dk = std::move(_dk); -} - -/*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ -const DotKernelAttr& MvregNodeAttr::dk() const -{ - return m_dk; -} - -/*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ -DotKernelAttr& MvregNodeAttr::dk() -{ - return m_dk; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void MvregNodeAttr::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 - */ -uint32_t MvregNodeAttr::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& MvregNodeAttr::agent_id() -{ - return m_agent_id; -} - - -/*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ -void MvregNodeAttr::timestamp( - uint64_t _timestamp) -{ - m_timestamp = _timestamp; -} - -/*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ -uint64_t MvregNodeAttr::timestamp() const -{ - return m_timestamp; -} - -/*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ -uint64_t& MvregNodeAttr::timestamp() -{ - return m_timestamp; -} - - -DotKernelEdge::DotKernelEdge() -{ - -} - -DotKernelEdge::~DotKernelEdge() -{ -} - -DotKernelEdge::DotKernelEdge( - const DotKernelEdge& x) -{ - m_ds = x.m_ds; - m_cbase = x.m_cbase; -} - -DotKernelEdge::DotKernelEdge( - DotKernelEdge&& x) noexcept -{ - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); -} - -DotKernelEdge& DotKernelEdge::operator =( - const DotKernelEdge& x) -{ - - m_ds = x.m_ds; - m_cbase = x.m_cbase; - return *this; -} - -DotKernelEdge& DotKernelEdge::operator =( - DotKernelEdge&& x) noexcept -{ - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; -} - -bool DotKernelEdge::operator ==( - const DotKernelEdge& x) const -{ - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); -} - -bool DotKernelEdge::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 - */ -void DotKernelEdge::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 - */ -void DotKernelEdge::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 - */ -const std::map& DotKernelEdge::ds() const -{ - return m_ds; -} - -/*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ -std::map& DotKernelEdge::ds() -{ - return m_ds; -} - - -/*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ -void DotKernelEdge::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 - */ -void DotKernelEdge::cbase( - DotContext&& _cbase) -{ - m_cbase = std::move(_cbase); -} - -/*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ -const DotContext& DotKernelEdge::cbase() const -{ - return m_cbase; -} - -/*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ -DotContext& DotKernelEdge::cbase() -{ - return m_cbase; -} - - -MvregEdge::MvregEdge() -{ - -} - -MvregEdge::~MvregEdge() -{ -} - -MvregEdge::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; -} - -MvregEdge::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; -} - -MvregEdge& 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; -} - -MvregEdge& 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; -} - -bool MvregEdge::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); -} - -bool MvregEdge::operator !=( - const MvregEdge& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void MvregEdge::id( - uint64_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint64_t MvregEdge::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint64_t& MvregEdge::id() -{ - return m_id; -} - - -/*! - * @brief This function sets a value in member from - * @param _from New value for member from - */ -void MvregEdge::from( - uint64_t _from) -{ - m_from = _from; -} - -/*! - * @brief This function returns the value of member from - * @return Value of member from - */ -uint64_t MvregEdge::from() const -{ - return m_from; -} - -/*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ -uint64_t& MvregEdge::from() -{ - return m_from; -} - - -/*! - * @brief This function sets a value in member to - * @param _to New value for member to - */ -void MvregEdge::to( - uint64_t _to) -{ - m_to = _to; -} - -/*! - * @brief This function returns the value of member to - * @return Value of member to - */ -uint64_t MvregEdge::to() const -{ - return m_to; -} - -/*! - * @brief This function returns a reference to member to - * @return Reference to member to - */ -uint64_t& MvregEdge::to() -{ - return m_to; -} - - -/*! - * @brief This function copies the value in member type - * @param _type New value to be copied in member type - */ -void MvregEdge::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 - */ -void MvregEdge::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 - */ -const std::string& MvregEdge::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -std::string& MvregEdge::type() -{ - return m_type; -} - - -/*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ -void MvregEdge::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 - */ -void MvregEdge::dk( - DotKernelEdge&& _dk) -{ - m_dk = std::move(_dk); -} - -/*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ -const DotKernelEdge& MvregEdge::dk() const -{ - return m_dk; -} - -/*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ -DotKernelEdge& MvregEdge::dk() -{ - return m_dk; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void MvregEdge::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 - */ -uint32_t MvregEdge::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& MvregEdge::agent_id() -{ - return m_agent_id; -} - - -/*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ -void MvregEdge::timestamp( - uint64_t _timestamp) -{ - m_timestamp = _timestamp; -} - -/*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ -uint64_t MvregEdge::timestamp() const -{ - return m_timestamp; -} - -/*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ -uint64_t& MvregEdge::timestamp() -{ - return m_timestamp; -} - - -IDLNode::IDLNode() -{ - -} - -IDLNode::~IDLNode() -{ -} - -IDLNode::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; -} - -IDLNode::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); -} - -IDLNode& 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; -} - -IDLNode& 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; -} - -bool IDLNode::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); -} - -bool IDLNode::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 - */ -void IDLNode::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 - */ -void IDLNode::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 - */ -const std::string& IDLNode::type() const -{ - return m_type; -} - -/*! - * @brief This function returns a reference to member type - * @return Reference to member type - */ -std::string& IDLNode::type() -{ - return m_type; -} - - -/*! - * @brief This function copies the value in member name - * @param _name New value to be copied in member name - */ -void IDLNode::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 - */ -void IDLNode::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 - */ -const std::string& IDLNode::name() const -{ - return m_name; -} - -/*! - * @brief This function returns a reference to member name - * @return Reference to member name - */ -std::string& IDLNode::name() -{ - return m_name; -} - - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void IDLNode::id( - uint64_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint64_t IDLNode::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint64_t& IDLNode::id() -{ - return m_id; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void IDLNode::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 - */ -uint32_t IDLNode::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& IDLNode::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 - */ -void IDLNode::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 - */ -void IDLNode::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 - */ -const std::map& IDLNode::attrs() const -{ - return m_attrs; -} - -/*! - * @brief This function returns a reference to member attrs - * @return Reference to member attrs - */ -std::map& IDLNode::attrs() -{ - return m_attrs; -} - - -/*! - * @brief This function copies the value in member fano - * @param _fano New value to be copied in member fano - */ -void IDLNode::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 - */ -void IDLNode::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 - */ -const std::map& IDLNode::fano() const -{ - return m_fano; -} - -/*! - * @brief This function returns a reference to member fano - * @return Reference to member fano - */ -std::map& IDLNode::fano() -{ - return m_fano; -} - - -GraphRequest::GraphRequest() -{ - -} - -GraphRequest::~GraphRequest() -{ -} - -GraphRequest::GraphRequest( - const GraphRequest& x) -{ - m_from = x.m_from; - m_id = x.m_id; -} - -GraphRequest::GraphRequest( - GraphRequest&& x) noexcept -{ - m_from = std::move(x.m_from); - m_id = x.m_id; -} - -GraphRequest& GraphRequest::operator =( - const GraphRequest& x) -{ - - m_from = x.m_from; - m_id = x.m_id; - return *this; -} - -GraphRequest& GraphRequest::operator =( - GraphRequest&& x) noexcept -{ - - m_from = std::move(x.m_from); - m_id = x.m_id; - return *this; -} - -bool GraphRequest::operator ==( - const GraphRequest& x) const -{ - return (m_from == x.m_from && - m_id == x.m_id); -} - -bool GraphRequest::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 - */ -void GraphRequest::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 - */ -void GraphRequest::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 - */ -const std::string& GraphRequest::from() const -{ - return m_from; -} - -/*! - * @brief This function returns a reference to member from - * @return Reference to member from - */ -std::string& GraphRequest::from() -{ - return m_from; -} - - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void GraphRequest::id( - int32_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -int32_t GraphRequest::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -int32_t& GraphRequest::id() -{ - return m_id; -} - - -DotKernel::DotKernel() -{ - -} - -DotKernel::~DotKernel() -{ -} - -DotKernel::DotKernel( - const DotKernel& x) -{ - m_ds = x.m_ds; - m_cbase = x.m_cbase; -} - -DotKernel::DotKernel( - DotKernel&& x) noexcept -{ - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); -} - -DotKernel& DotKernel::operator =( - const DotKernel& x) -{ - - m_ds = x.m_ds; - m_cbase = x.m_cbase; - return *this; -} - -DotKernel& DotKernel::operator =( - DotKernel&& x) noexcept -{ - - m_ds = std::move(x.m_ds); - m_cbase = std::move(x.m_cbase); - return *this; -} - -bool DotKernel::operator ==( - const DotKernel& x) const -{ - return (m_ds == x.m_ds && - m_cbase == x.m_cbase); -} - -bool DotKernel::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 - */ -void DotKernel::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 - */ -void DotKernel::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 - */ -const std::map& DotKernel::ds() const -{ - return m_ds; -} - -/*! - * @brief This function returns a reference to member ds - * @return Reference to member ds - */ -std::map& DotKernel::ds() -{ - return m_ds; -} - - -/*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ -void DotKernel::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 - */ -void DotKernel::cbase( - DotContext&& _cbase) -{ - m_cbase = std::move(_cbase); -} - -/*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ -const DotContext& DotKernel::cbase() const -{ - return m_cbase; -} - -/*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ -DotContext& DotKernel::cbase() -{ - return m_cbase; -} - - -MvregNode::MvregNode() -{ - -} - -MvregNode::~MvregNode() -{ -} - -MvregNode::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; -} - -MvregNode::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; -} - -MvregNode& 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; -} - -MvregNode& 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; -} - -bool MvregNode::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); -} - -bool MvregNode::operator !=( - const MvregNode& x) const -{ - return !(*this == x); -} - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void MvregNode::id( - uint64_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint64_t MvregNode::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint64_t& MvregNode::id() -{ - return m_id; -} - - -/*! - * @brief This function copies the value in member dk - * @param _dk New value to be copied in member dk - */ -void MvregNode::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 - */ -void MvregNode::dk( - DotKernel&& _dk) -{ - m_dk = std::move(_dk); -} - -/*! - * @brief This function returns a constant reference to member dk - * @return Constant reference to member dk - */ -const DotKernel& MvregNode::dk() const -{ - return m_dk; -} - -/*! - * @brief This function returns a reference to member dk - * @return Reference to member dk - */ -DotKernel& MvregNode::dk() -{ - return m_dk; -} - - -/*! - * @brief This function sets a value in member agent_id - * @param _agent_id New value for member agent_id - */ -void MvregNode::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 - */ -uint32_t MvregNode::agent_id() const -{ - return m_agent_id; -} - -/*! - * @brief This function returns a reference to member agent_id - * @return Reference to member agent_id - */ -uint32_t& MvregNode::agent_id() -{ - return m_agent_id; -} - - -/*! - * @brief This function sets a value in member timestamp - * @param _timestamp New value for member timestamp - */ -void MvregNode::timestamp( - uint64_t _timestamp) -{ - m_timestamp = _timestamp; -} - -/*! - * @brief This function returns the value of member timestamp - * @return Value of member timestamp - */ -uint64_t MvregNode::timestamp() const -{ - return m_timestamp; -} - -/*! - * @brief This function returns a reference to member timestamp - * @return Reference to member timestamp - */ -uint64_t& MvregNode::timestamp() -{ - return m_timestamp; -} - - -OrMap::OrMap() -{ - -} - -OrMap::~OrMap() -{ -} - -OrMap::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; -} - -OrMap::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); -} - -OrMap& 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; -} - -OrMap& 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; -} - -bool OrMap::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); -} - -bool OrMap::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 - */ -void OrMap::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 - */ -uint32_t OrMap::to_id() const -{ - return m_to_id; -} - -/*! - * @brief This function returns a reference to member to_id - * @return Reference to member to_id - */ -uint32_t& OrMap::to_id() -{ - return m_to_id; -} - - -/*! - * @brief This function sets a value in member id - * @param _id New value for member id - */ -void OrMap::id( - uint32_t _id) -{ - m_id = _id; -} - -/*! - * @brief This function returns the value of member id - * @return Value of member id - */ -uint32_t OrMap::id() const -{ - return m_id; -} - -/*! - * @brief This function returns a reference to member id - * @return Reference to member id - */ -uint32_t& OrMap::id() -{ - return m_id; -} - - -/*! - * @brief This function copies the value in member m - * @param _m New value to be copied in member m - */ -void OrMap::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 - */ -void OrMap::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 - */ -const std::map& OrMap::m() const -{ - return m_m; -} - -/*! - * @brief This function returns a reference to member m - * @return Reference to member m - */ -std::map& OrMap::m() -{ - return m_m; -} - - -/*! - * @brief This function copies the value in member cbase - * @param _cbase New value to be copied in member cbase - */ -void OrMap::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 - */ -void OrMap::cbase( - DotContext&& _cbase) -{ - m_cbase = std::move(_cbase); -} - -/*! - * @brief This function returns a constant reference to member cbase - * @return Constant reference to member cbase - */ -const DotContext& OrMap::cbase() const -{ - return m_cbase; -} - -/*! - * @brief This function returns a reference to member cbase - * @return Reference to member cbase - */ -DotContext& OrMap::cbase() -{ - return m_cbase; -} - - -MvregEdgeAttrVec::MvregEdgeAttrVec() -{ - -} - -MvregEdgeAttrVec::~MvregEdgeAttrVec() -{ -} - -MvregEdgeAttrVec::MvregEdgeAttrVec( - const MvregEdgeAttrVec& x) -{ - m_vec = x.m_vec; -} - -MvregEdgeAttrVec::MvregEdgeAttrVec( - MvregEdgeAttrVec&& x) noexcept -{ - m_vec = std::move(x.m_vec); -} - -MvregEdgeAttrVec& MvregEdgeAttrVec::operator =( - const MvregEdgeAttrVec& x) -{ - - m_vec = x.m_vec; - return *this; -} - -MvregEdgeAttrVec& MvregEdgeAttrVec::operator =( - MvregEdgeAttrVec&& x) noexcept -{ - - m_vec = std::move(x.m_vec); - return *this; -} - -bool MvregEdgeAttrVec::operator ==( - const MvregEdgeAttrVec& x) const -{ - return (m_vec == x.m_vec); -} - -bool MvregEdgeAttrVec::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 - */ -void MvregEdgeAttrVec::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 - */ -void MvregEdgeAttrVec::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 - */ -const std::vector& MvregEdgeAttrVec::vec() const -{ - return m_vec; -} - -/*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ -std::vector& MvregEdgeAttrVec::vec() -{ - return m_vec; -} - - -MvregNodeAttrVec::MvregNodeAttrVec() -{ - -} - -MvregNodeAttrVec::~MvregNodeAttrVec() -{ -} - -MvregNodeAttrVec::MvregNodeAttrVec( - const MvregNodeAttrVec& x) -{ - m_vec = x.m_vec; -} - -MvregNodeAttrVec::MvregNodeAttrVec( - MvregNodeAttrVec&& x) noexcept -{ - m_vec = std::move(x.m_vec); -} - -MvregNodeAttrVec& MvregNodeAttrVec::operator =( - const MvregNodeAttrVec& x) -{ - - m_vec = x.m_vec; - return *this; -} - -MvregNodeAttrVec& MvregNodeAttrVec::operator =( - MvregNodeAttrVec&& x) noexcept -{ - - m_vec = std::move(x.m_vec); - return *this; -} - -bool MvregNodeAttrVec::operator ==( - const MvregNodeAttrVec& x) const -{ - return (m_vec == x.m_vec); -} - -bool MvregNodeAttrVec::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 - */ -void MvregNodeAttrVec::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 - */ -void MvregNodeAttrVec::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 - */ -const std::vector& MvregNodeAttrVec::vec() const -{ - return m_vec; -} - -/*! - * @brief This function returns a reference to member vec - * @return Reference to member vec - */ -std::vector& MvregNodeAttrVec::vec() -{ - return m_vec; -} - -} - -// Include auxiliary functions like for serializing/deserializing. -#include "IDLGraphCdrAux.ipp" diff --git a/core/topics/IDLGraphCdrAux.ipp b/core/topics/IDLGraphCdrAux.ipp index 88a51583..705973f2 100644 --- a/core/topics/IDLGraphCdrAux.ipp +++ b/core/topics/IDLGraphCdrAux.ipp @@ -19,10 +19,10 @@ * This file was generated by the tool fastddsgen. */ -#ifndef _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_IPP_ -#define _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_IPP_ +#ifndef FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP +#define FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP -#include +#include "dsr/core/topics/IDLGraphCdrAux.hpp" #include #include @@ -37,7 +37,7 @@ namespace fastcdr { template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::Val& data, + const Val& data, size_t& current_alignment) { static_cast(data); @@ -54,73 +54,73 @@ eProsima_user_DllExport size_t calculate_serialized_size( switch (data._d()) { - case 0: - calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + 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(1), + 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(2), + 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(3), + 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(4), + 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(5), + 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(6), + 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(7), + 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(8), + 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(9), + 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(10), + 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(11), + 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(12), + 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(13), + case 13: + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(14), data.vec_float6(), current_alignment); break; @@ -137,7 +137,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::Val& data) + const Val& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -150,59 +150,59 @@ eProsima_user_DllExport void serialize( switch (data._d()) { case 0: - scdr << eprosima::fastcdr::MemberId(0) << data.str(); + scdr << eprosima::fastcdr::MemberId(1) << data.str(); break; case 1: - scdr << eprosima::fastcdr::MemberId(1) << data.dec(); + scdr << eprosima::fastcdr::MemberId(2) << data.dec(); break; case 2: - scdr << eprosima::fastcdr::MemberId(2) << data.fl(); + scdr << eprosima::fastcdr::MemberId(3) << data.fl(); break; case 3: - scdr << eprosima::fastcdr::MemberId(3) << data.float_vec(); + scdr << eprosima::fastcdr::MemberId(4) << data.float_vec(); break; case 4: - scdr << eprosima::fastcdr::MemberId(4) << data.bl(); + scdr << eprosima::fastcdr::MemberId(5) << data.bl(); break; case 5: - scdr << eprosima::fastcdr::MemberId(5) << data.byte_vec(); + scdr << eprosima::fastcdr::MemberId(6) << data.byte_vec(); break; case 6: - scdr << eprosima::fastcdr::MemberId(6) << data.uint(); + scdr << eprosima::fastcdr::MemberId(7) << data.uint(); break; case 7: - scdr << eprosima::fastcdr::MemberId(7) << data.u64(); + scdr << eprosima::fastcdr::MemberId(8) << data.u64(); break; case 8: - scdr << eprosima::fastcdr::MemberId(8) << data.dob(); + scdr << eprosima::fastcdr::MemberId(9) << data.dob(); break; case 9: - scdr << eprosima::fastcdr::MemberId(9) << data.uint64_vec(); + scdr << eprosima::fastcdr::MemberId(10) << data.uint64_vec(); break; case 10: - scdr << eprosima::fastcdr::MemberId(10) << data.vec_float2(); + scdr << eprosima::fastcdr::MemberId(11) << data.vec_float2(); break; case 11: - scdr << eprosima::fastcdr::MemberId(11) << data.vec_float3(); + scdr << eprosima::fastcdr::MemberId(12) << data.vec_float3(); break; case 12: - scdr << eprosima::fastcdr::MemberId(12) << data.vec_float4(); + scdr << eprosima::fastcdr::MemberId(13) << data.vec_float4(); break; case 13: - scdr << eprosima::fastcdr::MemberId(13) << data.vec_float6(); + scdr << eprosima::fastcdr::MemberId(14) << data.vec_float6(); break; default: @@ -215,7 +215,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::Val& data) + Val& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -223,75 +223,194 @@ eProsima_user_DllExport void deserialize( [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool { bool ret_value = true; - switch (mid.id) + if (0 == mid.id) { - case 0: - dcdr >> data._d(); - break; - default: - 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; - break; + 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; }); @@ -301,7 +420,7 @@ eProsima_user_DllExport void deserialize( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::Attrib& data, + const Attrib& data, size_t& current_alignment) { static_cast(data); @@ -335,7 +454,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::Attrib& data) + const Attrib& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -355,7 +474,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::Attrib& data) + Attrib& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -391,7 +510,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::Attrib& data) + const Attrib& data) { static_cast(scdr); static_cast(data); @@ -401,7 +520,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::PairInt& data, + const PairInt& data, size_t& current_alignment) { static_cast(data); @@ -429,7 +548,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::PairInt& data) + const PairInt& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -447,7 +566,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::PairInt& data) + PairInt& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -475,7 +594,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::PairInt& data) + const PairInt& data) { static_cast(scdr); static_cast(data); @@ -485,7 +604,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::DotContext& data, + const DotContext& data, size_t& current_alignment) { static_cast(data); @@ -513,7 +632,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::DotContext& data) + const DotContext& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -531,7 +650,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::DotContext& data) + DotContext& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -559,7 +678,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::DotContext& data) + const DotContext& data) { static_cast(scdr); static_cast(data); @@ -569,7 +688,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::DotKernelAttr& data, + const DotKernelAttr& data, size_t& current_alignment) { static_cast(data); @@ -597,7 +716,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelAttr& data) + const DotKernelAttr& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -615,7 +734,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::DotKernelAttr& data) + DotKernelAttr& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -643,7 +762,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelAttr& data) + const DotKernelAttr& data) { static_cast(scdr); static_cast(data); @@ -653,7 +772,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregEdgeAttr& data, + const MvregEdgeAttr& data, size_t& current_alignment) { static_cast(data); @@ -699,7 +818,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttr& data) + const MvregEdgeAttr& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -723,7 +842,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregEdgeAttr& data) + MvregEdgeAttr& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -775,7 +894,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttr& data) + const MvregEdgeAttr& data) { static_cast(scdr); static_cast(data); @@ -785,7 +904,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::IDLEdge& data, + const IDLEdge& data, size_t& current_alignment) { static_cast(data); @@ -822,7 +941,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::IDLEdge& data) + const IDLEdge& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -843,7 +962,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::IDLEdge& data) + IDLEdge& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -883,7 +1002,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::IDLEdge& data) + const IDLEdge& data) { static_cast(scdr); static_cast(data); @@ -893,7 +1012,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::EdgeKey& data, + const EdgeKey& data, size_t& current_alignment) { static_cast(data); @@ -921,7 +1040,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::EdgeKey& data) + const EdgeKey& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -939,7 +1058,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::EdgeKey& data) + EdgeKey& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -967,7 +1086,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::EdgeKey& data) + const EdgeKey& data) { static_cast(scdr); static_cast(data); @@ -977,7 +1096,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregNodeAttr& data, + const MvregNodeAttr& data, size_t& current_alignment) { static_cast(data); @@ -1017,7 +1136,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttr& data) + const MvregNodeAttr& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1039,7 +1158,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregNodeAttr& data) + MvregNodeAttr& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1083,7 +1202,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttr& data) + const MvregNodeAttr& data) { static_cast(scdr); static_cast(data); @@ -1093,7 +1212,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::DotKernelEdge& data, + const DotKernelEdge& data, size_t& current_alignment) { static_cast(data); @@ -1121,7 +1240,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelEdge& data) + const DotKernelEdge& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1139,7 +1258,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::DotKernelEdge& data) + DotKernelEdge& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1167,7 +1286,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernelEdge& data) + const DotKernelEdge& data) { static_cast(scdr); static_cast(data); @@ -1177,7 +1296,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregEdge& data, + const MvregEdge& data, size_t& current_alignment) { static_cast(data); @@ -1220,7 +1339,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdge& data) + const MvregEdge& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1243,7 +1362,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregEdge& data) + MvregEdge& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1291,7 +1410,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdge& data) + const MvregEdge& data) { static_cast(scdr); static_cast(data); @@ -1301,7 +1420,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::IDLNode& data, + const IDLNode& data, size_t& current_alignment) { static_cast(data); @@ -1341,7 +1460,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::IDLNode& data) + const IDLNode& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1363,7 +1482,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::IDLNode& data) + IDLNode& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1407,7 +1526,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::IDLNode& data) + const IDLNode& data) { static_cast(scdr); static_cast(data); @@ -1417,7 +1536,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::GraphRequest& data, + const GraphRequest& data, size_t& current_alignment) { static_cast(data); @@ -1445,7 +1564,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::GraphRequest& data) + const GraphRequest& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1463,7 +1582,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::GraphRequest& data) + GraphRequest& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1491,7 +1610,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::GraphRequest& data) + const GraphRequest& data) { static_cast(scdr); static_cast(data); @@ -1501,7 +1620,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::DotKernel& data, + const DotKernel& data, size_t& current_alignment) { static_cast(data); @@ -1529,7 +1648,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernel& data) + const DotKernel& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1547,7 +1666,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::DotKernel& data) + DotKernel& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1575,7 +1694,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::DotKernel& data) + const DotKernel& data) { static_cast(scdr); static_cast(data); @@ -1585,7 +1704,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregNode& data, + const MvregNode& data, size_t& current_alignment) { static_cast(data); @@ -1619,7 +1738,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNode& data) + const MvregNode& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1639,7 +1758,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregNode& data) + MvregNode& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1675,7 +1794,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNode& data) + const MvregNode& data) { static_cast(scdr); static_cast(data); @@ -1685,7 +1804,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::OrMap& data, + const OrMap& data, size_t& current_alignment) { static_cast(data); @@ -1719,7 +1838,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::OrMap& data) + const OrMap& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1739,7 +1858,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::OrMap& data) + OrMap& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1775,7 +1894,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::OrMap& data) + const OrMap& data) { static_cast(scdr); static_cast(data); @@ -1785,7 +1904,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregEdgeAttrVec& data, + const MvregEdgeAttrVec& data, size_t& current_alignment) { static_cast(data); @@ -1810,7 +1929,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttrVec& data) + const MvregEdgeAttrVec& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1827,7 +1946,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregEdgeAttrVec& data) + MvregEdgeAttrVec& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1851,7 +1970,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregEdgeAttrVec& data) + const MvregEdgeAttrVec& data) { static_cast(scdr); static_cast(data); @@ -1861,7 +1980,7 @@ void serialize_key( template<> eProsima_user_DllExport size_t calculate_serialized_size( eprosima::fastcdr::CdrSizeCalculator& calculator, - const IDL::MvregNodeAttrVec& data, + const MvregNodeAttrVec& data, size_t& current_alignment) { static_cast(data); @@ -1886,7 +2005,7 @@ eProsima_user_DllExport size_t calculate_serialized_size( template<> eProsima_user_DllExport void serialize( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttrVec& data) + const MvregNodeAttrVec& data) { eprosima::fastcdr::Cdr::state current_state(scdr); scdr.begin_serialize_type(current_state, @@ -1903,7 +2022,7 @@ eProsima_user_DllExport void serialize( template<> eProsima_user_DllExport void deserialize( eprosima::fastcdr::Cdr& cdr, - IDL::MvregNodeAttrVec& data) + MvregNodeAttrVec& data) { cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : @@ -1927,7 +2046,7 @@ eProsima_user_DllExport void deserialize( void serialize_key( eprosima::fastcdr::Cdr& scdr, - const IDL::MvregNodeAttrVec& data) + const MvregNodeAttrVec& data) { static_cast(scdr); static_cast(data); @@ -1938,5 +2057,5 @@ void serialize_key( } // namespace fastcdr } // namespace eprosima -#endif // _FAST_DDS_GENERATED_IDLGRAPHCDRAUX_IPP_ +#endif // FAST_DDS_GENERATED__IDLGRAPHCDRAUX_IPP diff --git a/core/topics/IDLGraphPubSubTypes.cxx b/core/topics/IDLGraphPubSubTypes.cxx index d4bc3dde..6beb0b3d 100644 --- a/core/topics/IDLGraphPubSubTypes.cxx +++ b/core/topics/IDLGraphPubSubTypes.cxx @@ -19,22 +19,29 @@ * This file was generated by the tool fastddsgen. */ +#include "dsr/core/topics/IDLGraphPubSubTypes.hpp" -#include -#include -#include +#include +#include -#include -#include +#include "dsr/core/topics/IDLGraphCdrAux.hpp" +//#include "IDLGraphTypeObjectSupport.hpp" -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using namespace IDL; + +using SerializedPayload_t = eprosima::fastdds::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastdds::rtps::InstanceHandle_t; using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; AttribPubSubType::AttribPubSubType() { setName("Attrib"); - uint32_t type_size = Attrib_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Attrib::getMaxCdrSerializedSize()); +#else + Attrib_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -52,11 +59,11 @@ AttribPubSubType::~AttribPubSubType() } bool AttribPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::Attrib* p_type = static_cast(data); + const Attrib* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -65,10 +72,12 @@ bool AttribPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -83,7 +92,11 @@ bool AttribPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -94,13 +107,17 @@ bool AttribPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::Attrib* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -118,34 +135,47 @@ bool AttribPubSubType::deserialize( } std::function AttribPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* AttribPubSubType::createData() { - return reinterpret_cast(new IDL::Attrib()); + return reinterpret_cast(new Attrib()); } void AttribPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool AttribPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -154,19 +184,27 @@ bool AttribPubSubType::getKey( return false; } - IDL::Attrib* p_type = static_cast(data); + const Attrib* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), Attrib_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || Attrib_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -183,10 +221,20 @@ bool AttribPubSubType::getKey( return true; } +void AttribPubSubType::register_type_object_representation() +{ + //register_Attrib_type_identifier(type_identifiers_); +} + PairIntPubSubType::PairIntPubSubType() { setName("PairInt"); - uint32_t type_size = PairInt_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PairInt::getMaxCdrSerializedSize()); +#else + PairInt_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -204,11 +252,11 @@ PairIntPubSubType::~PairIntPubSubType() } bool PairIntPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::PairInt* p_type = static_cast(data); + const PairInt* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -217,10 +265,12 @@ bool PairIntPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -235,7 +285,11 @@ bool PairIntPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -246,13 +300,17 @@ bool PairIntPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::PairInt* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -270,34 +328,47 @@ bool PairIntPubSubType::deserialize( } std::function PairIntPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* PairIntPubSubType::createData() { - return reinterpret_cast(new IDL::PairInt()); + return reinterpret_cast(new PairInt()); } void PairIntPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool PairIntPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -306,19 +377,27 @@ bool PairIntPubSubType::getKey( return false; } - IDL::PairInt* p_type = static_cast(data); + const PairInt* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), PairInt_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || PairInt_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -335,10 +414,20 @@ bool PairIntPubSubType::getKey( return true; } +void PairIntPubSubType::register_type_object_representation() +{ + //register_PairInt_type_identifier(type_identifiers_); +} + DotContextPubSubType::DotContextPubSubType() { setName("DotContext"); - uint32_t type_size = DotContext_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DotContext::getMaxCdrSerializedSize()); +#else + DotContext_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -356,11 +445,11 @@ DotContextPubSubType::~DotContextPubSubType() } bool DotContextPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::DotContext* p_type = static_cast(data); + const DotContext* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -369,10 +458,12 @@ bool DotContextPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -387,7 +478,11 @@ bool DotContextPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -398,13 +493,17 @@ bool DotContextPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::DotContext* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -422,34 +521,47 @@ bool DotContextPubSubType::deserialize( } std::function DotContextPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* DotContextPubSubType::createData() { - return reinterpret_cast(new IDL::DotContext()); + return reinterpret_cast(new DotContext()); } void DotContextPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool DotContextPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -458,19 +570,27 @@ bool DotContextPubSubType::getKey( return false; } - IDL::DotContext* p_type = static_cast(data); + const DotContext* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), DotContext_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotContext_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -487,10 +607,20 @@ bool DotContextPubSubType::getKey( return true; } +void DotContextPubSubType::register_type_object_representation() +{ + //register_DotContext_type_identifier(type_identifiers_); +} + DotKernelAttrPubSubType::DotKernelAttrPubSubType() { setName("DotKernelAttr"); - uint32_t type_size = DotKernelAttr_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DotKernelAttr::getMaxCdrSerializedSize()); +#else + DotKernelAttr_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -508,11 +638,11 @@ DotKernelAttrPubSubType::~DotKernelAttrPubSubType() } bool DotKernelAttrPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::DotKernelAttr* p_type = static_cast(data); + const DotKernelAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -521,10 +651,12 @@ bool DotKernelAttrPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -539,7 +671,11 @@ bool DotKernelAttrPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -550,13 +686,17 @@ bool DotKernelAttrPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::DotKernelAttr* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -574,34 +714,47 @@ bool DotKernelAttrPubSubType::deserialize( } std::function DotKernelAttrPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* DotKernelAttrPubSubType::createData() { - return reinterpret_cast(new IDL::DotKernelAttr()); + return reinterpret_cast(new DotKernelAttr()); } void DotKernelAttrPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool DotKernelAttrPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -610,19 +763,27 @@ bool DotKernelAttrPubSubType::getKey( return false; } - IDL::DotKernelAttr* p_type = static_cast(data); + const DotKernelAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), DotKernelAttr_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernelAttr_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -639,10 +800,20 @@ bool DotKernelAttrPubSubType::getKey( return true; } +void DotKernelAttrPubSubType::register_type_object_representation() +{ + //register_DotKernelAttr_type_identifier(type_identifiers_); +} + MvregEdgeAttrPubSubType::MvregEdgeAttrPubSubType() { setName("MvregEdgeAttr"); - uint32_t type_size = MvregEdgeAttr_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregEdgeAttr::getMaxCdrSerializedSize()); +#else + MvregEdgeAttr_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -660,11 +831,11 @@ MvregEdgeAttrPubSubType::~MvregEdgeAttrPubSubType() } bool MvregEdgeAttrPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregEdgeAttr* p_type = static_cast(data); + const MvregEdgeAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -673,10 +844,12 @@ bool MvregEdgeAttrPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -691,7 +864,11 @@ bool MvregEdgeAttrPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -702,13 +879,17 @@ bool MvregEdgeAttrPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregEdgeAttr* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -726,34 +907,47 @@ bool MvregEdgeAttrPubSubType::deserialize( } std::function MvregEdgeAttrPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregEdgeAttrPubSubType::createData() { - return reinterpret_cast(new IDL::MvregEdgeAttr()); + return reinterpret_cast(new MvregEdgeAttr()); } void MvregEdgeAttrPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregEdgeAttrPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -762,19 +956,27 @@ bool MvregEdgeAttrPubSubType::getKey( return false; } - IDL::MvregEdgeAttr* p_type = static_cast(data); + const MvregEdgeAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregEdgeAttr_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdgeAttr_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -791,10 +993,20 @@ bool MvregEdgeAttrPubSubType::getKey( return true; } +void MvregEdgeAttrPubSubType::register_type_object_representation() +{ + //register_MvregEdgeAttr_type_identifier(type_identifiers_); +} + IDLEdgePubSubType::IDLEdgePubSubType() { setName("IDLEdge"); - uint32_t type_size = IDLEdge_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(IDLEdge::getMaxCdrSerializedSize()); +#else + IDLEdge_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -812,11 +1024,11 @@ IDLEdgePubSubType::~IDLEdgePubSubType() } bool IDLEdgePubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::IDLEdge* p_type = static_cast(data); + const IDLEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -825,10 +1037,12 @@ bool IDLEdgePubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -843,7 +1057,11 @@ bool IDLEdgePubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -854,13 +1072,17 @@ bool IDLEdgePubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::IDLEdge* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -878,34 +1100,47 @@ bool IDLEdgePubSubType::deserialize( } std::function IDLEdgePubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* IDLEdgePubSubType::createData() { - return reinterpret_cast(new IDL::IDLEdge()); + return reinterpret_cast(new IDLEdge()); } void IDLEdgePubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool IDLEdgePubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -914,19 +1149,27 @@ bool IDLEdgePubSubType::getKey( return false; } - IDL::IDLEdge* p_type = static_cast(data); + const IDLEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), IDLEdge_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || IDLEdge_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -943,10 +1186,20 @@ bool IDLEdgePubSubType::getKey( return true; } +void IDLEdgePubSubType::register_type_object_representation() +{ + //register_IDLEdge_type_identifier(type_identifiers_); +} + EdgeKeyPubSubType::EdgeKeyPubSubType() { setName("EdgeKey"); - uint32_t type_size = EdgeKey_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(EdgeKey::getMaxCdrSerializedSize()); +#else + EdgeKey_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -964,11 +1217,11 @@ EdgeKeyPubSubType::~EdgeKeyPubSubType() } bool EdgeKeyPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::EdgeKey* p_type = static_cast(data); + const EdgeKey* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -977,10 +1230,12 @@ bool EdgeKeyPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -995,7 +1250,11 @@ bool EdgeKeyPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1006,13 +1265,17 @@ bool EdgeKeyPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::EdgeKey* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1030,34 +1293,47 @@ bool EdgeKeyPubSubType::deserialize( } std::function EdgeKeyPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* EdgeKeyPubSubType::createData() { - return reinterpret_cast(new IDL::EdgeKey()); + return reinterpret_cast(new EdgeKey()); } void EdgeKeyPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool EdgeKeyPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1066,19 +1342,27 @@ bool EdgeKeyPubSubType::getKey( return false; } - IDL::EdgeKey* p_type = static_cast(data); + const EdgeKey* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), EdgeKey_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || EdgeKey_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1095,10 +1379,20 @@ bool EdgeKeyPubSubType::getKey( return true; } +void EdgeKeyPubSubType::register_type_object_representation() +{ + //register_EdgeKey_type_identifier(type_identifiers_); +} + MvregNodeAttrPubSubType::MvregNodeAttrPubSubType() { setName("MvregNodeAttr"); - uint32_t type_size = MvregNodeAttr_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregNodeAttr::getMaxCdrSerializedSize()); +#else + MvregNodeAttr_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1116,11 +1410,11 @@ MvregNodeAttrPubSubType::~MvregNodeAttrPubSubType() } bool MvregNodeAttrPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregNodeAttr* p_type = static_cast(data); + const MvregNodeAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1129,10 +1423,12 @@ bool MvregNodeAttrPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1147,7 +1443,11 @@ bool MvregNodeAttrPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1158,13 +1458,17 @@ bool MvregNodeAttrPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregNodeAttr* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1182,34 +1486,47 @@ bool MvregNodeAttrPubSubType::deserialize( } std::function MvregNodeAttrPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregNodeAttrPubSubType::createData() { - return reinterpret_cast(new IDL::MvregNodeAttr()); + return reinterpret_cast(new MvregNodeAttr()); } void MvregNodeAttrPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregNodeAttrPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1218,19 +1535,27 @@ bool MvregNodeAttrPubSubType::getKey( return false; } - IDL::MvregNodeAttr* p_type = static_cast(data); + const MvregNodeAttr* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregNodeAttr_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNodeAttr_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1247,10 +1572,20 @@ bool MvregNodeAttrPubSubType::getKey( return true; } +void MvregNodeAttrPubSubType::register_type_object_representation() +{ + //register_MvregNodeAttr_type_identifier(type_identifiers_); +} + DotKernelEdgePubSubType::DotKernelEdgePubSubType() { setName("DotKernelEdge"); - uint32_t type_size = DotKernelEdge_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DotKernelEdge::getMaxCdrSerializedSize()); +#else + DotKernelEdge_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1268,11 +1603,11 @@ DotKernelEdgePubSubType::~DotKernelEdgePubSubType() } bool DotKernelEdgePubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::DotKernelEdge* p_type = static_cast(data); + const DotKernelEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1281,10 +1616,12 @@ bool DotKernelEdgePubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1299,7 +1636,11 @@ bool DotKernelEdgePubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1310,13 +1651,17 @@ bool DotKernelEdgePubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::DotKernelEdge* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1334,34 +1679,47 @@ bool DotKernelEdgePubSubType::deserialize( } std::function DotKernelEdgePubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* DotKernelEdgePubSubType::createData() { - return reinterpret_cast(new IDL::DotKernelEdge()); + return reinterpret_cast(new DotKernelEdge()); } void DotKernelEdgePubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool DotKernelEdgePubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1370,19 +1728,27 @@ bool DotKernelEdgePubSubType::getKey( return false; } - IDL::DotKernelEdge* p_type = static_cast(data); + const DotKernelEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), DotKernelEdge_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernelEdge_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1399,10 +1765,20 @@ bool DotKernelEdgePubSubType::getKey( return true; } +void DotKernelEdgePubSubType::register_type_object_representation() +{ + //register_DotKernelEdge_type_identifier(type_identifiers_); +} + MvregEdgePubSubType::MvregEdgePubSubType() { setName("MvregEdge"); - uint32_t type_size = MvregEdge_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregEdge::getMaxCdrSerializedSize()); +#else + MvregEdge_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1420,11 +1796,11 @@ MvregEdgePubSubType::~MvregEdgePubSubType() } bool MvregEdgePubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregEdge* p_type = static_cast(data); + const MvregEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1433,10 +1809,12 @@ bool MvregEdgePubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1451,7 +1829,11 @@ bool MvregEdgePubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1462,13 +1844,17 @@ bool MvregEdgePubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregEdge* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1486,34 +1872,47 @@ bool MvregEdgePubSubType::deserialize( } std::function MvregEdgePubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregEdgePubSubType::createData() { - return reinterpret_cast(new IDL::MvregEdge()); + return reinterpret_cast(new MvregEdge()); } void MvregEdgePubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregEdgePubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1522,19 +1921,27 @@ bool MvregEdgePubSubType::getKey( return false; } - IDL::MvregEdge* p_type = static_cast(data); + const MvregEdge* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregEdge_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdge_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1551,10 +1958,20 @@ bool MvregEdgePubSubType::getKey( return true; } +void MvregEdgePubSubType::register_type_object_representation() +{ + //register_MvregEdge_type_identifier(type_identifiers_); +} + IDLNodePubSubType::IDLNodePubSubType() { setName("IDLNode"); - uint32_t type_size = std::numeric_limits::max(); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(IDLNode::getMaxCdrSerializedSize()); +#else + IDLNode_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1572,11 +1989,11 @@ IDLNodePubSubType::~IDLNodePubSubType() } bool IDLNodePubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::IDLNode* p_type = static_cast(data); + const IDLNode* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1585,10 +2002,12 @@ bool IDLNodePubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1603,7 +2022,11 @@ bool IDLNodePubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1614,13 +2037,17 @@ bool IDLNodePubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::IDLNode* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1638,34 +2065,47 @@ bool IDLNodePubSubType::deserialize( } std::function IDLNodePubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* IDLNodePubSubType::createData() { - return reinterpret_cast(new IDL::IDLNode()); + return reinterpret_cast(new IDLNode()); } void IDLNodePubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool IDLNodePubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1674,19 +2114,27 @@ bool IDLNodePubSubType::getKey( return false; } - IDL::IDLNode* p_type = static_cast(data); + const IDLNode* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), IDLNode_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || IDLNode_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1703,10 +2151,20 @@ bool IDLNodePubSubType::getKey( return true; } +void IDLNodePubSubType::register_type_object_representation() +{ + //register_IDLNode_type_identifier(type_identifiers_); +} + GraphRequestPubSubType::GraphRequestPubSubType() { setName("GraphRequest"); - uint32_t type_size = GraphRequest_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GraphRequest::getMaxCdrSerializedSize()); +#else + GraphRequest_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1724,11 +2182,11 @@ GraphRequestPubSubType::~GraphRequestPubSubType() } bool GraphRequestPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::GraphRequest* p_type = static_cast(data); + const GraphRequest* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1737,10 +2195,12 @@ bool GraphRequestPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1755,7 +2215,11 @@ bool GraphRequestPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1766,13 +2230,17 @@ bool GraphRequestPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::GraphRequest* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1790,34 +2258,47 @@ bool GraphRequestPubSubType::deserialize( } std::function GraphRequestPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* GraphRequestPubSubType::createData() { - return reinterpret_cast(new IDL::GraphRequest()); + return reinterpret_cast(new GraphRequest()); } void GraphRequestPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool GraphRequestPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1826,19 +2307,27 @@ bool GraphRequestPubSubType::getKey( return false; } - IDL::GraphRequest* p_type = static_cast(data); + const GraphRequest* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), GraphRequest_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || GraphRequest_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -1855,10 +2344,20 @@ bool GraphRequestPubSubType::getKey( return true; } +void GraphRequestPubSubType::register_type_object_representation() +{ + //register_GraphRequest_type_identifier(type_identifiers_); +} + DotKernelPubSubType::DotKernelPubSubType() { setName("DotKernel"); - uint32_t type_size = std::numeric_limits::max(); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DotKernel::getMaxCdrSerializedSize()); +#else + DotKernel_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -1876,11 +2375,11 @@ DotKernelPubSubType::~DotKernelPubSubType() } bool DotKernelPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::DotKernel* p_type = static_cast(data); + const DotKernel* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -1889,10 +2388,12 @@ bool DotKernelPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1907,7 +2408,11 @@ bool DotKernelPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -1918,13 +2423,17 @@ bool DotKernelPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::DotKernel* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -1942,34 +2451,47 @@ bool DotKernelPubSubType::deserialize( } std::function DotKernelPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* DotKernelPubSubType::createData() { - return reinterpret_cast(new IDL::DotKernel()); + return reinterpret_cast(new DotKernel()); } void DotKernelPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool DotKernelPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -1978,19 +2500,27 @@ bool DotKernelPubSubType::getKey( return false; } - IDL::DotKernel* p_type = static_cast(data); + const DotKernel* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), DotKernel_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernel_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -2007,10 +2537,20 @@ bool DotKernelPubSubType::getKey( return true; } +void DotKernelPubSubType::register_type_object_representation() +{ + //register_DotKernel_type_identifier(type_identifiers_); +} + MvregNodePubSubType::MvregNodePubSubType() { setName("MvregNode"); - uint32_t type_size = std::numeric_limits::max(); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregNode::getMaxCdrSerializedSize()); +#else + MvregNode_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -2028,11 +2568,11 @@ MvregNodePubSubType::~MvregNodePubSubType() } bool MvregNodePubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregNode* p_type = static_cast(data); + const MvregNode* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -2041,10 +2581,12 @@ bool MvregNodePubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2059,7 +2601,11 @@ bool MvregNodePubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -2070,13 +2616,17 @@ bool MvregNodePubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregNode* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -2094,34 +2644,47 @@ bool MvregNodePubSubType::deserialize( } std::function MvregNodePubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregNodePubSubType::createData() { - return reinterpret_cast(new IDL::MvregNode()); + return reinterpret_cast(new MvregNode()); } void MvregNodePubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregNodePubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -2130,19 +2693,27 @@ bool MvregNodePubSubType::getKey( return false; } - IDL::MvregNode* p_type = static_cast(data); + const MvregNode* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregNode_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNode_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -2159,10 +2730,20 @@ bool MvregNodePubSubType::getKey( return true; } +void MvregNodePubSubType::register_type_object_representation() +{ + //register_MvregNode_type_identifier(type_identifiers_); +} + OrMapPubSubType::OrMapPubSubType() { setName("OrMap"); - uint32_t type_size = std::numeric_limits::max(); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(OrMap::getMaxCdrSerializedSize()); +#else + OrMap_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -2180,11 +2761,11 @@ OrMapPubSubType::~OrMapPubSubType() } bool OrMapPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::OrMap* p_type = static_cast(data); + const OrMap* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -2193,10 +2774,12 @@ bool OrMapPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2211,7 +2794,11 @@ bool OrMapPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -2222,13 +2809,17 @@ bool OrMapPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::OrMap* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -2246,34 +2837,47 @@ bool OrMapPubSubType::deserialize( } std::function OrMapPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* OrMapPubSubType::createData() { - return reinterpret_cast(new IDL::OrMap()); + return reinterpret_cast(new OrMap()); } void OrMapPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool OrMapPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -2282,19 +2886,27 @@ bool OrMapPubSubType::getKey( return false; } - IDL::OrMap* p_type = static_cast(data); + const OrMap* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), OrMap_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || OrMap_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -2311,10 +2923,20 @@ bool OrMapPubSubType::getKey( return true; } +void OrMapPubSubType::register_type_object_representation() +{ + //register_OrMap_type_identifier(type_identifiers_); +} + MvregEdgeAttrVecPubSubType::MvregEdgeAttrVecPubSubType() { setName("MvregEdgeAttrVec"); - uint32_t type_size = MvregEdgeAttrVec_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregEdgeAttrVec::getMaxCdrSerializedSize()); +#else + MvregEdgeAttrVec_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -2332,11 +2954,11 @@ MvregEdgeAttrVecPubSubType::~MvregEdgeAttrVecPubSubType() } bool MvregEdgeAttrVecPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregEdgeAttrVec* p_type = static_cast(data); + const MvregEdgeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -2345,10 +2967,12 @@ bool MvregEdgeAttrVecPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2363,7 +2987,11 @@ bool MvregEdgeAttrVecPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -2374,13 +3002,17 @@ bool MvregEdgeAttrVecPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregEdgeAttrVec* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -2398,34 +3030,47 @@ bool MvregEdgeAttrVecPubSubType::deserialize( } std::function MvregEdgeAttrVecPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregEdgeAttrVecPubSubType::createData() { - return reinterpret_cast(new IDL::MvregEdgeAttrVec()); + return reinterpret_cast(new MvregEdgeAttrVec()); } void MvregEdgeAttrVecPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregEdgeAttrVecPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -2434,19 +3079,27 @@ bool MvregEdgeAttrVecPubSubType::getKey( return false; } - IDL::MvregEdgeAttrVec* p_type = static_cast(data); + const MvregEdgeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregEdgeAttrVec_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdgeAttrVec_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -2463,10 +3116,20 @@ bool MvregEdgeAttrVecPubSubType::getKey( return true; } +void MvregEdgeAttrVecPubSubType::register_type_object_representation() +{ + //register_MvregEdgeAttrVec_type_identifier(type_identifiers_); +} + MvregNodeAttrVecPubSubType::MvregNodeAttrVecPubSubType() { setName("MvregNodeAttrVec"); - uint32_t type_size = MvregNodeAttrVec_max_cdr_typesize; + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(MvregNodeAttrVec::getMaxCdrSerializedSize()); +#else + MvregNodeAttrVec_max_cdr_typesize; +#endif type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ m_typeSize = type_size + 4; /*encapsulation*/ m_isGetKeyDefined = false; @@ -2484,11 +3147,11 @@ MvregNodeAttrVecPubSubType::~MvregNodeAttrVecPubSubType() } bool MvregNodeAttrVecPubSubType::serialize( - void* data, + const void* const data, SerializedPayload_t* payload, DataRepresentationId_t data_representation) { - IDL::MvregNodeAttrVec* p_type = static_cast(data); + const MvregNodeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->max_size); @@ -2497,10 +3160,12 @@ bool MvregNodeAttrVecPubSubType::serialize( 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; +#if FASTCDR_VERSION_MAJOR > 1 ser.set_encoding_flag( data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2515,7 +3180,11 @@ bool MvregNodeAttrVecPubSubType::serialize( } // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 return true; } @@ -2526,13 +3195,17 @@ bool MvregNodeAttrVecPubSubType::deserialize( try { // Convert DATA to pointer of your type - IDL::MvregNodeAttrVec* p_type = static_cast(data); + 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); + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); // Deserialize encapsulation. deser.read_encapsulation(); @@ -2550,34 +3223,47 @@ bool MvregNodeAttrVecPubSubType::deserialize( } std::function MvregNodeAttrVecPubSubType::getSerializedSizeProvider( - void* data, + const void* const data, DataRepresentationId_t data_representation) { return [data, data_representation]() -> uint32_t { - 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*/; +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + 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; + } +#endif // FASTCDR_VERSION_MAJOR == 1 }; } void* MvregNodeAttrVecPubSubType::createData() { - return reinterpret_cast(new IDL::MvregNodeAttrVec()); + return reinterpret_cast(new MvregNodeAttrVec()); } void MvregNodeAttrVecPubSubType::deleteData( void* data) { - delete(reinterpret_cast(data)); + delete(reinterpret_cast(data)); } bool MvregNodeAttrVecPubSubType::getKey( - void* data, + const void* const data, InstanceHandle_t* handle, bool force_md5) { @@ -2586,19 +3272,27 @@ bool MvregNodeAttrVecPubSubType::getKey( return false; } - IDL::MvregNodeAttrVec* p_type = static_cast(data); + const MvregNodeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), MvregNodeAttrVec_max_key_cdr_typesize); // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); + eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS, eprosima::fastcdr::CdrVersion::XCDRv1); +#if FASTCDR_VERSION_MAJOR == 1 + p_type->serializeKey(ser); +#else eprosima::fastcdr::serialize_key(ser, *p_type); +#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNodeAttrVec_max_key_cdr_typesize > 16) { m_md5.init(); +#if FASTCDR_VERSION_MAJOR == 1 + m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); +#else m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); +#endif // FASTCDR_VERSION_MAJOR == 1 m_md5.finalize(); for (uint8_t i = 0; i < 16; ++i) { @@ -2615,3 +3309,11 @@ bool MvregNodeAttrVecPubSubType::getKey( return true; } +void MvregNodeAttrVecPubSubType::register_type_object_representation() +{ + //register_MvregNodeAttrVec_type_identifier(type_identifiers_); +} + + +// Include auxiliary functions like for serializing/deserializing. +#include "IDLGraphCdrAux.ipp" From b417d0e406d02da3494198fb249b8712b6764e19 Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Wed, 17 Jul 2024 21:58:16 +0200 Subject: [PATCH 2/8] fixup! [DSR] fix breaking changes for FastDDS 3.0 --- core/rtps/dsrpublisher.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/core/rtps/dsrpublisher.cpp b/core/rtps/dsrpublisher.cpp index bc2e9bec..de34e399 100644 --- a/core/rtps/dsrpublisher.cpp +++ b/core/rtps/dsrpublisher.cpp @@ -66,8 +66,8 @@ std::tuple Date: Thu, 24 Oct 2024 16:56:19 +0200 Subject: [PATCH 3/8] [DSR] regenerate IDL --- core/include/dsr/core/topics/IDLGraph.hpp | 133 +- .../dsr/core/topics/IDLGraphPubSubTypes.hpp | 718 ++--- core/topics/IDLGraphCdrAux.ipp | 177 ++ core/topics/IDLGraphPubSubTypes.cxx | 2505 ++++++++--------- core/topics/regenidl.md | 50 + 5 files changed, 1727 insertions(+), 1856 deletions(-) create mode 100644 core/topics/regenidl.md diff --git a/core/include/dsr/core/topics/IDLGraph.hpp b/core/include/dsr/core/topics/IDLGraph.hpp index c3b65391..65c21888 100644 --- a/core/include/dsr/core/topics/IDLGraph.hpp +++ b/core/include/dsr/core/topics/IDLGraph.hpp @@ -57,9 +57,7 @@ #else #define IDLGRAPH_DllAPI #endif // _WIN32 - - -namespace IDL { +namespace IDL{ /*! * @brief This class represents the union Val defined by the user in the IDL file. * @ingroup IDLGraph @@ -379,67 +377,76 @@ class Val { bool ret_value {false}; - if (m__d == x.m__d && - selected_member_ == x.selected_member_) + if (x.selected_member_ == selected_member_) { - switch (selected_member_) + if (0x0FFFFFFFu != selected_member_) { - case 0x00000001: - ret_value = (m_str == x.m_str); - break; + if (x.m__d == m__d) + { + switch (selected_member_) + { + case 0x00000001: + ret_value = (x.m_str == m_str); + break; - case 0x00000002: - ret_value = (m_dec == x.m_dec); - break; + case 0x00000002: + ret_value = (x.m_dec == m_dec); + break; - case 0x00000003: - ret_value = (m_fl == x.m_fl); - break; + case 0x00000003: + ret_value = (x.m_fl == m_fl); + break; - case 0x00000004: - ret_value = (m_float_vec == x.m_float_vec); - break; + case 0x00000004: + ret_value = (x.m_float_vec == m_float_vec); + break; - case 0x00000005: - ret_value = (m_bl == x.m_bl); - break; + case 0x00000005: + ret_value = (x.m_bl == m_bl); + break; - case 0x00000006: - ret_value = (m_byte_vec == x.m_byte_vec); - break; + case 0x00000006: + ret_value = (x.m_byte_vec == m_byte_vec); + break; - case 0x00000007: - ret_value = (m_uint == x.m_uint); - break; + case 0x00000007: + ret_value = (x.m_uint == m_uint); + break; - case 0x00000008: - ret_value = (m_u64 == x.m_u64); - break; + case 0x00000008: + ret_value = (x.m_u64 == m_u64); + break; - case 0x00000009: - ret_value = (m_dob == x.m_dob); - break; + case 0x00000009: + ret_value = (x.m_dob == m_dob); + break; - case 0x0000000a: - ret_value = (m_uint64_vec == x.m_uint64_vec); - break; + case 0x0000000a: + ret_value = (x.m_uint64_vec == m_uint64_vec); + break; - case 0x0000000b: - ret_value = (m_vec_float2 == x.m_vec_float2); - break; + case 0x0000000b: + ret_value = (x.m_vec_float2 == m_vec_float2); + break; - case 0x0000000c: - ret_value = (m_vec_float3 == x.m_vec_float3); - break; + case 0x0000000c: + ret_value = (x.m_vec_float3 == m_vec_float3); + break; - case 0x0000000d: - ret_value = (m_vec_float4 == x.m_vec_float4); - break; + case 0x0000000d: + ret_value = (x.m_vec_float4 == m_vec_float4); + break; - case 0x0000000e: - ret_value = (m_vec_float6 == x.m_vec_float6); - break; + case 0x0000000e: + ret_value = (x.m_vec_float6 == m_vec_float6); + break; + } + } + } + else + { + ret_value = true; } } @@ -1286,7 +1293,7 @@ class Val selected_member_ = 0x00000001; member_destructor_ = [&]() {m_str.~basic_string();}; new(&m_str) std::string(); - ; + } return m_str; @@ -1304,7 +1311,7 @@ class Val selected_member_ = 0x00000002; member_destructor_ = nullptr; m_dec = {0}; - ; + } return m_dec; @@ -1322,7 +1329,7 @@ class Val selected_member_ = 0x00000003; member_destructor_ = nullptr; m_fl = {0.0}; - ; + } return m_fl; @@ -1340,7 +1347,7 @@ class Val selected_member_ = 0x00000004; member_destructor_ = [&]() {m_float_vec.~vector();}; new(&m_float_vec) std::vector(); - ; + } return m_float_vec; @@ -1358,7 +1365,7 @@ class Val selected_member_ = 0x00000005; member_destructor_ = nullptr; m_bl = {false}; - ; + } return m_bl; @@ -1376,7 +1383,7 @@ class Val selected_member_ = 0x00000006; member_destructor_ = [&]() {m_byte_vec.~vector();}; new(&m_byte_vec) std::vector(); - ; + } return m_byte_vec; @@ -1394,7 +1401,7 @@ class Val selected_member_ = 0x00000007; member_destructor_ = nullptr; m_uint = {0}; - ; + } return m_uint; @@ -1412,7 +1419,7 @@ class Val selected_member_ = 0x00000008; member_destructor_ = nullptr; m_u64 = {0}; - ; + } return m_u64; @@ -1430,7 +1437,7 @@ class Val selected_member_ = 0x00000009; member_destructor_ = nullptr; m_dob = {0.0}; - ; + } return m_dob; @@ -1448,7 +1455,7 @@ class Val selected_member_ = 0x0000000a; member_destructor_ = [&]() {m_uint64_vec.~vector();}; new(&m_uint64_vec) std::vector(); - ; + } return m_uint64_vec; @@ -1466,7 +1473,7 @@ class Val selected_member_ = 0x0000000b; member_destructor_ = [&]() {m_vec_float2.~array();}; new(&m_vec_float2) std::array(); - ; + } return m_vec_float2; @@ -1484,7 +1491,7 @@ class Val selected_member_ = 0x0000000c; member_destructor_ = [&]() {m_vec_float3.~array();}; new(&m_vec_float3) std::array(); - ; + } return m_vec_float3; @@ -1502,7 +1509,7 @@ class Val selected_member_ = 0x0000000d; member_destructor_ = [&]() {m_vec_float4.~array();}; new(&m_vec_float4) std::array(); - ; + } return m_vec_float4; @@ -1520,7 +1527,7 @@ class Val selected_member_ = 0x0000000e; member_destructor_ = [&]() {m_vec_float6.~array();}; new(&m_vec_float6) std::array(); - ; + } return m_vec_float6; @@ -3144,7 +3151,6 @@ class EdgeKey return !(*this == x); } - eProsima_user_DllExport bool operator<( const EdgeKey &rhs) const { @@ -5565,7 +5571,6 @@ class MvregNodeAttrVec std::vector m_vec; }; - } #endif // _FAST_DDS_GENERATED_IDLGRAPH_HPP_ diff --git a/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp b/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp index 56b613a3..517d3aea 100644 --- a/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp +++ b/core/include/dsr/core/topics/IDLGraphPubSubTypes.hpp @@ -32,10 +32,10 @@ #include "IDLGraph.hpp" -#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 // GEN_API_VER +#endif // FASTDDS_GEN_API_VER /*! @@ -54,38 +54,30 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -100,10 +92,6 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -124,8 +112,10 @@ class AttribPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -145,38 +135,30 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -191,10 +173,6 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -215,8 +193,10 @@ class PairIntPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -236,38 +216,30 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -282,10 +254,6 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -306,8 +274,10 @@ class DotContextPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -327,38 +297,30 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -373,10 +335,6 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -397,8 +355,10 @@ class DotKernelAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -418,38 +378,30 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -464,10 +416,6 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -488,8 +436,10 @@ class MvregEdgeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -509,38 +459,30 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -555,10 +497,6 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -579,8 +517,10 @@ class IDLEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -600,38 +540,30 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -646,10 +578,6 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -670,8 +598,10 @@ class EdgeKeyPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -691,38 +621,30 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -737,10 +659,6 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -761,8 +679,10 @@ class MvregNodeAttrPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -782,38 +702,30 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -828,10 +740,6 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -852,8 +760,10 @@ class DotKernelEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -873,38 +783,30 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -919,10 +821,6 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -943,8 +841,10 @@ class MvregEdgePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -964,38 +864,30 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1010,10 +902,6 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1034,8 +922,10 @@ class IDLNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1055,38 +945,30 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1101,10 +983,6 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1125,8 +1003,10 @@ class GraphRequestPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1146,38 +1026,30 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1192,10 +1064,6 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1216,8 +1084,10 @@ class DotKernelPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1237,38 +1107,30 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1283,10 +1145,6 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1307,8 +1165,10 @@ class MvregNodePubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1328,38 +1188,30 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1374,10 +1226,6 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1398,8 +1246,10 @@ class OrMapPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1419,38 +1269,30 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1465,10 +1307,6 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1489,8 +1327,10 @@ class MvregEdgeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; @@ -1510,38 +1350,30 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType eProsima_user_DllExport bool serialize( const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload) override - { - return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport bool serialize( - const void* const data, - eprosima::fastdds::rtps::SerializedPayload_t* payload, + 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, + eprosima::fastdds::rtps::SerializedPayload_t& payload, void* data) override; - eProsima_user_DllExport std::function getSerializedSizeProvider( - const void* const data) override - { - return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); - } - - eProsima_user_DllExport std::function getSerializedSizeProvider( + eProsima_user_DllExport uint32_t calculate_serialized_size( const void* const data, eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; - eProsima_user_DllExport bool getKey( + 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, + eprosima::fastdds::rtps::InstanceHandle_t& ihandle, bool force_md5 = false) override; - eProsima_user_DllExport void* createData() override; + eProsima_user_DllExport void* create_data() override; - eProsima_user_DllExport void deleteData( + eProsima_user_DllExport void delete_data( void* data) override; //Register TypeObject representation in Fast DDS TypeObjectRegistry @@ -1556,10 +1388,6 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_IS_BOUNDED #ifdef TOPIC_DATA_TYPE_API_HAS_IS_PLAIN - eProsima_user_DllExport inline bool is_plain() const override - { - return false; - } eProsima_user_DllExport inline bool is_plain( eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override @@ -1580,8 +1408,10 @@ class MvregNodeAttrVecPubSubType : public eprosima::fastdds::dds::TopicDataType #endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE - eprosima::fastdds::MD5 m_md5; - unsigned char* m_keyBuffer; +private: + + eprosima::fastdds::MD5 md5_; + unsigned char* key_buffer_; }; diff --git a/core/topics/IDLGraphCdrAux.ipp b/core/topics/IDLGraphCdrAux.ipp index 705973f2..e011c3ae 100644 --- a/core/topics/IDLGraphCdrAux.ipp +++ b/core/topics/IDLGraphCdrAux.ipp @@ -512,8 +512,17 @@ 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(); + } @@ -596,8 +605,13 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const PairInt& data) { + static_cast(scdr); static_cast(data); + scdr << data.first(); + + scdr << data.second(); + } @@ -680,8 +694,13 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const DotContext& data) { + static_cast(scdr); static_cast(data); + scdr << data.cc(); + + scdr << data.dc(); + } @@ -764,8 +783,17 @@ 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()); + } @@ -896,8 +924,31 @@ 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(); + } @@ -1004,8 +1055,19 @@ 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(); + } @@ -1088,8 +1150,13 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const EdgeKey& data) { + static_cast(scdr); static_cast(data); + scdr << data.to(); + + scdr << data.type(); + } @@ -1204,8 +1271,27 @@ 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(); + } @@ -1288,8 +1374,17 @@ 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()); + } @@ -1412,8 +1507,29 @@ 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(); + } @@ -1528,8 +1644,21 @@ 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(); + } @@ -1612,8 +1741,13 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const GraphRequest& data) { + static_cast(scdr); static_cast(data); + scdr << data.from(); + + scdr << data.id(); + } @@ -1696,8 +1830,17 @@ 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()); + } @@ -1796,8 +1939,23 @@ 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(); + } @@ -1896,8 +2054,21 @@ 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()); + } @@ -1972,8 +2143,11 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const MvregEdgeAttrVec& data) { + static_cast(scdr); static_cast(data); + scdr << data.vec(); + } @@ -2048,8 +2222,11 @@ void serialize_key( eprosima::fastcdr::Cdr& scdr, const MvregNodeAttrVec& data) { + static_cast(scdr); static_cast(data); + scdr << data.vec(); + } diff --git a/core/topics/IDLGraphPubSubTypes.cxx b/core/topics/IDLGraphPubSubTypes.cxx index 6beb0b3d..ccc47db7 100644 --- a/core/topics/IDLGraphPubSubTypes.cxx +++ b/core/topics/IDLGraphPubSubTypes.cxx @@ -25,59 +25,48 @@ #include #include "dsr/core/topics/IDLGraphCdrAux.hpp" -//#include "IDLGraphTypeObjectSupport.hpp" - -using namespace IDL; - using SerializedPayload_t = eprosima::fastdds::rtps::SerializedPayload_t; using InstanceHandle_t = eprosima::fastdds::rtps::InstanceHandle_t; -using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; +using namespace IDL;using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; AttribPubSubType::AttribPubSubType() { - setName("Attrib"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(Attrib::getMaxCdrSerializedSize()); -#else - Attrib_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = Attrib_max_key_cdr_typesize > 16 ? Attrib_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool AttribPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -92,16 +81,12 @@ bool AttribPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool AttribPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -110,18 +95,14 @@ bool AttribPubSubType::deserialize( Attrib* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -134,52 +115,62 @@ bool AttribPubSubType::deserialize( return true; } -std::function AttribPubSubType::getSerializedSizeProvider( +uint32_t AttribPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* AttribPubSubType::createData() + 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::deleteData( +void AttribPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool AttribPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -187,35 +178,28 @@ bool AttribPubSubType::getKey( const Attrib* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || Attrib_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -223,54 +207,48 @@ bool AttribPubSubType::getKey( void AttribPubSubType::register_type_object_representation() { - //register_Attrib_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } PairIntPubSubType::PairIntPubSubType() { - setName("PairInt"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(PairInt::getMaxCdrSerializedSize()); -#else - PairInt_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = PairInt_max_key_cdr_typesize > 16 ? PairInt_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool PairIntPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -285,16 +263,12 @@ bool PairIntPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool PairIntPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -303,18 +277,14 @@ bool PairIntPubSubType::deserialize( PairInt* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -327,52 +297,62 @@ bool PairIntPubSubType::deserialize( return true; } -std::function PairIntPubSubType::getSerializedSizeProvider( +uint32_t PairIntPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* PairIntPubSubType::createData() + 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::deleteData( +void PairIntPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool PairIntPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -380,35 +360,28 @@ bool PairIntPubSubType::getKey( const PairInt* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || PairInt_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -416,54 +389,48 @@ bool PairIntPubSubType::getKey( void PairIntPubSubType::register_type_object_representation() { - //register_PairInt_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } DotContextPubSubType::DotContextPubSubType() { - setName("DotContext"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(DotContext::getMaxCdrSerializedSize()); -#else - DotContext_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = DotContext_max_key_cdr_typesize > 16 ? DotContext_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool DotContextPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -478,16 +445,12 @@ bool DotContextPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool DotContextPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -496,18 +459,14 @@ bool DotContextPubSubType::deserialize( DotContext* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -520,52 +479,62 @@ bool DotContextPubSubType::deserialize( return true; } -std::function DotContextPubSubType::getSerializedSizeProvider( +uint32_t DotContextPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* DotContextPubSubType::createData() + 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::deleteData( +void DotContextPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool DotContextPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -573,35 +542,28 @@ bool DotContextPubSubType::getKey( const DotContext* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotContext_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -609,54 +571,48 @@ bool DotContextPubSubType::getKey( void DotContextPubSubType::register_type_object_representation() { - //register_DotContext_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } DotKernelAttrPubSubType::DotKernelAttrPubSubType() { - setName("DotKernelAttr"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(DotKernelAttr::getMaxCdrSerializedSize()); -#else - DotKernelAttr_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = DotKernelAttr_max_key_cdr_typesize > 16 ? DotKernelAttr_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool DotKernelAttrPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -671,16 +627,12 @@ bool DotKernelAttrPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool DotKernelAttrPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -689,18 +641,14 @@ bool DotKernelAttrPubSubType::deserialize( DotKernelAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -713,52 +661,62 @@ bool DotKernelAttrPubSubType::deserialize( return true; } -std::function DotKernelAttrPubSubType::getSerializedSizeProvider( +uint32_t DotKernelAttrPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* DotKernelAttrPubSubType::createData() + 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::deleteData( +void DotKernelAttrPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool DotKernelAttrPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -766,35 +724,28 @@ bool DotKernelAttrPubSubType::getKey( const DotKernelAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernelAttr_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -802,54 +753,48 @@ bool DotKernelAttrPubSubType::getKey( void DotKernelAttrPubSubType::register_type_object_representation() { - //register_DotKernelAttr_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregEdgeAttrPubSubType::MvregEdgeAttrPubSubType() { - setName("MvregEdgeAttr"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregEdgeAttr::getMaxCdrSerializedSize()); -#else - MvregEdgeAttr_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregEdgeAttr_max_key_cdr_typesize > 16 ? MvregEdgeAttr_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregEdgeAttrPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -864,16 +809,12 @@ bool MvregEdgeAttrPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregEdgeAttrPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -882,18 +823,14 @@ bool MvregEdgeAttrPubSubType::deserialize( MvregEdgeAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -906,52 +843,62 @@ bool MvregEdgeAttrPubSubType::deserialize( return true; } -std::function MvregEdgeAttrPubSubType::getSerializedSizeProvider( +uint32_t MvregEdgeAttrPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregEdgeAttrPubSubType::createData() + 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::deleteData( +void MvregEdgeAttrPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregEdgeAttrPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -959,35 +906,28 @@ bool MvregEdgeAttrPubSubType::getKey( const MvregEdgeAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdgeAttr_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -995,54 +935,48 @@ bool MvregEdgeAttrPubSubType::getKey( void MvregEdgeAttrPubSubType::register_type_object_representation() { - //register_MvregEdgeAttr_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } IDLEdgePubSubType::IDLEdgePubSubType() { - setName("IDLEdge"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(IDLEdge::getMaxCdrSerializedSize()); -#else - IDLEdge_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = IDLEdge_max_key_cdr_typesize > 16 ? IDLEdge_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool IDLEdgePubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1057,16 +991,12 @@ bool IDLEdgePubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool IDLEdgePubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -1075,18 +1005,14 @@ bool IDLEdgePubSubType::deserialize( IDLEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -1099,52 +1025,62 @@ bool IDLEdgePubSubType::deserialize( return true; } -std::function IDLEdgePubSubType::getSerializedSizeProvider( +uint32_t IDLEdgePubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* IDLEdgePubSubType::createData() + 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::deleteData( +void IDLEdgePubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool IDLEdgePubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -1152,35 +1088,28 @@ bool IDLEdgePubSubType::getKey( const IDLEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || IDLEdge_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -1188,54 +1117,48 @@ bool IDLEdgePubSubType::getKey( void IDLEdgePubSubType::register_type_object_representation() { - //register_IDLEdge_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } EdgeKeyPubSubType::EdgeKeyPubSubType() { - setName("EdgeKey"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(EdgeKey::getMaxCdrSerializedSize()); -#else - EdgeKey_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = EdgeKey_max_key_cdr_typesize > 16 ? EdgeKey_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool EdgeKeyPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1250,16 +1173,12 @@ bool EdgeKeyPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool EdgeKeyPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -1268,18 +1187,14 @@ bool EdgeKeyPubSubType::deserialize( EdgeKey* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -1292,52 +1207,62 @@ bool EdgeKeyPubSubType::deserialize( return true; } -std::function EdgeKeyPubSubType::getSerializedSizeProvider( +uint32_t EdgeKeyPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* EdgeKeyPubSubType::createData() + 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::deleteData( +void EdgeKeyPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool EdgeKeyPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -1345,35 +1270,28 @@ bool EdgeKeyPubSubType::getKey( const EdgeKey* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || EdgeKey_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -1381,54 +1299,48 @@ bool EdgeKeyPubSubType::getKey( void EdgeKeyPubSubType::register_type_object_representation() { - //register_EdgeKey_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregNodeAttrPubSubType::MvregNodeAttrPubSubType() { - setName("MvregNodeAttr"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregNodeAttr::getMaxCdrSerializedSize()); -#else - MvregNodeAttr_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregNodeAttr_max_key_cdr_typesize > 16 ? MvregNodeAttr_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregNodeAttrPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1443,16 +1355,12 @@ bool MvregNodeAttrPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregNodeAttrPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -1461,18 +1369,14 @@ bool MvregNodeAttrPubSubType::deserialize( MvregNodeAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -1485,52 +1389,62 @@ bool MvregNodeAttrPubSubType::deserialize( return true; } -std::function MvregNodeAttrPubSubType::getSerializedSizeProvider( +uint32_t MvregNodeAttrPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregNodeAttrPubSubType::createData() + 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::deleteData( +void MvregNodeAttrPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregNodeAttrPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -1538,35 +1452,28 @@ bool MvregNodeAttrPubSubType::getKey( const MvregNodeAttr* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNodeAttr_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -1574,54 +1481,48 @@ bool MvregNodeAttrPubSubType::getKey( void MvregNodeAttrPubSubType::register_type_object_representation() { - //register_MvregNodeAttr_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } DotKernelEdgePubSubType::DotKernelEdgePubSubType() { - setName("DotKernelEdge"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(DotKernelEdge::getMaxCdrSerializedSize()); -#else - DotKernelEdge_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = DotKernelEdge_max_key_cdr_typesize > 16 ? DotKernelEdge_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool DotKernelEdgePubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1636,16 +1537,12 @@ bool DotKernelEdgePubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool DotKernelEdgePubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -1654,18 +1551,14 @@ bool DotKernelEdgePubSubType::deserialize( DotKernelEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -1678,52 +1571,62 @@ bool DotKernelEdgePubSubType::deserialize( return true; } -std::function DotKernelEdgePubSubType::getSerializedSizeProvider( +uint32_t DotKernelEdgePubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* DotKernelEdgePubSubType::createData() + 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::deleteData( +void DotKernelEdgePubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool DotKernelEdgePubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -1731,35 +1634,28 @@ bool DotKernelEdgePubSubType::getKey( const DotKernelEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernelEdge_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -1767,54 +1663,48 @@ bool DotKernelEdgePubSubType::getKey( void DotKernelEdgePubSubType::register_type_object_representation() { - //register_DotKernelEdge_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregEdgePubSubType::MvregEdgePubSubType() { - setName("MvregEdge"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregEdge::getMaxCdrSerializedSize()); -#else - MvregEdge_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregEdge_max_key_cdr_typesize > 16 ? MvregEdge_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregEdgePubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -1829,16 +1719,12 @@ bool MvregEdgePubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregEdgePubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -1847,18 +1733,14 @@ bool MvregEdgePubSubType::deserialize( MvregEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -1871,52 +1753,62 @@ bool MvregEdgePubSubType::deserialize( return true; } -std::function MvregEdgePubSubType::getSerializedSizeProvider( +uint32_t MvregEdgePubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregEdgePubSubType::createData() + 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::deleteData( +void MvregEdgePubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregEdgePubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -1924,35 +1816,28 @@ bool MvregEdgePubSubType::getKey( const MvregEdge* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdge_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -1960,54 +1845,48 @@ bool MvregEdgePubSubType::getKey( void MvregEdgePubSubType::register_type_object_representation() { - //register_MvregEdge_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } IDLNodePubSubType::IDLNodePubSubType() { - setName("IDLNode"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(IDLNode::getMaxCdrSerializedSize()); -#else - IDLNode_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = IDLNode_max_key_cdr_typesize > 16 ? IDLNode_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool IDLNodePubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2022,16 +1901,12 @@ bool IDLNodePubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool IDLNodePubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -2040,18 +1915,14 @@ bool IDLNodePubSubType::deserialize( IDLNode* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -2064,52 +1935,62 @@ bool IDLNodePubSubType::deserialize( return true; } -std::function IDLNodePubSubType::getSerializedSizeProvider( +uint32_t IDLNodePubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* IDLNodePubSubType::createData() + 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::deleteData( +void IDLNodePubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool IDLNodePubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -2117,35 +1998,28 @@ bool IDLNodePubSubType::getKey( const IDLNode* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || IDLNode_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -2153,54 +2027,48 @@ bool IDLNodePubSubType::getKey( void IDLNodePubSubType::register_type_object_representation() { - //register_IDLNode_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } GraphRequestPubSubType::GraphRequestPubSubType() { - setName("GraphRequest"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(GraphRequest::getMaxCdrSerializedSize()); -#else - GraphRequest_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = GraphRequest_max_key_cdr_typesize > 16 ? GraphRequest_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool GraphRequestPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2215,16 +2083,12 @@ bool GraphRequestPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool GraphRequestPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -2233,18 +2097,14 @@ bool GraphRequestPubSubType::deserialize( GraphRequest* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -2257,52 +2117,62 @@ bool GraphRequestPubSubType::deserialize( return true; } -std::function GraphRequestPubSubType::getSerializedSizeProvider( +uint32_t GraphRequestPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* GraphRequestPubSubType::createData() + 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::deleteData( +void GraphRequestPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool GraphRequestPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -2310,35 +2180,28 @@ bool GraphRequestPubSubType::getKey( const GraphRequest* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || GraphRequest_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -2346,54 +2209,48 @@ bool GraphRequestPubSubType::getKey( void GraphRequestPubSubType::register_type_object_representation() { - //register_GraphRequest_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } DotKernelPubSubType::DotKernelPubSubType() { - setName("DotKernel"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(DotKernel::getMaxCdrSerializedSize()); -#else - DotKernel_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = DotKernel_max_key_cdr_typesize > 16 ? DotKernel_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool DotKernelPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2408,16 +2265,12 @@ bool DotKernelPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool DotKernelPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -2426,18 +2279,14 @@ bool DotKernelPubSubType::deserialize( DotKernel* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -2450,52 +2299,62 @@ bool DotKernelPubSubType::deserialize( return true; } -std::function DotKernelPubSubType::getSerializedSizeProvider( +uint32_t DotKernelPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* DotKernelPubSubType::createData() + 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::deleteData( +void DotKernelPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool DotKernelPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -2503,35 +2362,28 @@ bool DotKernelPubSubType::getKey( const DotKernel* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || DotKernel_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -2539,54 +2391,48 @@ bool DotKernelPubSubType::getKey( void DotKernelPubSubType::register_type_object_representation() { - //register_DotKernel_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregNodePubSubType::MvregNodePubSubType() { - setName("MvregNode"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregNode::getMaxCdrSerializedSize()); -#else - MvregNode_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregNode_max_key_cdr_typesize > 16 ? MvregNode_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregNodePubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2601,16 +2447,12 @@ bool MvregNodePubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregNodePubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -2619,18 +2461,14 @@ bool MvregNodePubSubType::deserialize( MvregNode* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -2643,52 +2481,62 @@ bool MvregNodePubSubType::deserialize( return true; } -std::function MvregNodePubSubType::getSerializedSizeProvider( +uint32_t MvregNodePubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregNodePubSubType::createData() + 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::deleteData( +void MvregNodePubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregNodePubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -2696,35 +2544,28 @@ bool MvregNodePubSubType::getKey( const MvregNode* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNode_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -2732,54 +2573,48 @@ bool MvregNodePubSubType::getKey( void MvregNodePubSubType::register_type_object_representation() { - //register_MvregNode_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } OrMapPubSubType::OrMapPubSubType() { - setName("OrMap"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(OrMap::getMaxCdrSerializedSize()); -#else - OrMap_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = OrMap_max_key_cdr_typesize > 16 ? OrMap_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool OrMapPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2794,16 +2629,12 @@ bool OrMapPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool OrMapPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -2812,18 +2643,14 @@ bool OrMapPubSubType::deserialize( OrMap* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -2836,52 +2663,62 @@ bool OrMapPubSubType::deserialize( return true; } -std::function OrMapPubSubType::getSerializedSizeProvider( +uint32_t OrMapPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* OrMapPubSubType::createData() + 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::deleteData( +void OrMapPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool OrMapPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -2889,35 +2726,28 @@ bool OrMapPubSubType::getKey( const OrMap* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || OrMap_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -2925,54 +2755,48 @@ bool OrMapPubSubType::getKey( void OrMapPubSubType::register_type_object_representation() { - //register_OrMap_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregEdgeAttrVecPubSubType::MvregEdgeAttrVecPubSubType() { - setName("MvregEdgeAttrVec"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregEdgeAttrVec::getMaxCdrSerializedSize()); -#else - MvregEdgeAttrVec_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregEdgeAttrVec_max_key_cdr_typesize > 16 ? MvregEdgeAttrVec_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregEdgeAttrVecPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -2987,16 +2811,12 @@ bool MvregEdgeAttrVecPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregEdgeAttrVecPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -3005,18 +2825,14 @@ bool MvregEdgeAttrVecPubSubType::deserialize( MvregEdgeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -3029,52 +2845,62 @@ bool MvregEdgeAttrVecPubSubType::deserialize( return true; } -std::function MvregEdgeAttrVecPubSubType::getSerializedSizeProvider( +uint32_t MvregEdgeAttrVecPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregEdgeAttrVecPubSubType::createData() + 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::deleteData( +void MvregEdgeAttrVecPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregEdgeAttrVecPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -3082,35 +2908,28 @@ bool MvregEdgeAttrVecPubSubType::getKey( const MvregEdgeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregEdgeAttrVec_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -3118,54 +2937,48 @@ bool MvregEdgeAttrVecPubSubType::getKey( void MvregEdgeAttrVecPubSubType::register_type_object_representation() { - //register_MvregEdgeAttrVec_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } MvregNodeAttrVecPubSubType::MvregNodeAttrVecPubSubType() { - setName("MvregNodeAttrVec"); - uint32_t type_size = -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(MvregNodeAttrVec::getMaxCdrSerializedSize()); -#else - MvregNodeAttrVec_max_cdr_typesize; -#endif + 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 */ - m_typeSize = type_size + 4; /*encapsulation*/ - m_isGetKeyDefined = false; - uint32_t keyLength = MvregNodeAttrVec_max_key_cdr_typesize > 16 ? MvregNodeAttrVec_max_key_cdr_typesize : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); + 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 (m_keyBuffer != nullptr) + if (key_buffer_ != nullptr) { - free(m_keyBuffer); + free(key_buffer_); } } bool MvregNodeAttrVecPubSubType::serialize( const void* const data, - SerializedPayload_t* payload, + 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); + 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; -#if FASTCDR_VERSION_MAJOR > 1 + 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); -#endif // FASTCDR_VERSION_MAJOR > 1 try { @@ -3180,16 +2993,12 @@ bool MvregNodeAttrVecPubSubType::serialize( } // Get the serialized length -#if FASTCDR_VERSION_MAJOR == 1 - payload->length = static_cast(ser.getSerializedDataLength()); -#else - payload->length = static_cast(ser.get_serialized_data_length()); -#endif // FASTCDR_VERSION_MAJOR == 1 + payload.length = static_cast(ser.get_serialized_data_length()); return true; } bool MvregNodeAttrVecPubSubType::deserialize( - SerializedPayload_t* payload, + SerializedPayload_t& payload, void* data) { try @@ -3198,18 +3007,14 @@ bool MvregNodeAttrVecPubSubType::deserialize( MvregNodeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(payload->data), payload->length); + 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 -#if FASTCDR_VERSION_MAJOR == 1 - , eprosima::fastcdr::Cdr::CdrType::DDS_CDR -#endif // FASTCDR_VERSION_MAJOR == 1 - ); + 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; + payload.encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; // Deserialize the object. deser >> *p_type; @@ -3222,52 +3027,62 @@ bool MvregNodeAttrVecPubSubType::deserialize( return true; } -std::function MvregNodeAttrVecPubSubType::getSerializedSizeProvider( +uint32_t MvregNodeAttrVecPubSubType::calculate_serialized_size( const void* const data, DataRepresentationId_t data_representation) { - return [data, data_representation]() -> uint32_t - { -#if FASTCDR_VERSION_MAJOR == 1 - static_cast(data_representation); - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; -#else - 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; - } -#endif // FASTCDR_VERSION_MAJOR == 1 - }; -} - -void* MvregNodeAttrVecPubSubType::createData() + 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::deleteData( +void MvregNodeAttrVecPubSubType::delete_data( void* data) { delete(reinterpret_cast(data)); } -bool MvregNodeAttrVecPubSubType::getKey( +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, + InstanceHandle_t& handle, bool force_md5) { - if (!m_isGetKeyDefined) + if (!is_compute_key_provided) { return false; } @@ -3275,35 +3090,28 @@ bool MvregNodeAttrVecPubSubType::getKey( const MvregNodeAttrVec* p_type = static_cast(data); // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), + 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::XCDRv1); -#if FASTCDR_VERSION_MAJOR == 1 - p_type->serializeKey(ser); -#else + 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); -#endif // FASTCDR_VERSION_MAJOR == 1 if (force_md5 || MvregNodeAttrVec_max_key_cdr_typesize > 16) { - m_md5.init(); -#if FASTCDR_VERSION_MAJOR == 1 - m_md5.update(m_keyBuffer, static_cast(ser.getSerializedDataLength())); -#else - m_md5.update(m_keyBuffer, static_cast(ser.get_serialized_data_length())); -#endif // FASTCDR_VERSION_MAJOR == 1 - m_md5.finalize(); + 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] = m_md5.digest[i]; + handle.value[i] = md5_.digest[i]; } } else { for (uint8_t i = 0; i < 16; ++i) { - handle->value[i] = m_keyBuffer[i]; + handle.value[i] = key_buffer_[i]; } } return true; @@ -3311,7 +3119,8 @@ bool MvregNodeAttrVecPubSubType::getKey( void MvregNodeAttrVecPubSubType::register_type_object_representation() { - //register_MvregNodeAttrVec_type_identifier(type_identifiers_); + EPROSIMA_LOG_WARNING(XTYPES_TYPE_REPRESENTATION, + "TypeObject type representation support disabled in generated code"); } diff --git a/core/topics/regenidl.md b/core/topics/regenidl.md new file mode 100644 index 00000000..1e9388df --- /dev/null +++ b/core/topics/regenidl.md @@ -0,0 +1,50 @@ +``` 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; + } +``` + From 8ab1e83f5b3ecd2d23f0e94d8984b5d65fec0591 Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Thu, 24 Oct 2024 16:57:22 +0200 Subject: [PATCH 4/8] [DSR] fix compatibility with fastdds3.0 --- api/dsr_api.cpp | 19 +++++++------- api/include/dsr/api/dsr_api.h | 10 +++++--- core/include/dsr/core/rtps/dsrparticipant.h | 28 +++++++++++---------- core/include/dsr/core/rtps/dsrpublisher.h | 3 --- core/include/dsr/core/rtps/dsrsubscriber.h | 2 -- core/rtps/dsrparticipant.cpp | 4 +-- core/rtps/dsrsubscriber.cpp | 3 +-- 7 files changed, 34 insertions(+), 35 deletions(-) diff --git a/api/dsr_api.cpp b/api/dsr_api.cpp index 942d4d07..4ecc6faf 100644 --- a/api/dsr_api.cpp +++ b/api/dsr_api.cpp @@ -41,21 +41,22 @@ DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_f // RTPS Create participant auto[suc, participant_handle] = dsrparticipant.init(agent_id, agent_name, all_same_host, ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph, - eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info) + eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, + const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) { - if (info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::DISCOVERED_PARTICIPANT) + if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT) { std::unique_lock lck(participant_set_mutex); - std::cout << "Participant matched [" <participant_set.insert({info.info.m_participantName.to_string(), false}); + std::cout << "Participant matched [" << info.participant_name.to_string() << "]" << std::endl; + graph->participant_set.emplace(info.participant_name.to_string(), false); } - else if (info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::REMOVED_PARTICIPANT || - info.status == eprosima::fastdds::rtps::ParticipantDiscoveryInfo::DROPPED_PARTICIPANT) + 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.info.m_participantName.to_string()); - std::cout << "Participant unmatched [" <delete_node(info.info.m_participantName.to_string()); + graph->participant_set.erase(info.participant_name.to_string()); + std::cout << "Participant unmatched [" << info.participant_name.to_string() << "]" << std::endl; + graph->delete_node(info.participant_name.to_string()); } })); diff --git a/api/include/dsr/api/dsr_api.h b/api/include/dsr/api/dsr_api.h index 7508671b..40babd88 100644 --- a/api/include/dsr/api/dsr_api.h +++ b/api/include/dsr/api/dsr_api.h @@ -631,17 +631,19 @@ namespace DSR class ParticipantChangeFunctor { public: DSRGraph *graph{}; - std::function f; + std::function f; ParticipantChangeFunctor(DSRGraph *graph_, - std::function f_) + std::function f_) : graph(graph_), f(std::move(f_)) {} ParticipantChangeFunctor() = default; - void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info) const + void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, + const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) const { - f(graph, std::forward(info)); + f(graph, status, info); }; }; diff --git a/core/include/dsr/core/rtps/dsrparticipant.h b/core/include/dsr/core/rtps/dsrparticipant.h index 82bf57ae..c985e918 100644 --- a/core/include/dsr/core/rtps/dsrparticipant.h +++ b/core/include/dsr/core/rtps/dsrparticipant.h @@ -2,11 +2,10 @@ #define _PARTICIPANT_H_ #include -#include -#include #include #include #include +#include #include #include @@ -17,14 +16,14 @@ class DSRParticipant public: DSRParticipant(); virtual ~DSRParticipant(); - [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn); + [[nodiscard]] std::tuple init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn); [[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const; - [[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->getName();} - [[nodiscard]] const char *getRequestTopicName() const { return graphrequestType->getName();} - [[nodiscard]] const char *getAnswerTopicName() const { return graphRequestAnswerType->getName();} - [[nodiscard]] const char *getEdgeTopicName() const { return dsrEdgeType->getName();} - [[nodiscard]] const char *getNodeAttrTopicName() const { return dsrNodeAttrType->getName();} - [[nodiscard]] const char *getEdgeAttrTopicName() const { return dsrEdgeAttrType->getName();} + [[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->get_name().data();} + [[nodiscard]] const char *getRequestTopicName() const { return graphrequestType->get_name().data();} + [[nodiscard]] const char *getAnswerTopicName() const { return graphRequestAnswerType->get_name().data();} + [[nodiscard]] const char *getEdgeTopicName() const { return dsrEdgeType->get_name().data();} + [[nodiscard]] const char *getNodeAttrTopicName() const { return dsrNodeAttrType->get_name().data();} + [[nodiscard]] const char *getEdgeAttrTopicName() const { return dsrEdgeAttrType->get_name().data();} [[nodiscard]] eprosima::fastdds::dds::Topic* getNodeTopic() { return topic_node; } [[nodiscard]] eprosima::fastdds::dds::Topic* getEdgeTopic() { return topic_edge; } @@ -66,21 +65,24 @@ class DSRParticipant class ParticpantListener : public eprosima::fastdds::dds::DomainParticipantListener { public: - explicit ParticpantListener(std::function&& fn) + explicit ParticpantListener(std::function&& fn) : eprosima::fastdds::dds::DomainParticipantListener(), f(std::move(fn)){}; ~ParticpantListener() override = default; void on_participant_discovery ( eprosima::fastdds::dds::DomainParticipant* participant, - eprosima::fastdds::rtps::ParticipantDiscoveryInfo&& info, + eprosima::fastdds::rtps::ParticipantDiscoveryStatus status, + const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info, bool& should_be_ignored) override { //Callback - f(std::forward(info)); + f(status, info); } - std::function f; + std::function 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 e542e6b0..a55f000a 100644 --- a/core/include/dsr/core/rtps/dsrpublisher.h +++ b/core/include/dsr/core/rtps/dsrpublisher.h @@ -3,14 +3,11 @@ #include -#include -#include #include #include #include #include #include -#include #include diff --git a/core/include/dsr/core/rtps/dsrsubscriber.h b/core/include/dsr/core/rtps/dsrsubscriber.h index fc7dc255..d51f3177 100644 --- a/core/include/dsr/core/rtps/dsrsubscriber.h +++ b/core/include/dsr/core/rtps/dsrsubscriber.h @@ -3,9 +3,7 @@ #include #include -#include #include -#include #include diff --git a/core/rtps/dsrparticipant.cpp b/core/rtps/dsrparticipant.cpp index 95bf6dbf..745e8c0b 100644 --- a/core/rtps/dsrparticipant.cpp +++ b/core/rtps/dsrparticipant.cpp @@ -30,7 +30,7 @@ DSRParticipant::~DSRParticipant() } -std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn) +std::tuple DSRParticipant::init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function fn) { // Create RTPSParticipant DomainParticipantQos PParam; @@ -80,7 +80,7 @@ std::tuple DSRParticipant::ini PParam.wire_protocol().builtin.discovery_config.leaseDuration = /*eprosima::fastdds::c_TimeInfinite;*/ Duration_t(6); PParam.wire_protocol().builtin.discovery_config.leaseDuration_announcementperiod = - eprosima::fastdds::Duration_t(3, 0); + eprosima::fastdds::dds::Duration_t(3, 0); eprosima::fastdds::dds::Log::SetVerbosity(eprosima::fastdds::dds::Log::Info); diff --git a/core/rtps/dsrsubscriber.cpp b/core/rtps/dsrsubscriber.cpp index 5ab6eadd..68dc334a 100644 --- a/core/rtps/dsrsubscriber.cpp +++ b/core/rtps/dsrsubscriber.cpp @@ -17,8 +17,7 @@ using namespace eprosima::fastdds::rtps; DSRSubscriber::DSRSubscriber() : mp_participant(nullptr), mp_subscriber(nullptr), mp_reader(nullptr) {} DSRSubscriber::~DSRSubscriber() -{ -} += default; std::tuple DSRSubscriber::init(eprosima::fastdds::dds::DomainParticipant *mp_participant_, From 469fef9b59b070e84f90c3dedda0060dc8caac06 Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Thu, 24 Oct 2024 17:04:07 +0200 Subject: [PATCH 5/8] fixup! [DSR] regenerate IDL --- core/topics/regenidl.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/core/topics/regenidl.md b/core/topics/regenidl.md index 1e9388df..9a32e8a6 100644 --- a/core/topics/regenidl.md +++ b/core/topics/regenidl.md @@ -3,7 +3,7 @@ cd ~/software/Fast-DDS-Gen git pull ./gradlew clean ./gradlew jar -mv ./build/libs/fastddsgen.jar ./share/fastddsgen/ java/fastddsgen.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 From 6ff0f1dce32cb9f90246c219b2d8d3ffa1b021e6 Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Mon, 28 Oct 2024 11:49:03 +0100 Subject: [PATCH 6/8] [Cmake] replace fastrtps with fastddps --- api/CMakeLists.txt | 2 +- gui/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/api/CMakeLists.txt b/api/CMakeLists.txt index 3083e74f..ff5fe371 100644 --- a/api/CMakeLists.txt +++ b/api/CMakeLists.txt @@ -56,7 +56,7 @@ target_sources(dsr_api target_link_libraries(dsr_api PRIVATE - fastcdr fastrtps + fastcdr fastdds osgDB OpenThreads Qt6::Core PUBLIC diff --git a/gui/CMakeLists.txt b/gui/CMakeLists.txt index 114c0c3b..235aa29f 100644 --- a/gui/CMakeLists.txt +++ b/gui/CMakeLists.txt @@ -86,7 +86,7 @@ target_link_libraries(dsr_gui osgViewer osgDB osgGA OpenThreads PUBLIC Qt6::OpenGL - fastrtps + fastdds ${qt3d_libs} ) From 19eb1f8ccb6f303a3db64bd2bab1beb8d03182ca Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Mon, 28 Oct 2024 11:59:55 +0100 Subject: [PATCH 7/8] [CI/Install] install qt6-base-dev instead of qtbase5-dev in dependencies.sh --- dependencies.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dependencies.sh b/dependencies.sh index 1b283324..01c5f7e7 100644 --- a/dependencies.sh +++ b/dependencies.sh @@ -3,7 +3,7 @@ branch="${1:-development}" sudo apt install -y curl curl -O https://raw.githubusercontent.com/robocomp/robocomp/$branch/classes/threadpool/threadpool.h && sudo mkdir -p /usr/include/threadpool && sudo mv threadpool.h /usr/include/threadpool -sudo apt install qtbase5-dev +sudo apt install qt6-base-dev sudo apt-get install -y libopenscenegraph-dev sudo apt install libasio-dev sudo apt install libtinyxml2-dev From ea8ffdc34c91fbf2f617716b00c23f7392fda0b9 Mon Sep 17 00:00:00 2001 From: juancarlosgg Date: Mon, 28 Oct 2024 12:15:34 +0100 Subject: [PATCH 8/8] [CI] replace old link in dependencies.sh --- dependencies.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dependencies.sh b/dependencies.sh index 01c5f7e7..ff5faabb 100644 --- a/dependencies.sh +++ b/dependencies.sh @@ -2,7 +2,7 @@ # Please make sure that bin/bash is the location of your bash terminal,if not please replace with your local machine's bash path branch="${1:-development}" sudo apt install -y curl -curl -O https://raw.githubusercontent.com/robocomp/robocomp/$branch/classes/threadpool/threadpool.h && sudo mkdir -p /usr/include/threadpool && sudo mv threadpool.h /usr/include/threadpool +curl -O https://raw.githubusercontent.com/robocomp/robocomp_core/${branch}/classes/threadpool/threadpool.h && sudo mkdir -p /usr/include/threadpool && sudo mv threadpool.h /usr/include/threadpool sudo apt install qt6-base-dev sudo apt-get install -y libopenscenegraph-dev sudo apt install libasio-dev