From 0ffb5f3e5f53251d7d0b2899c1ddc3bae806e953 Mon Sep 17 00:00:00 2001 From: JuanCarlos Date: Fri, 30 Nov 2018 10:42:07 +0100 Subject: [PATCH 1/5] Refs #3555 Apply the changes to the current master on ROS2 --- rmw_fastrtps_cpp/src/rmw_client.cpp | 18 +++++-- rmw_fastrtps_cpp/src/rmw_publisher.cpp | 10 ++-- rmw_fastrtps_cpp/src/rmw_service.cpp | 18 +++++-- rmw_fastrtps_cpp/src/rmw_subscription.cpp | 8 ++- rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp | 18 +++++-- .../src/rmw_publisher.cpp | 10 ++-- rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp | 18 +++++-- .../src/rmw_subscription.cpp | 8 ++- .../custom_participant_info.hpp | 1 + rmw_fastrtps_shared_cpp/src/rmw_node.cpp | 53 +++++++++++++++++-- 10 files changed, 128 insertions(+), 34 deletions(-) diff --git a/rmw_fastrtps_cpp/src/rmw_client.cpp b/rmw_fastrtps_cpp/src/rmw_client.cpp index 171a72cfb..874784c89 100644 --- a/rmw_fastrtps_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_cpp/src/rmw_client.cpp @@ -120,10 +120,14 @@ rmw_create_client( _register_type(participant, info->response_type_support_); } + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + } + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = response_type_name; - subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name; } else { @@ -131,11 +135,15 @@ rmw_create_client( } subscriberParam.topic.topicName += "Reply"; + if (!impl->leave_middleware_default_qos) + { + 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 = request_type_name; - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name; } else { diff --git a/rmw_fastrtps_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_cpp/src/rmw_publisher.cpp index 5907590fd..5e50cb2bb 100644 --- a/rmw_fastrtps_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_cpp/src/rmw_publisher.cpp @@ -113,9 +113,13 @@ rmw_create_publisher( _register_type(participant, info->type_support_); } - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + if (!impl->leave_middleware_default_qos) + { + 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; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_cpp/src/rmw_service.cpp b/rmw_fastrtps_cpp/src/rmw_service.cpp index af81304e4..391949cb4 100644 --- a/rmw_fastrtps_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_cpp/src/rmw_service.cpp @@ -132,9 +132,13 @@ rmw_create_service( _register_type(participant, info->response_type_support_); } + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::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; if (!qos_policies->avoid_ros_namespace_conventions) { subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name; @@ -143,11 +147,15 @@ rmw_create_service( } subscriberParam.topic.topicName += "Request"; + if (!impl->leave_middleware_default_qos) + { + 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 = response_type_name; - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name; } else { diff --git a/rmw_fastrtps_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_cpp/src/rmw_subscription.cpp index 998b859f8..e4dc65699 100644 --- a/rmw_fastrtps_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_cpp/src/rmw_subscription.cpp @@ -116,8 +116,12 @@ rmw_create_subscription( _register_type(participant, info->type_support_); } - subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + } + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = type_name; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp index da3c6cda0..9e0fc2538 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp @@ -125,10 +125,14 @@ rmw_create_client( _register_type(participant, info->response_type_support_); } + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + } + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = response_type_name; - subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name; } else { @@ -136,11 +140,15 @@ rmw_create_client( } subscriberParam.topic.topicName += "Reply"; + if (!impl->leave_middleware_default_qos) + { + 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 = request_type_name; - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name; } else { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp index ae44cfe03..9433ae7c9 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp @@ -108,9 +108,13 @@ rmw_create_publisher( _register_type(participant, info->type_support_); } - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + if (!impl->leave_middleware_default_qos) + { + 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; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp index 2de1d7645..6c2353b64 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp @@ -137,9 +137,13 @@ rmw_create_service( _register_type(participant, info->response_type_support_); } + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::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; if (!qos_policies->avoid_ros_namespace_conventions) { subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name; @@ -148,11 +152,15 @@ rmw_create_service( } subscriberParam.topic.topicName += "Request"; + if (!impl->leave_middleware_default_qos) + { + 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 = response_type_name; - publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; - publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; if (!qos_policies->avoid_ros_namespace_conventions) { publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name; } else { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp index a421424fe..e1aaa21ee 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp @@ -112,8 +112,12 @@ rmw_create_subscription( _register_type(participant, info->type_support_); } - subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + if (!impl->leave_middleware_default_qos) + { + subscriberParam.historyMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + } + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = type_name; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp index 4e086435d..20588e57b 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp @@ -37,6 +37,7 @@ typedef struct CustomParticipantInfo ReaderInfo * secondarySubListener; WriterInfo * secondaryPubListener; rmw_guard_condition_t * graph_guard_condition; + bool leave_middleware_default_qos; } CustomParticipantInfo; class ParticipantListener : public eprosima::fastrtps::ParticipantListener diff --git a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp index c106f5db6..74d9e2f41 100644 --- a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp +++ b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp @@ -104,6 +104,27 @@ create_node( try { node_impl = new CustomParticipantInfo(); + + node_impl->leave_middleware_default_qos = false; + const char * env_var = "RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS"; + // Check if the configuration from XML has been enabled from + // the RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS env variable. + char * config_env_val = nullptr; +#ifndef _WIN32 + config_env_val = getenv(env_var); + if (config_env_val != nullptr) + { + node_impl->leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; + } +#else + size_t config_env_val_size; + _dupenv_s(&config_env_val, &config_env_val_size, env_var); + if (config_env_val != nullptr) + { + node_impl->leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; + } + free(config_env_val); +#endif } catch (std::bad_alloc &) { RMW_SET_ERROR_MSG("failed to allocate node impl struct"); goto fail; @@ -246,11 +267,35 @@ __rmw_create_node( // since the participant name is not part of the DDS spec participantAttrs.rtps.setName(name); + bool leave_middleware_default_qos = false; + const char * env_var = "RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS"; + // Check if the configuration from XML has been enabled from + // the RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS env variable. + char * config_env_val = nullptr; +#ifndef _WIN32 + config_env_val = getenv(env_var); + if (config_env_val != nullptr) + { + leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; + } +#else + size_t config_env_val_size; + _dupenv_s(&config_env_val, &config_env_val_size, env_var); + if (config_env_val != nullptr) + { + leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; + } + free(config_env_val); +#endif + // allow reallocation to support discovery messages bigger than 5000 bytes - participantAttrs.rtps.builtin.readerHistoryMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; - participantAttrs.rtps.builtin.writerHistoryMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + if (!leave_middleware_default_qos) + { + participantAttrs.rtps.builtin.readerHistoryMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + participantAttrs.rtps.builtin.writerHistoryMemoryPolicy = + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + } size_t length = strlen(name) + strlen("name=;") + strlen(namespace_) + strlen("namespace=;") + 1; From 1e4c252985f1e10a6b87049d94f27982bc10f504 Mon Sep 17 00:00:00 2001 From: Juan Carlos Arceredillo Date: Mon, 3 Dec 2018 07:32:24 +0100 Subject: [PATCH 2/5] Refs #3555 rename the environment variable from "RMW_LEAVE_MIDDLEWARE_DEFAULT_QOS" to "RMW_FASTRTPS_USE_QOS_FROM_XML" --- rmw_fastrtps_shared_cpp/src/rmw_node.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp index 74d9e2f41..1a2ed7109 100644 --- a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp +++ b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp @@ -106,9 +106,9 @@ create_node( node_impl = new CustomParticipantInfo(); node_impl->leave_middleware_default_qos = false; - const char * env_var = "RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS"; + const char * env_var = "RMW_FASTRTPS_USE_QOS_FROM_XML"; // Check if the configuration from XML has been enabled from - // the RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS env variable. + // the RMW_FASTRTPS_USE_QOS_FROM_XML env variable. char * config_env_val = nullptr; #ifndef _WIN32 config_env_val = getenv(env_var); @@ -268,9 +268,9 @@ __rmw_create_node( participantAttrs.rtps.setName(name); bool leave_middleware_default_qos = false; - const char * env_var = "RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS"; + const char * env_var = "RMW_FASTRTPS_USE_QOS_FROM_XML"; // Check if the configuration from XML has been enabled from - // the RMW_FASTRTPS_LEAVE_MIDDLEWARE_DEFAULT_QOS env variable. + // the RMW_FASTRTPS_USE_QOS_FROM_XML env variable. char * config_env_val = nullptr; #ifndef _WIN32 config_env_val = getenv(env_var); From 54b6cbbbff7d183983227476c85e10217b6eac48 Mon Sep 17 00:00:00 2001 From: Juan Carlos Arceredillo Date: Wed, 5 Dec 2018 09:40:06 +0100 Subject: [PATCH 3/5] Refs #3555 Fix lint issues. --- rmw_fastrtps_cpp/src/rmw_client.cpp | 6 ++---- rmw_fastrtps_cpp/src/rmw_publisher.cpp | 5 ++--- rmw_fastrtps_cpp/src/rmw_service.cpp | 10 ++++------ rmw_fastrtps_cpp/src/rmw_subscription.cpp | 5 ++--- rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp | 10 ++++------ .../src/rmw_publisher.cpp | 3 +-- rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp | 8 +++----- .../src/rmw_subscription.cpp | 5 ++--- rmw_fastrtps_shared_cpp/src/rmw_node.cpp | 19 +++++++------------ 9 files changed, 27 insertions(+), 44 deletions(-) diff --git a/rmw_fastrtps_cpp/src/rmw_client.cpp b/rmw_fastrtps_cpp/src/rmw_client.cpp index 874784c89..409a91f1c 100644 --- a/rmw_fastrtps_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_cpp/src/rmw_client.cpp @@ -120,8 +120,7 @@ rmw_create_client( _register_type(participant, info->response_type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } @@ -135,8 +134,7 @@ rmw_create_client( } subscriberParam.topic.topicName += "Reply"; - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; diff --git a/rmw_fastrtps_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_cpp/src/rmw_publisher.cpp index 5e50cb2bb..520afdf6a 100644 --- a/rmw_fastrtps_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_cpp/src/rmw_publisher.cpp @@ -113,13 +113,12 @@ rmw_create_publisher( _register_type(participant, info->type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { 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; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_cpp/src/rmw_service.cpp b/rmw_fastrtps_cpp/src/rmw_service.cpp index 391949cb4..80a8739ff 100644 --- a/rmw_fastrtps_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_cpp/src/rmw_service.cpp @@ -132,10 +132,9 @@ rmw_create_service( _register_type(participant, info->response_type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; @@ -147,11 +146,10 @@ rmw_create_service( } subscriberParam.topic.topicName += "Request"; - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; diff --git a/rmw_fastrtps_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_cpp/src/rmw_subscription.cpp index e4dc65699..27ad9e374 100644 --- a/rmw_fastrtps_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_cpp/src/rmw_subscription.cpp @@ -116,12 +116,11 @@ rmw_create_subscription( _register_type(participant, info->type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } - + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = type_name; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp index 9e0fc2538..712562518 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp @@ -125,10 +125,9 @@ rmw_create_client( _register_type(participant, info->response_type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; @@ -140,11 +139,10 @@ rmw_create_client( } subscriberParam.topic.topicName += "Reply"; - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; publisherParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp index 9433ae7c9..82492ff24 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp @@ -108,8 +108,7 @@ rmw_create_publisher( _register_type(participant, info->type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp index 6c2353b64..42495c7d0 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp @@ -137,10 +137,9 @@ rmw_create_service( _register_type(participant, info->response_type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; @@ -152,8 +151,7 @@ rmw_create_service( } subscriberParam.topic.topicName += "Request"; - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE; publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp index e1aaa21ee..a274872e3 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp @@ -112,10 +112,9 @@ rmw_create_subscription( _register_type(participant, info->type_support_); } - if (!impl->leave_middleware_default_qos) - { + if (!impl->leave_middleware_default_qos) { subscriberParam.historyMemoryPolicy = - eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; diff --git a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp index 1a2ed7109..e9dc8b207 100644 --- a/rmw_fastrtps_shared_cpp/src/rmw_node.cpp +++ b/rmw_fastrtps_shared_cpp/src/rmw_node.cpp @@ -107,20 +107,18 @@ create_node( node_impl->leave_middleware_default_qos = false; const char * env_var = "RMW_FASTRTPS_USE_QOS_FROM_XML"; - // Check if the configuration from XML has been enabled from + // Check if the configuration from XML has been enabled from // the RMW_FASTRTPS_USE_QOS_FROM_XML env variable. char * config_env_val = nullptr; #ifndef _WIN32 config_env_val = getenv(env_var); - if (config_env_val != nullptr) - { + if (config_env_val != nullptr) { node_impl->leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; } #else size_t config_env_val_size; _dupenv_s(&config_env_val, &config_env_val_size, env_var); - if (config_env_val != nullptr) - { + if (config_env_val != nullptr) { node_impl->leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; } free(config_env_val); @@ -269,28 +267,25 @@ __rmw_create_node( bool leave_middleware_default_qos = false; const char * env_var = "RMW_FASTRTPS_USE_QOS_FROM_XML"; - // Check if the configuration from XML has been enabled from + // Check if the configuration from XML has been enabled from // the RMW_FASTRTPS_USE_QOS_FROM_XML env variable. char * config_env_val = nullptr; #ifndef _WIN32 config_env_val = getenv(env_var); - if (config_env_val != nullptr) - { + if (config_env_val != nullptr) { leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; } #else size_t config_env_val_size; _dupenv_s(&config_env_val, &config_env_val_size, env_var); - if (config_env_val != nullptr) - { + if (config_env_val != nullptr) { leave_middleware_default_qos = strcmp(config_env_val, "1") == 0; } free(config_env_val); #endif // allow reallocation to support discovery messages bigger than 5000 bytes - if (!leave_middleware_default_qos) - { + if (!leave_middleware_default_qos) { participantAttrs.rtps.builtin.readerHistoryMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; participantAttrs.rtps.builtin.writerHistoryMemoryPolicy = From 4c518b00e922b5cd8917a35420adae2364d36079 Mon Sep 17 00:00:00 2001 From: Juan Carlos Arceredillo Date: Wed, 5 Dec 2018 10:08:05 +0100 Subject: [PATCH 4/5] Refs #3555 Fix lint issues. --- rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp | 2 +- rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp | 2 +- rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp index 712562518..7adbf62f0 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp @@ -144,7 +144,7 @@ rmw_create_client( publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } - + publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; publisherParam.topic.topicDataType = request_type_name; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp index 82492ff24..f279dcbfc 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp @@ -113,7 +113,7 @@ rmw_create_publisher( publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } - + publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; publisherParam.topic.topicDataType = type_name; if (!qos_policies->avoid_ros_namespace_conventions) { diff --git a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp index a274872e3..a5c9e7e52 100644 --- a/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp +++ b/rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp @@ -116,7 +116,7 @@ rmw_create_subscription( subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; } - + subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY; subscriberParam.topic.topicDataType = type_name; if (!qos_policies->avoid_ros_namespace_conventions) { From fa5396afd1c71a2048f1d409ebdc8d7b02c689bc Mon Sep 17 00:00:00 2001 From: Juan Carlos Arceredillo Date: Wed, 5 Dec 2018 19:28:33 +0100 Subject: [PATCH 5/5] Refs #3555 Add an explanation to the attribute to explain it --- .../rmw_fastrtps_shared_cpp/custom_participant_info.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp index 20588e57b..163eb9484 100644 --- a/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp +++ b/rmw_fastrtps_shared_cpp/include/rmw_fastrtps_shared_cpp/custom_participant_info.hpp @@ -37,6 +37,12 @@ typedef struct CustomParticipantInfo ReaderInfo * secondarySubListener; WriterInfo * secondaryPubListener; rmw_guard_condition_t * graph_guard_condition; + + // Flag to establish if the QoS of the participant, + // its publishers and its subscribers are going + // to be configured only from an XML file or if + // their settings are going to be overwritten by code + // with the default configuration. bool leave_middleware_default_qos; } CustomParticipantInfo;