Skip to content

Commit

Permalink
RMW_FastRTPS configuration from XML only (#243)
Browse files Browse the repository at this point in the history
* Refs #3555 Apply the changes to the current master on ROS2

* Refs #3555 rename the environment variable from "RMW_LEAVE_MIDDLEWARE_DEFAULT_QOS" to "RMW_FASTRTPS_USE_QOS_FROM_XML"

* Refs #3555 Fix lint issues.

* Refs #3555 Fix lint issues.

* Refs #3555 Add an explanation to the attribute to explain it
  • Loading branch information
JuanCarlos-Arce authored and mjcarroll committed Dec 5, 2018
1 parent fae9283 commit 9bdc763
Show file tree
Hide file tree
Showing 10 changed files with 117 additions and 34 deletions.
16 changes: 11 additions & 5 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,22 +120,28 @@ 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 {
subscriberParam.topic.topicName = service_name;
}
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 {
Expand Down
9 changes: 6 additions & 3 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,12 @@ 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) {
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,9 +132,12 @@ 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;
Expand All @@ -143,11 +146,14 @@ 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 {
Expand Down
7 changes: 5 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,11 @@ 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) {
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,22 +125,28 @@ 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 {
subscriberParam.topic.topicName = service_name;
}
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 {
Expand Down
9 changes: 6 additions & 3 deletions rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,12 @@ 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) {
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,9 +137,12 @@ 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;
Expand All @@ -148,11 +151,14 @@ 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 {
Expand Down
7 changes: 5 additions & 2 deletions rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,11 @@ 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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,13 @@ 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;

class ParticipantListener : public eprosima::fastrtps::ParticipantListener
Expand Down
48 changes: 44 additions & 4 deletions rmw_fastrtps_shared_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,25 @@ create_node(

try {
node_impl = new CustomParticipantInfo();

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
// 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) {
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;
Expand Down Expand Up @@ -246,11 +265,32 @@ __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_USE_QOS_FROM_XML";
// 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) {
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;
Expand Down

0 comments on commit 9bdc763

Please sign in to comment.