From 7320a33d0947c9affe338784ca571e14265eaa0c Mon Sep 17 00:00:00 2001 From: "andrew.konecki" Date: Mon, 12 Feb 2018 14:28:52 -0800 Subject: [PATCH 1/2] update rmw_fastrtps to not rely on namespace escalation fron Fast-RTPS --- .../include/rmw_fastrtps_cpp/TypeSupport.hpp | 4 ++-- .../rmw_fastrtps_cpp/TypeSupport_impl.hpp | 8 ++++--- .../rmw_fastrtps_cpp/custom_client_info.hpp | 4 ++-- .../custom_participant_info.hpp | 15 ++++++++----- .../rmw_fastrtps_cpp/custom_service_info.hpp | 2 +- .../custom_subscriber_info.hpp | 2 +- .../include/rmw_fastrtps_cpp/reader_info.hpp | 17 ++++++++------ .../include/rmw_fastrtps_cpp/writer_info.hpp | 17 ++++++++------ rmw_fastrtps_cpp/src/assign_partitions.hpp | 4 ++-- rmw_fastrtps_cpp/src/demangle.cpp | 6 ++--- rmw_fastrtps_cpp/src/qos.cpp | 4 ++-- rmw_fastrtps_cpp/src/rmw_client.cpp | 20 +++++++++++------ rmw_fastrtps_cpp/src/rmw_node.cpp | 8 ++++++- rmw_fastrtps_cpp/src/rmw_node_names.cpp | 2 ++ rmw_fastrtps_cpp/src/rmw_publisher.cpp | 22 ++++++++++++------- rmw_fastrtps_cpp/src/rmw_service.cpp | 20 +++++++++++------ .../src/rmw_service_server_is_available.cpp | 4 ++-- rmw_fastrtps_cpp/src/rmw_subscription.cpp | 18 ++++++++++----- rmw_fastrtps_cpp/src/rmw_take.cpp | 4 ++-- 19 files changed, 112 insertions(+), 69 deletions(-) diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp index 115353f81..42fdc1eb1 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp @@ -115,9 +115,9 @@ class TypeSupport : public eprosima::fastrtps::TopicDataType bool deserializeROSmessage(eprosima::fastcdr::FastBuffer * data, void * ros_message); - bool serialize(void * data, SerializedPayload_t * payload); + bool serialize(void * data, eprosima::fastrtps::rtps::SerializedPayload_t * payload); - bool deserialize(SerializedPayload_t * payload, void * data); + bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t * payload, void * data); std::function getSerializedSizeProvider(void * data); diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport_impl.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport_impl.hpp index 9235761fd..1d263638d 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport_impl.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport_impl.hpp @@ -632,7 +632,7 @@ size_t TypeSupport::calculateMaxSerializedSize( if (member->is_array_) { array_size = member->array_size_; // Whether it is a sequence. - if (array_size == 0 || member->is_upper_bound_) { + if (0 == array_size || member->is_upper_bound_) { current_alignment += padding + eprosima::fastcdr::Cdr::alignment(current_alignment, padding); } @@ -738,7 +738,7 @@ void * TypeSupport::createData() template bool TypeSupport::serialize( - void * data, SerializedPayload_t * payload) + void * data, eprosima::fastrtps::rtps::SerializedPayload_t * payload) { assert(data); assert(payload); @@ -756,7 +756,9 @@ bool TypeSupport::serialize( } template -bool TypeSupport::deserialize(SerializedPayload_t * payload, void * data) +bool TypeSupport::deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t * payload, + void * data) { assert(data); assert(payload); diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_client_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_client_info.hpp index ea91da2b7..8f137ea6c 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_client_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_client_info.hpp @@ -67,10 +67,10 @@ class ClientListener : public eprosima::fastrtps::SubscriberListener eprosima::fastrtps::SampleInfo_t sinfo; if (sub->takeNextData(response.buffer_, &sinfo)) { - if (sinfo.sampleKind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == sinfo.sampleKind) { response.sample_identity_ = sinfo.related_sample_identity; - if (info_->writer_guid_ == response.sample_identity_.writer_guid()) { + if (response.sample_identity_.writer_guid() == info_->writer_guid_) { std::lock_guard lock(internalMutex_); if (conditionMutex_ != nullptr) { diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp index 804aea487..faac74fd0 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp @@ -29,6 +29,7 @@ #include "rmw_fastrtps_cpp/reader_info.hpp" #include "rmw_fastrtps_cpp/writer_info.hpp" + class ParticipantListener; typedef struct CustomParticipantInfo @@ -43,17 +44,19 @@ typedef struct CustomParticipantInfo class ParticipantListener : public eprosima::fastrtps::ParticipantListener { public: - void onParticipantDiscovery(Participant *, ParticipantDiscoveryInfo info) override + void onParticipantDiscovery( + eprosima::fastrtps::Participant *, + eprosima::fastrtps::ParticipantDiscoveryInfo info) override { if ( - info.rtps.m_status != DISCOVERED_RTPSPARTICIPANT && - info.rtps.m_status != REMOVED_RTPSPARTICIPANT && - info.rtps.m_status != DROPPED_RTPSPARTICIPANT) + info.rtps.m_status != eprosima::fastrtps::rtps::DISCOVERED_RTPSPARTICIPANT && + info.rtps.m_status != eprosima::fastrtps::rtps::REMOVED_RTPSPARTICIPANT && + info.rtps.m_status != eprosima::fastrtps::rtps::DROPPED_RTPSPARTICIPANT) { return; } - if (DISCOVERED_RTPSPARTICIPANT == info.rtps.m_status) { + if (eprosima::fastrtps::rtps::DISCOVERED_RTPSPARTICIPANT == info.rtps.m_status) { // ignore already known GUIDs if (discovered_names.find(info.rtps.m_guid) == discovered_names.end()) { auto map = rmw::impl::cpp::parse_key_value(info.rtps.m_userData); @@ -90,7 +93,7 @@ class ParticipantListener : public eprosima::fastrtps::ParticipantListener return names; } - std::map discovered_names; + std::map discovered_names; }; #endif // RMW_FASTRTPS_CPP__CUSTOM_PARTICIPANT_INFO_HPP_ diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_service_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_service_info.hpp index 935ff5ec9..0ca083c46 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_service_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_service_info.hpp @@ -70,7 +70,7 @@ class ServiceListener : public eprosima::fastrtps::SubscriberListener eprosima::fastrtps::SampleInfo_t sinfo; if (sub->takeNextData(request.buffer_, &sinfo)) { - if (sinfo.sampleKind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == sinfo.sampleKind) { request.sample_identity_ = sinfo.sample_identity; std::lock_guard lock(internalMutex_); diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_subscriber_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_subscriber_info.hpp index bcc263caf..c5047c0b7 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_subscriber_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_subscriber_info.hpp @@ -46,7 +46,7 @@ class SubListener : public eprosima::fastrtps::SubscriberListener void onSubscriptionMatched( - eprosima::fastrtps::Subscriber * sub, eprosima::fastrtps::MatchingInfo & info) + eprosima::fastrtps::Subscriber * sub, eprosima::fastrtps::rtps::MatchingInfo & info) { (void)sub; (void)info; diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/reader_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/reader_info.hpp index d34da275d..5862af49f 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/reader_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/reader_info.hpp @@ -33,7 +33,7 @@ #include "fastrtps/rtps/reader/ReaderListener.h" #include "fastrtps/rtps/reader/RTPSReader.h" -class ReaderInfo : public eprosima::fastrtps::ReaderListener +class ReaderInfo : public eprosima::fastrtps::rtps::ReaderListener { public: ReaderInfo( @@ -46,14 +46,17 @@ class ReaderInfo : public eprosima::fastrtps::ReaderListener void onNewCacheChangeAdded( eprosima::fastrtps::rtps::RTPSReader *, - const eprosima::fastrtps::CacheChange_t * const change) + const eprosima::fastrtps::rtps::CacheChange_t * const change) { eprosima::fastrtps::rtps::ReaderProxyData proxyData; - if (change->kind == ALIVE) { - CDRMessage_t tempMsg(0); + if (eprosima::fastrtps::rtps::ALIVE == change->kind) { + eprosima::fastrtps::rtps::CDRMessage_t tempMsg(0); tempMsg.wraps = true; - tempMsg.msg_endian = change->serializedPayload.encapsulation == - PL_CDR_BE ? BIGEND : LITTLEEND; + if (PL_CDR_BE == change->serializedPayload.encapsulation) { + tempMsg.msg_endian = eprosima::fastrtps::rtps::BIGEND; + } else { + tempMsg.msg_endian = eprosima::fastrtps::rtps::LITTLEEND; + } tempMsg.length = change->serializedPayload.length; tempMsg.max_size = change->serializedPayload.max_size; tempMsg.buffer = change->serializedPayload.data; @@ -77,7 +80,7 @@ class ReaderInfo : public eprosima::fastrtps::ReaderListener bool trigger = false; mapmutex.lock(); - if (change->kind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == change->kind) { topicNtypes[fqdn].push_back(proxyData.typeName()); trigger = true; } else { diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/writer_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/writer_info.hpp index f86d8d267..8a6f1e46c 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/writer_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/writer_info.hpp @@ -31,7 +31,7 @@ #include "rmw/rmw.h" -class WriterInfo : public eprosima::fastrtps::ReaderListener +class WriterInfo : public eprosima::fastrtps::rtps::ReaderListener { public: WriterInfo( @@ -44,14 +44,17 @@ class WriterInfo : public eprosima::fastrtps::ReaderListener void onNewCacheChangeAdded( eprosima::fastrtps::rtps::RTPSReader *, - const eprosima::fastrtps::CacheChange_t * const change) + const eprosima::fastrtps::rtps::CacheChange_t * const change) { eprosima::fastrtps::rtps::WriterProxyData proxyData; - if (change->kind == ALIVE) { - eprosima::fastrtps::CDRMessage_t tempMsg(0); + if (eprosima::fastrtps::rtps::ALIVE == change->kind) { + eprosima::fastrtps::rtps::CDRMessage_t tempMsg(0); tempMsg.wraps = true; - tempMsg.msg_endian = change->serializedPayload.encapsulation == - PL_CDR_BE ? BIGEND : LITTLEEND; + if (PL_CDR_BE == change->serializedPayload.encapsulation) { + tempMsg.msg_endian = eprosima::fastrtps::rtps::BIGEND; + } else { + tempMsg.msg_endian = eprosima::fastrtps::rtps::LITTLEEND; + } tempMsg.length = change->serializedPayload.length; tempMsg.max_size = change->serializedPayload.max_size; tempMsg.buffer = change->serializedPayload.data; @@ -75,7 +78,7 @@ class WriterInfo : public eprosima::fastrtps::ReaderListener bool trigger = false; mapmutex.lock(); - if (change->kind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == change->kind) { topicNtypes[fqdn].push_back(proxyData.typeName()); trigger = true; } else { diff --git a/rmw_fastrtps_cpp/src/assign_partitions.hpp b/rmw_fastrtps_cpp/src/assign_partitions.hpp index 6361cff48..c6c2fd764 100644 --- a/rmw_fastrtps_cpp/src/assign_partitions.hpp +++ b/rmw_fastrtps_cpp/src/assign_partitions.hpp @@ -44,13 +44,13 @@ _assign_partitions_to_attributes( RMW_SET_ERROR_MSG(rcutils_get_error_string_safe()); return ret; } - if (name_tokens.size == 1) { + if (1 == name_tokens.size) { if (!avoid_ros_namespace_conventions) { attributes->qos.m_partition.push_back(prefix); } attributes->topic.topicName = name_tokens.data[0]; ret = RCUTILS_RET_OK; - } else if (name_tokens.size == 2) { + } else if (2 == name_tokens.size) { std::string partition; if (avoid_ros_namespace_conventions) { // no prefix to be used, just assign the user's namespace diff --git a/rmw_fastrtps_cpp/src/demangle.cpp b/rmw_fastrtps_cpp/src/demangle.cpp index 2c1c3a57f..2741384b3 100644 --- a/rmw_fastrtps_cpp/src/demangle.cpp +++ b/rmw_fastrtps_cpp/src/demangle.cpp @@ -89,7 +89,7 @@ _demangle_service_from_topic(const std::string & topic_name) break; } } - if (suffix_position == std::string::npos) { + if (std::string::npos == suffix_position) { RCUTILS_LOG_WARN_NAMED("rmw_fastrtps_cpp", "service topic has prefix but no suffix" ", report this: '%s'", topic_name.c_str()) @@ -108,7 +108,7 @@ _demangle_service_type_only(const std::string & dds_type_name) { std::string ns_substring = "::srv::dds_::"; size_t ns_substring_position = dds_type_name.find(ns_substring); - if (ns_substring_position == std::string::npos) { + if (std::string::npos == ns_substring_position) { // not a ROS service type return ""; } @@ -131,7 +131,7 @@ _demangle_service_type_only(const std::string & dds_type_name) break; } } - if (suffix_position == std::string::npos) { + if (std::string::npos == suffix_position) { RCUTILS_LOG_WARN_NAMED("rmw_fastrtps_cpp", "service type contains '::srv::dds_::' but does not have a suffix" ", report this: '%s'", dds_type_name.c_str()) diff --git a/rmw_fastrtps_cpp/src/qos.cpp b/rmw_fastrtps_cpp/src/qos.cpp index 694aa4b00..fafd73bf9 100644 --- a/rmw_fastrtps_cpp/src/qos.cpp +++ b/rmw_fastrtps_cpp/src/qos.cpp @@ -77,7 +77,7 @@ get_datareader_qos( // ensure the history depth is at least the requested queue size assert(sattr.topic.historyQos.depth >= 0); if ( - sattr.topic.historyQos.kind == eprosima::fastrtps::KEEP_LAST_HISTORY_QOS && + eprosima::fastrtps::KEEP_LAST_HISTORY_QOS == sattr.topic.historyQos.kind && static_cast(sattr.topic.historyQos.depth) < qos_policies.depth) { if (qos_policies.depth > (std::numeric_limits::max)()) { @@ -144,7 +144,7 @@ get_datawriter_qos( // ensure the history depth is at least the requested queue size assert(pattr.topic.historyQos.depth >= 0); if ( - pattr.topic.historyQos.kind == eprosima::fastrtps::KEEP_LAST_HISTORY_QOS && + eprosima::fastrtps::KEEP_LAST_HISTORY_QOS == pattr.topic.historyQos.kind && static_cast(pattr.topic.historyQos.depth) < qos_policies.depth) { if (qos_policies.depth > (std::numeric_limits::max)()) { diff --git a/rmw_fastrtps_cpp/src/rmw_client.cpp b/rmw_fastrtps_cpp/src/rmw_client.cpp index 9b5b5aef4..bf75d570c 100644 --- a/rmw_fastrtps_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_cpp/src/rmw_client.cpp @@ -32,6 +32,10 @@ #include "rmw_fastrtps_cpp/custom_client_info.hpp" #include "rmw_fastrtps_cpp/custom_participant_info.hpp" +using Domain = eprosima::fastrtps::Domain; +using Participant = eprosima::fastrtps::Participant; +using TopicDataType = eprosima::fastrtps::TopicDataType; + extern "C" { rmw_client_t * @@ -84,8 +88,8 @@ rmw_create_client( } CustomClientInfo * info = nullptr; - SubscriberAttributes subscriberParam; - PublisherAttributes publisherParam; + eprosima::fastrtps::SubscriberAttributes subscriberParam; + eprosima::fastrtps::PublisherAttributes publisherParam; rmw_client_t * rmw_client = nullptr; info = new CustomClientInfo(); @@ -121,9 +125,10 @@ rmw_create_client( _register_type(participant, info->response_type_support_, info->typesupport_identifier_); } - subscriberParam.topic.topicKind = NO_KEY; + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = response_type_name; - subscriberParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; rcutils_ret_t ret = _assign_partitions_to_attributes( service_name, ros_service_response_prefix, qos_policies->avoid_ros_namespace_conventions, &subscriberParam); @@ -133,10 +138,11 @@ rmw_create_client( } subscriberParam.topic.topicName += "Reply"; - publisherParam.topic.topicKind = NO_KEY; + publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; publisherParam.topic.topicDataType = request_type_name; - publisherParam.qos.m_publishMode.kind = ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; + publisherParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; ret = _assign_partitions_to_attributes( service_name, ros_service_requester_prefix, qos_policies->avoid_ros_namespace_conventions, &publisherParam); diff --git a/rmw_fastrtps_cpp/src/rmw_node.cpp b/rmw_fastrtps_cpp/src/rmw_node.cpp index a7b35f11e..41653d968 100644 --- a/rmw_fastrtps_cpp/src/rmw_node.cpp +++ b/rmw_fastrtps_cpp/src/rmw_node.cpp @@ -46,6 +46,11 @@ #include "rmw_fastrtps_cpp/identifier.hpp" #include "rmw_fastrtps_cpp/custom_participant_info.hpp" +using Domain = eprosima::fastrtps::Domain; +using Participant = eprosima::fastrtps::Participant; +using ParticipantAttributes = eprosima::fastrtps::ParticipantAttributes; +using StatefulReader = eprosima::fastrtps::rtps::StatefulReader; + extern "C" { rmw_node_t * @@ -246,7 +251,8 @@ rmw_create_node( std::array security_files_paths; if (get_security_file_paths(security_files_paths, security_options->security_root_path)) { - PropertyPolicy property_policy; + eprosima::fastrtps::rtps::PropertyPolicy property_policy; + using Property = eprosima::fastrtps::rtps::Property; property_policy.properties().emplace_back( Property("dds.sec.auth.plugin", "builtin.PKI-DH")); property_policy.properties().emplace_back( diff --git a/rmw_fastrtps_cpp/src/rmw_node_names.cpp b/rmw_fastrtps_cpp/src/rmw_node_names.cpp index 40afa7a53..6cc2d614e 100644 --- a/rmw_fastrtps_cpp/src/rmw_node_names.cpp +++ b/rmw_fastrtps_cpp/src/rmw_node_names.cpp @@ -29,6 +29,8 @@ #include "rmw_fastrtps_cpp/identifier.hpp" #include "rmw_fastrtps_cpp/custom_participant_info.hpp" +using Participant = eprosima::fastrtps::Participant; + extern "C" { rmw_ret_t diff --git a/rmw_fastrtps_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_cpp/src/rmw_publisher.cpp index e50aef3df..93ef8edbc 100644 --- a/rmw_fastrtps_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_cpp/src/rmw_publisher.cpp @@ -26,6 +26,10 @@ #include "rmw_fastrtps_cpp/custom_publisher_info.hpp" #include "type_support_common.hpp" +using Domain = eprosima::fastrtps::Domain; +using Participant = eprosima::fastrtps::Participant; +using TopicDataType = eprosima::fastrtps::TopicDataType; + extern "C" { rmw_publisher_t * @@ -79,8 +83,8 @@ rmw_create_publisher( CustomPublisherInfo * info = nullptr; rmw_publisher_t * rmw_publisher = nullptr; - PublisherAttributes publisherParam; - const GUID_t * guid = nullptr; + eprosima::fastrtps::PublisherAttributes publisherParam; + const eprosima::fastrtps::rtps::GUID_t * guid = nullptr; // Load default XML profile. Domain::getDefaultPublisherAttributes(publisherParam); @@ -99,12 +103,14 @@ rmw_create_publisher( _register_type(participant, info->type_support_, info->typesupport_identifier_); } - publisherParam.qos.m_publishMode.kind = ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; - publisherParam.topic.topicKind = NO_KEY; + publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; + publisherParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; publisherParam.topic.topicDataType = type_name; rcutils_ret_t ret = _assign_partitions_to_attributes( - topic_name, ros_topic_prefix, qos_policies->avoid_ros_namespace_conventions, &publisherParam); + topic_name, ros_topic_prefix, + qos_policies->avoid_ros_namespace_conventions, &publisherParam); if (ret != RCUTILS_RET_OK) { // error msg already set goto fail; @@ -112,12 +118,12 @@ rmw_create_publisher( #if HAVE_SECURITY // see if our participant has a security property set - if (eprosima::fastrtps::PropertyPolicyHelper::find_property( + if (eprosima::fastrtps::rtps::PropertyPolicyHelper::find_property( participant->getAttributes().rtps.properties, std::string("dds.sec.crypto.plugin"))) { // set the encryption property on the publisher - PropertyPolicy publisher_property_policy; + eprosima::fastrtps::rtps::PropertyPolicy publisher_property_policy; publisher_property_policy.properties().emplace_back( "rtps.endpoint.submessage_protection_kind", "ENCRYPT"); publisher_property_policy.properties().emplace_back( diff --git a/rmw_fastrtps_cpp/src/rmw_service.cpp b/rmw_fastrtps_cpp/src/rmw_service.cpp index 43ef1fbaa..7f9cb1e58 100644 --- a/rmw_fastrtps_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_cpp/src/rmw_service.cpp @@ -42,6 +42,10 @@ #include "rmw_fastrtps_cpp/custom_participant_info.hpp" #include "rmw_fastrtps_cpp/custom_service_info.hpp" +using Domain = eprosima::fastrtps::Domain; +using Participant = eprosima::fastrtps::Participant; +using TopicDataType = eprosima::fastrtps::TopicDataType; + extern "C" { rmw_service_t * @@ -94,8 +98,8 @@ rmw_create_service( } CustomServiceInfo * info = nullptr; - SubscriberAttributes subscriberParam; - PublisherAttributes publisherParam; + eprosima::fastrtps::SubscriberAttributes subscriberParam; + eprosima::fastrtps::PublisherAttributes publisherParam; rmw_service_t * rmw_service = nullptr; info = new CustomServiceInfo(); @@ -131,8 +135,9 @@ rmw_create_service( _register_type(participant, info->response_type_support_, info->typesupport_identifier_); } - subscriberParam.topic.topicKind = NO_KEY; - subscriberParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; subscriberParam.topic.topicDataType = request_type_name; rcutils_ret_t ret = _assign_partitions_to_attributes( service_name, ros_service_requester_prefix, @@ -143,10 +148,11 @@ rmw_create_service( } subscriberParam.topic.topicName += "Request"; - publisherParam.topic.topicKind = NO_KEY; + publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; publisherParam.topic.topicDataType = response_type_name; - publisherParam.qos.m_publishMode.kind = ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; + publisherParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; ret = _assign_partitions_to_attributes( service_name, ros_service_response_prefix, qos_policies->avoid_ros_namespace_conventions, &publisherParam); diff --git a/rmw_fastrtps_cpp/src/rmw_service_server_is_available.cpp b/rmw_fastrtps_cpp/src/rmw_service_server_is_available.cpp index d2f686538..0aead8ffd 100644 --- a/rmw_fastrtps_cpp/src/rmw_service_server_is_available.cpp +++ b/rmw_fastrtps_cpp/src/rmw_service_server_is_available.cpp @@ -102,7 +102,7 @@ rmw_service_server_is_available( // error string already set return ret; } - if (number_of_request_subscribers == 0) { + if (0 == number_of_request_subscribers) { // not ready return RMW_RET_OK; } @@ -116,7 +116,7 @@ rmw_service_server_is_available( // error string already set return ret; } - if (number_of_response_publishers == 0) { + if (0 == number_of_response_publishers) { // not ready return RMW_RET_OK; } diff --git a/rmw_fastrtps_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_cpp/src/rmw_subscription.cpp index 7c222865c..a95fe7863 100644 --- a/rmw_fastrtps_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_cpp/src/rmw_subscription.cpp @@ -30,6 +30,10 @@ #include "rmw_fastrtps_cpp/custom_subscriber_info.hpp" #include "type_support_common.hpp" +using Domain = eprosima::fastrtps::Domain; +using Participant = eprosima::fastrtps::Participant; +using TopicDataType = eprosima::fastrtps::TopicDataType; + extern "C" { rmw_subscription_t * @@ -84,7 +88,7 @@ rmw_create_subscription( (void)ignore_local_publications; CustomSubscriberInfo * info = nullptr; rmw_subscription_t * rmw_subscription = nullptr; - SubscriberAttributes subscriberParam; + eprosima::fastrtps::SubscriberAttributes subscriberParam; // Load default XML profile. Domain::getDefaultSubscriberAttributes(subscriberParam); @@ -102,11 +106,13 @@ rmw_create_subscription( _register_type(participant, info->type_support_, info->typesupport_identifier_); } - subscriberParam.historyMemoryPolicy = PREALLOCATED_WITH_REALLOC_MEMORY_MODE; - subscriberParam.topic.topicKind = NO_KEY; + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = type_name; rcutils_ret_t ret = _assign_partitions_to_attributes( - topic_name, ros_topic_prefix, qos_policies->avoid_ros_namespace_conventions, &subscriberParam); + topic_name, ros_topic_prefix, + qos_policies->avoid_ros_namespace_conventions, &subscriberParam); if (ret != RCUTILS_RET_OK) { // error msg already set goto fail; @@ -114,12 +120,12 @@ rmw_create_subscription( #if HAVE_SECURITY // see if our subscriber has a security property set - if (eprosima::fastrtps::PropertyPolicyHelper::find_property( + if (eprosima::fastrtps::rtps::PropertyPolicyHelper::find_property( participant->getAttributes().rtps.properties, std::string("dds.sec.crypto.plugin"))) { // set the encryption property on the subscriber - PropertyPolicy subscriber_property_policy; + eprosima::fastrtps::rtps::PropertyPolicy subscriber_property_policy; subscriber_property_policy.properties().emplace_back( "rtps.endpoint.submessage_protection_kind", "ENCRYPT"); subscriber_property_policy.properties().emplace_back( diff --git a/rmw_fastrtps_cpp/src/rmw_take.cpp b/rmw_fastrtps_cpp/src/rmw_take.cpp index 9231b3129..abe401813 100644 --- a/rmw_fastrtps_cpp/src/rmw_take.cpp +++ b/rmw_fastrtps_cpp/src/rmw_take.cpp @@ -50,7 +50,7 @@ rmw_take(const rmw_subscription_t * subscription, void * ros_message, bool * tak if (info->subscriber_->takeNextData(&buffer, &sinfo)) { info->listener_->data_taken(); - if (sinfo.sampleKind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == sinfo.sampleKind) { _deserialize_ros_message(&buffer, ros_message, info->type_support_, info->typesupport_identifier_); *taken = true; @@ -92,7 +92,7 @@ rmw_take_with_info( if (info->subscriber_->takeNextData(&buffer, &sinfo)) { info->listener_->data_taken(); - if (sinfo.sampleKind == ALIVE) { + if (eprosima::fastrtps::rtps::ALIVE == sinfo.sampleKind) { _deserialize_ros_message(&buffer, ros_message, info->type_support_, info->typesupport_identifier_); rmw_gid_t * sender_gid = &message_info->publisher_gid; From 5a67d54927327c2cc4ef251d43c08084e347467f Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Mon, 16 Apr 2018 10:57:10 -0700 Subject: [PATCH 2/2] revert spurious line change --- .../include/rmw_fastrtps_cpp/custom_participant_info.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp index faac74fd0..84e479d15 100644 --- a/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp +++ b/rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/custom_participant_info.hpp @@ -29,7 +29,6 @@ #include "rmw_fastrtps_cpp/reader_info.hpp" #include "rmw_fastrtps_cpp/writer_info.hpp" - class ParticipantListener; typedef struct CustomParticipantInfo