Skip to content

Commit

Permalink
Upgrades to support Fast-RTPS 1.8.0
Browse files Browse the repository at this point in the history
  • Loading branch information
nburek authored and Emerson Knapp committed May 2, 2019
1 parent b27c4a5 commit d63e246
Show file tree
Hide file tree
Showing 6 changed files with 32 additions and 29 deletions.
13 changes: 7 additions & 6 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,12 +129,13 @@ rmw_create_client(

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = response_type_name;
std::string topic_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
topic_name = std::string(ros_service_response_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
topic_name = service_name;
}
subscriberParam.topic.topicName += "Reply";
subscriberParam.topic.topicName = topic_name + "Reply";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
Expand All @@ -145,11 +146,11 @@ rmw_create_client(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = request_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
topic_name = std::string(ros_service_requester_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
topic_name = service_name;
}
publisherParam.topic.topicName += "Request";
publisherParam.topic.topicName = topic_name + "Request";

RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
Expand Down
13 changes: 7 additions & 6 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,12 +139,13 @@ rmw_create_service(

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = request_type_name;
std::string topic_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
topic_name = std::string(ros_service_requester_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
topic_name = service_name;
}
subscriberParam.topic.topicName += "Request";
subscriberParam.topic.topicName = topic_name + "Request";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
Expand All @@ -155,11 +156,11 @@ rmw_create_service(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = response_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
topic_name = std::string(ros_service_response_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
topic_name = service_name;
}
publisherParam.topic.topicName += "Reply";
publisherParam.topic.topicName = topic_name + "Reply";

RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
Expand Down
13 changes: 7 additions & 6 deletions rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,12 +134,13 @@ rmw_create_client(

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = response_type_name;
std::string topic_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
topic_name = std::string(ros_service_response_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
topic_name = service_name;
}
subscriberParam.topic.topicName += "Reply";
subscriberParam.topic.topicName = topic_name + "Reply";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
Expand All @@ -150,11 +151,11 @@ rmw_create_client(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = request_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
topic_name = std::string(ros_service_requester_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
topic_name = service_name;
}
publisherParam.topic.topicName += "Request";
publisherParam.topic.topicName = topic_name + "Request";

RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_dynamic_cpp",
Expand Down
13 changes: 7 additions & 6 deletions rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,12 +144,13 @@ rmw_create_service(

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = request_type_name;
std::string topic_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
topic_name = std::string(ros_service_requester_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
topic_name = service_name;
}
subscriberParam.topic.topicName += "Request";
subscriberParam.topic.topicName = topic_name + "Request";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
Expand All @@ -160,11 +161,11 @@ rmw_create_service(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = response_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
topic_name = std::string(ros_service_response_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
topic_name = service_name;
}
publisherParam.topic.topicName += "Reply";
publisherParam.topic.topicName = topic_name + "Reply";

RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_dynamic_cpp",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -161,16 +161,15 @@ class ParticipantListener : public eprosima::fastrtps::ParticipantListener
auto & topic_cache =
is_reader ? reader_topic_cache : writer_topic_cache;

auto fqdn = proxyData.topicName();
bool trigger;
{
std::lock_guard<std::mutex> guard(topic_cache.getMutex());
if (is_alive) {
trigger = topic_cache().addTopic(proxyData.RTPSParticipantKey(),
proxyData.topicName(), proxyData.typeName());
proxyData.topicName().to_string(), proxyData.typeName().to_string());
} else {
trigger = topic_cache().removeTopic(proxyData.RTPSParticipantKey(),
proxyData.topicName(), proxyData.typeName());
proxyData.topicName().to_string(), proxyData.typeName().to_string());
}
}
if (trigger) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,12 +64,12 @@ __rmw_service_server_is_available(
}

auto pub_topic_name =
client_info->request_publisher_->getAttributes().topic.getTopicName();
client_info->request_publisher_->getAttributes().topic.getTopicName().to_string();

auto pub_fqdn = _demangle_if_ros_topic(pub_topic_name);

auto sub_topic_name =
client_info->response_subscriber_->getAttributes().topic.getTopicName();
client_info->response_subscriber_->getAttributes().topic.getTopicName().to_string();

auto sub_fqdn = _demangle_if_ros_topic(sub_topic_name);

Expand Down

0 comments on commit d63e246

Please sign in to comment.