Skip to content

Commit

Permalink
Remove topic partitions (#192)
Browse files Browse the repository at this point in the history
* removed the use of partitions, use the complete topic_name directly

Removed assign_partitions.hpp header

trial: removal of topic partitions from services and client

Modified readerinfo, writerinfo and added prefix to the topic names.

* Changed topic namespacing in services and clients

minor style changes

Delete assign_partitions.hpp and removed anything related to partitons

re-adding avoid_ros_namespace_conventions check for prefixing names

Corrected indentation

Added vertical space between the headers

* remove unnecessary initializations
  • Loading branch information
rohitsalem authored and Karsten1987 committed Jun 7, 2018
1 parent bc1ff87 commit a33f9f8
Show file tree
Hide file tree
Showing 8 changed files with 31 additions and 164 deletions.
7 changes: 1 addition & 6 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/reader_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,12 +71,7 @@ class ReaderInfo : public eprosima::fastrtps::rtps::ReaderListener
}
}

auto partition_str = std::string("");
// don't use std::accumulate - schlemiel O(n2)
for (const auto & partition : proxyData.m_qos.m_partition.getNames()) {
partition_str += partition;
}
auto fqdn = partition_str + "/" + proxyData.topicName();
auto fqdn = proxyData.topicName();

bool trigger = false;
mapmutex.lock();
Expand Down
7 changes: 1 addition & 6 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/writer_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,12 +69,7 @@ class WriterInfo : public eprosima::fastrtps::rtps::ReaderListener
}
}

auto partition_str = std::string("");
// don't use std::accumulate - schlemiel O(n2)
for (const auto & partition : proxyData.m_qos.m_partition.getNames()) {
partition_str += partition;
}
auto fqdn = partition_str + "/" + proxyData.topicName();
auto fqdn = proxyData.topicName();

bool trigger = false;
mapmutex.lock();
Expand Down
76 changes: 0 additions & 76 deletions rmw_fastrtps_cpp/src/assign_partitions.hpp

This file was deleted.

27 changes: 8 additions & 19 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include "rosidl_typesupport_introspection_c/identifier.h"

#include "assign_partitions.hpp"
#include "client_service_common.hpp"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "namespace_prefix.hpp"
Expand Down Expand Up @@ -129,12 +128,10 @@ rmw_create_client(
subscriberParam.topic.topicDataType = response_type_name;
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);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
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";

Expand All @@ -143,12 +140,10 @@ rmw_create_client(
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);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
}
publisherParam.topic.topicName += "Request";

Expand All @@ -158,15 +153,9 @@ rmw_create_client(
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Sub Topic %s", subscriberParam.topic.topicName.c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Sub Partition %s", subscriberParam.qos.m_partition.getNames()[0].c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Pub Topic %s", publisherParam.topic.topicName.c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Pub Partition %s", publisherParam.qos.m_partition.getNames()[0].c_str())
RCUTILS_LOG_DEBUG_NAMED("rmw_fastrtps_cpp", "***********")

// Create Client Subscriber and set QoS
Expand Down
11 changes: 4 additions & 7 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "rmw/error_handling.h"
#include "rmw/rmw.h"

#include "assign_partitions.hpp"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "namespace_prefix.hpp"
#include "qos.hpp"
Expand Down Expand Up @@ -108,12 +107,10 @@ rmw_create_publisher(
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);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_topic_prefix) + topic_name;
} else {
publisherParam.topic.topicName = topic_name;
}

// 1 Heartbeat every 10ms
Expand Down
28 changes: 9 additions & 19 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@
#include "rmw/rmw.h"

#include "rosidl_typesupport_introspection_cpp/identifier.hpp"

#include "rosidl_typesupport_introspection_c/identifier.h"

#include "assign_partitions.hpp"
#include "client_service_common.hpp"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "namespace_prefix.hpp"
Expand Down Expand Up @@ -139,12 +139,10 @@ rmw_create_service(
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,
qos_policies->avoid_ros_namespace_conventions, &subscriberParam);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
}
subscriberParam.topic.topicName += "Request";

Expand All @@ -153,12 +151,10 @@ rmw_create_service(
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);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
} else {
publisherParam.topic.topicName = service_name;
}
publisherParam.topic.topicName += "Reply";

Expand All @@ -168,15 +164,9 @@ rmw_create_service(
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Sub Topic %s", subscriberParam.topic.topicName.c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Sub Partition %s", subscriberParam.qos.m_partition.getNames()[0].c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Pub Topic %s", publisherParam.topic.topicName.c_str())
RCUTILS_LOG_DEBUG_NAMED(
"rmw_fastrtps_cpp",
"Pub Partition %s", publisherParam.qos.m_partition.getNames()[0].c_str())
RCUTILS_LOG_DEBUG_NAMED("rmw_fastrtps_cpp", "***********")

// Create Service Subscriber and set QoS
Expand Down
28 changes: 4 additions & 24 deletions rmw_fastrtps_cpp/src/rmw_service_server_is_available.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,33 +64,13 @@ rmw_service_server_is_available(

auto pub_topic_name =
client_info->request_publisher_->getAttributes().topic.getTopicName();
auto pub_partitions =
client_info->request_publisher_->getAttributes().qos.m_partition.getNames();
// every rostopic has exactly 1 partition field set
if (pub_partitions.size() != 1) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_fastrtps_cpp",
"Topic %s is not a ros topic", pub_topic_name.c_str())
RMW_SET_ERROR_MSG((std::string(pub_topic_name) + " is a non-ros topic\n").c_str());
return RMW_RET_ERROR;
}
auto pub_fqdn = pub_partitions[0] + "/" + pub_topic_name;
pub_fqdn = _demangle_if_ros_topic(pub_fqdn);

auto pub_fqdn = _demangle_if_ros_topic(pub_topic_name);

auto sub_topic_name =
client_info->response_subscriber_->getAttributes().topic.getTopicName();
auto sub_partitions =
client_info->response_subscriber_->getAttributes().qos.m_partition.getNames();
// every rostopic has exactly 1 partition field set
if (sub_partitions.size() != 1) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_fastrtps_cpp",
"Topic %s is not a ros topic", pub_topic_name.c_str())
RMW_SET_ERROR_MSG((std::string(sub_topic_name) + " is a non-ros topic\n").c_str());
return RMW_RET_ERROR;
}
auto sub_fqdn = sub_partitions[0] + "/" + sub_topic_name;
sub_fqdn = _demangle_if_ros_topic(sub_fqdn);

auto sub_fqdn = _demangle_if_ros_topic(sub_topic_name);

*is_available = false;
size_t number_of_request_subscribers = 0;
Expand Down
11 changes: 4 additions & 7 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include "fastrtps/participant/Participant.h"
#include "fastrtps/subscriber/Subscriber.h"

#include "assign_partitions.hpp"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "namespace_prefix.hpp"
#include "qos.hpp"
Expand Down Expand Up @@ -110,12 +109,10 @@ rmw_create_subscription(
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);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_topic_prefix) + topic_name;
} else {
subscriberParam.topic.topicName = topic_name;
}

if (!get_datareader_qos(*qos_policies, subscriberParam)) {
Expand Down

0 comments on commit a33f9f8

Please sign in to comment.