Skip to content

Commit

Permalink
Merge pull request #6 from robocomp/fastdds3.0
Browse files Browse the repository at this point in the history
FastDDS 3.0 breaking changes
  • Loading branch information
JuanCarlosgg authored Nov 3, 2024
2 parents 95a5200 + ea8ffdc commit d6e4469
Show file tree
Hide file tree
Showing 29 changed files with 7,975 additions and 9,310 deletions.
2 changes: 1 addition & 1 deletion api/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ target_sources(dsr_api

target_link_libraries(dsr_api
PRIVATE
fastcdr fastrtps
fastcdr fastdds
osgDB OpenThreads
Qt6::Core
PUBLIC
Expand Down
2 changes: 1 addition & 1 deletion api/GHistorySaver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -832,4 +832,4 @@ void GSerializer::add_change(ChangeInfo && c)
total_size+=ser.size;
used_size+=ser.p;

}
}
37 changes: 19 additions & 18 deletions api/dsr_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include <utility>
#include <cmath>

#include <fastrtps/transport/UDPv4TransportDescriptor.h>
#include <fastrtps/Domain.h>
#include <fastdds/rtps/transport/UDPv4TransportDescriptor.hpp>
#include <fastdds/rtps/RTPSDomain.hpp>


#include <QtCore/qlogging.h>
Expand Down Expand Up @@ -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::fastrtps::rtps::ParticipantDiscoveryInfo&& info)
eprosima::fastdds::rtps::ParticipantDiscoveryStatus status,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info)
{
if (info.status == eprosima::fastrtps::rtps::ParticipantDiscoveryInfo::DISCOVERED_PARTICIPANT)
if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT)
{
std::unique_lock<std::mutex> lck(participant_set_mutex);
std::cout << "Participant matched [" <<info.info.m_participantName.to_string() << "]" << std::endl;
graph->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::fastrtps::rtps::ParticipantDiscoveryInfo::REMOVED_PARTICIPANT ||
info.status == eprosima::fastrtps::rtps::ParticipantDiscoveryInfo::DROPPED_PARTICIPANT)
else if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::REMOVED_PARTICIPANT ||
status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DROPPED_PARTICIPANT)
{
std::unique_lock<std::mutex> lck(participant_set_mutex);
graph->participant_set.erase(info.info.m_participantName.to_string());
std::cout << "Participant unmatched [" <<info.info.m_participantName.to_string() << "]" << std::endl;
graph->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());
}
}));

Expand Down Expand Up @@ -1532,7 +1533,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) {
Expand Down Expand Up @@ -1565,7 +1566,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) {
Expand Down Expand Up @@ -1599,7 +1600,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: "
Expand Down Expand Up @@ -1666,7 +1667,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: "
Expand Down Expand Up @@ -1730,7 +1731,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<std::mutex> lck(participant_set_mutex);
Expand Down Expand Up @@ -1785,7 +1786,7 @@ std::pair<bool, bool> 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<uint32_t>(-1)) {
Expand Down Expand Up @@ -1870,4 +1871,4 @@ std::unique_ptr<DSRGraph> DSRGraph::G_copy()
bool DSRGraph::is_copy() const
{
return copy;
}
}
12 changes: 7 additions & 5 deletions api/include/dsr/api/dsr_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -631,17 +631,19 @@ namespace DSR
class ParticipantChangeFunctor {
public:
DSRGraph *graph{};
std::function<void(DSRGraph *graph_,eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&)> f;
std::function<void(DSRGraph *graph_,eprosima::fastdds::rtps::ParticipantDiscoveryStatus, const eprosima::fastdds::rtps::ParticipantBuiltinTopicData&)> f;

ParticipantChangeFunctor(DSRGraph *graph_,
std::function<void(DSRGraph *graph_, eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&)> f_)
std::function<void(DSRGraph *graph_, eprosima::fastdds::rtps::ParticipantDiscoveryStatus,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData&)> f_)
: graph(graph_), f(std::move(f_)) {}

ParticipantChangeFunctor() = default;

void operator()(eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&& info) const
void operator()(eprosima::fastdds::rtps::ParticipantDiscoveryStatus status,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info) const
{
f(graph, std::forward<eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&>(info));
f(graph, status, info);
};
};

Expand Down
4 changes: 2 additions & 2 deletions api/include/dsr/api/dsr_camera_api.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef CAMERA_API
#define CAMERA_API

#include <dsr/core/topics/IDLGraphPubSubTypes.h>
#include <dsr/core/topics/IDLGraphPubSubTypes.hpp>
#include <dsr/core/types/user_types.h>
#include <Eigen/Dense>
#include <optional>
Expand Down Expand Up @@ -68,4 +68,4 @@ namespace DSR
};
}

#endif
#endif
3 changes: 2 additions & 1 deletion api/include/dsr/api/dsr_exceptions.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#define DSR_EXCEPTIONS

#include <exception>
#include <string>
#include <utility>

/////////////////////////////////////////////////////////////////
Expand All @@ -27,4 +28,4 @@ namespace DSR
std::string msg_;
};
}
#endif
#endif
7 changes: 5 additions & 2 deletions api/include/dsr/api/dsr_inner_eigen_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,13 @@
#define INNER_EIGEN_API

#include <QObject>
#include <dsr/core/topics/IDLGraphPubSubTypes.h>
#include <dsr/core/topics/IDLGraphPubSubTypes.hpp>
#include <dsr/api/dsr_eigen_defs.h>
#include <dsr/api/dsr_rt_api.h>
#include <optional>
#include <cstdint>
#include <tuple>
#include <map>

namespace DSR
{
Expand Down Expand Up @@ -52,4 +55,4 @@ namespace DSR
};
}

#endif
#endif
2 changes: 1 addition & 1 deletion api/include/dsr/api/dsr_rt_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include <cassert>
#include <QtCore>
#include <dsr/core/topics/IDLGraphPubSubTypes.h>
#include <dsr/core/topics/IDLGraphPubSubTypes.hpp>
#include <dsr/core/types/user_types.h>
#include <dsr/core/types/type_checking/dsr_attr_name.h>
#include <dsr/api/dsr_eigen_defs.h>
Expand Down
4 changes: 2 additions & 2 deletions api/include/dsr/api/dsr_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

#include <string>
#include <optional>
#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/api/dsr_exceptions.h>
Expand Down Expand Up @@ -37,4 +37,4 @@ namespace DSR
};
}

#endif
#endif
8 changes: 4 additions & 4 deletions core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
13 changes: 4 additions & 9 deletions core/include/dsr/core/crdt/delta_crdt.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,11 @@ Reimplementation from https://github.com/CBaquero/delta-enabled-crdts
#ifndef DELTA_CRDT
#define DELTA_CRDT

#include <set>
#include <unordered_set>
#include <map>
#include <list>
#include <tuple>
#include <vector>
#include <string>
#include <iostream>
#include <type_traits>
#include <cassert>
#include <cstdint>
#include <map>
#include <set>

using key_type = uint64_t;

Expand Down Expand Up @@ -468,4 +463,4 @@ class mvreg // Multi-value register, Optimized
};


#endif
#endif
38 changes: 20 additions & 18 deletions core/include/dsr/core/rtps/dsrparticipant.h
Original file line number Diff line number Diff line change
@@ -1,15 +1,13 @@
#ifndef _PARTICIPANT_H_
#define _PARTICIPANT_H_

#include <fastrtps/fastrtps_fwd.h>
#include <fastrtps/log/Log.h>
#include <fastdds/rtps/RTPSDomain.h>
#include <fastdds/dds/domain/DomainParticipantFactory.hpp>
#include <fastdds/dds/log/Log.hpp>
#include <fastdds/dds/topic/TypeSupport.hpp>
#include <fastdds/dds/domain/DomainParticipant.hpp>
#include <fastdds/dds/domain/DomainParticipantListener.hpp>
#include <fastdds/rtps/builtin/data/ParticipantBuiltinTopicData.hpp>

#include <dsr/core/topics/IDLGraphPubSubTypes.h>
#include <dsr/core/topics/IDLGraphPubSubTypes.hpp>
#include <dsr/core/rtps/dsrpublisher.h>
#include <dsr/core/rtps/dsrsubscriber.h>

Expand All @@ -18,14 +16,14 @@ class DSRParticipant
public:
DSRParticipant();
virtual ~DSRParticipant();
[[nodiscard]] std::tuple<bool, eprosima::fastdds::dds::DomainParticipant *> init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function<void(eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&)> fn);
[[nodiscard]] const eprosima::fastrtps::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]] std::tuple<bool, eprosima::fastdds::dds::DomainParticipant *> init(uint32_t agent_id, const std::string& agent_name, int localhost, std::function<void(eprosima::fastdds::rtps::ParticipantDiscoveryStatus, const eprosima::fastdds::rtps::ParticipantBuiltinTopicData&)> fn);
[[nodiscard]] const eprosima::fastdds::rtps::GUID_t& getID() const;
[[nodiscard]] const char *getNodeTopicName() const { return dsrgraphType->get_name().data();}
[[nodiscard]] const char *getRequestTopicName() const { return graphrequestType->get_name().data();}
[[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; }
Expand Down Expand Up @@ -67,23 +65,27 @@ class DSRParticipant
class ParticpantListener : public eprosima::fastdds::dds::DomainParticipantListener
{
public:
explicit ParticpantListener(std::function<void(eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&)>&& fn)
explicit ParticpantListener(std::function<void(eprosima::fastdds::rtps::ParticipantDiscoveryStatus,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData&)>&& 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::ParticipantDiscoveryStatus status,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info,
bool& should_be_ignored) override
{
//Callback
f(std::forward<eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&>(info));
f(status, info);
}


std::function<void(eprosima::fastrtps::rtps::ParticipantDiscoveryInfo&&)> f;
std::function<void(eprosima::fastdds::rtps::ParticipantDiscoveryStatus,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData&)> f;
//int n_matched;
};
std::unique_ptr<ParticpantListener> m_listener;
};

#endif // _Participant_H_
#endif // _Participant_H_
9 changes: 3 additions & 6 deletions core/include/dsr/core/rtps/dsrpublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,24 +3,21 @@


#include <fastdds/dds/domain/DomainParticipantFactory.hpp>
#include <fastdds/dds/subscriber/SampleInfo.hpp>
#include <fastdds/rtps/transport/UDPv4TransportDescriptor.h>
#include <fastdds/dds/domain/DomainParticipant.hpp>
#include <fastdds/dds/publisher/Publisher.hpp>
#include <fastdds/dds/topic/Topic.hpp>
#include <fastdds/dds/publisher/DataWriter.hpp>
#include <fastdds/dds/publisher/DataWriterListener.hpp>
#include <fastrtps/utils/IPLocator.h>

#include "../topics/IDLGraphPubSubTypes.h"
#include <dsr/core/topics/IDLGraphPubSubTypes.hpp>

class DSRPublisher
{
public:
DSRPublisher();
virtual ~DSRPublisher();
[[nodiscard]] std::tuple<bool, eprosima::fastdds::dds::Publisher*, eprosima::fastdds::dds::DataWriter*> 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);
Expand All @@ -45,4 +42,4 @@ class DSRPublisher

};

#endif // _PUBLISHER_H_
#endif // _PUBLISHER_H_
Loading

0 comments on commit d6e4469

Please sign in to comment.