Skip to content

Commit

Permalink
Update with comments and fix some changes of rmw
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <Barry.Xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Jan 15, 2020
1 parent 9866d7e commit 40d24ef
Show file tree
Hide file tree
Showing 6 changed files with 87 additions and 94 deletions.
26 changes: 12 additions & 14 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1072,52 +1072,50 @@ class Node : public std::enable_shared_from_this<Node>
bool
assert_liveliness() const;

/// Return a list of publishers about topic information to a given topic.
/// Return a list of publishers about topic endpoint information to a given topic.
/**
* The returned parameter is a list of topic info, where each topic info will
* contain the node name, node namespace, topic type, participant's GID and its QoS profile.
* The returned parameter is a list of topic endpoint information, where each item will contain
* the node name, node namespace, topic type, endpoint type, participant's GID and its QoS
* profile.
*
* "topic_name" may be a relative, private or fully qualified topic name.
* A relative or private topic will be expanded using this node's namespace and name, if
* the "no_mangle" param is set to false.
*
* The queried topic name is not remapped.
*
* "no_mangle" defaults to false.
*
* \param[in] topic_name the topic_name on which to find the publishers.
* \param[in] no_mangle if false, the given topic name will be expanded
* to its fully qualified name.
* to its fully qualified name. Default to `false`.
* \return a list of TopicInfo representing all the publishers on this topic.
* \throws InvalidTopicNameError if the given topic_name is invalid.
* \throws std::runtime_error if internal error happens.
*/
RCLCPP_PUBLIC
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;

/// Return a list of subscriptions about topic information to a given topic.
/// Return a list of subscriptions about topic endpoint information to a given topic.
/**
* The returned parameter is a list of topic info, where each topic info will
* contain the node name, node namespace, topic type, participant's GID and its QoS profile.
* The returned parameter is a list of topic endpoint information, where each item will contain
* the node name, node namespace, topic type, endpoint type, participant's GID and its QoS
* profile.
*
* "topic_name" may be a relative, private or fully qualified topic name.
* A relative or private topic will be expanded using this node's namespace and name, if
* the "no_mangle" param is set to false.
*
* The queried topic name is not remapped.
*
* "no_mangle" defaults to false.
*
* \param[in] topic_name the topic_name on which to find the subscriptions.
* \param[in] no_mangle if false, the given topic name will be expanded
* to its fully qualified name.
* to its fully qualified name. Default to `false`.
* \return a list of TopicInfo representing all the subscriptions on this topic.
* \throws InvalidTopicNameError if the given topic_name is invalid.
* \throws std::runtime_error if internal error happens.
*/
RCLCPP_PUBLIC
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;

protected:
Expand Down
20 changes: 3 additions & 17 deletions rclcpp/include/rclcpp/node_interfaces/node_graph.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/topic_info_array.h"
#include "rmw/topic_endpoint_info_array.h"

namespace rclcpp
{
Expand Down Expand Up @@ -119,34 +119,20 @@ class NodeGraph : public NodeGraphInterface
count_graph_users() override;

RCLCPP_PUBLIC
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(
const std::string & topic_name,
bool no_mangle = false) const override;

RCLCPP_PUBLIC
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_subscriptions_info_by_topic(
const std::string & topic_name,
bool no_mangle = false) const override;

private:
RCLCPP_DISABLE_COPY(NodeGraph)

typedef rcl_ret_t (* rcl_get_info_by_topic_func_t)(
const rcl_node_t * node,
rcutils_allocator_t * allocator,
const char * topic_name,
bool no_mangle,
rmw_topic_info_array_t * info_array);

std::vector<rclcpp::TopicInfo>
get_info_by_topic(
const std::string & topic_name,
bool no_mangle,
const std::string & type,
rcl_get_info_by_topic_func_t rcl_get_info_by_topic) const;

/// Handle to the NodeBaseInterface given in the constructor.
rclcpp::node_interfaces::NodeBaseInterface * node_base_;

Expand Down
41 changes: 28 additions & 13 deletions rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_

#include <array>
#include <chrono>
#include <map>
#include <string>
Expand All @@ -25,22 +26,38 @@

#include "rclcpp/event.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/topic_endpoint_info.h"

namespace rclcpp
{

using EndpointType = rmw_endpoint_type_t;

/**
* Use to get topic information that containing the node name, node namespace, topic type,
* participant's GID and its QoS profile
* Use to get topic endpoint information that containing the node name, node namespace, topic type,
* endpoint type, GID of endpoint and its QoS.
*/
struct RCLCPP_PUBLIC TopicInfo
struct RCLCPP_PUBLIC TopicEndpointInfo
{
std::string node_name;
std::string node_namespace;
std::string topic_type;
uint8_t gid[RMW_GID_STORAGE_SIZE];
rmw_qos_profile_t qos_profile;
rclcpp::EndpointType endpoint_type;
std::array<uint8_t, RMW_GID_STORAGE_SIZE> endpoint_gid;
rclcpp::QoS qos;

/// Constructor which convert rmw_topic_endpoint_info_t to TopicEndpointInfo.
TopicEndpointInfo(const rmw_topic_endpoint_info_t & info)
: node_name(info.node_name),
node_namespace(info.node_namespace),
topic_type(info.topic_type),
endpoint_type(info.endpoint_type),
qos({info.qos_profile.history, info.qos_profile.depth}, info.qos_profile)
{
std::copy(info.endpoint_gid, info.endpoint_gid+RMW_GID_STORAGE_SIZE, endpoint_gid.begin());
}
};

namespace node_interfaces
Expand Down Expand Up @@ -165,24 +182,22 @@ class NodeGraphInterface
size_t
count_graph_users() = 0;

/// Returns a list of all publishers to a topic.
/// Return a list of publishers about topic endpoint information to a given topic.
/**
* Each element in the list will contain the node name, node namespace, topic type,
* gid and the qos profile of the publisher.
* \sa rclcpp::Node::get_publishers_info_by_topic
*/
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;

/// Returns a list of all subscriptions to a topic.
/// Return a list of subscriptions about topic endpoint information to a given topic.
/**
* Each element in the list will contain the node name, node namespace, topic type,
* gid and the qos profile of the subscription.
* \sa rclcpp::Node::get_subscriptions_info_by_topic
*/
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
};

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -494,13 +494,13 @@ Node::assert_liveliness() const
return node_base_->assert_liveliness();
}

std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
Node::get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle) const
{
return node_graph_->get_publishers_info_by_topic(topic_name, no_mangle);
}

std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle) const
{
return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
Expand Down
75 changes: 33 additions & 42 deletions rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,12 @@
using rclcpp::node_interfaces::NodeGraph;
using rclcpp::exceptions::throw_from_rcl_error;
using rclcpp::graph_listener::GraphListener;
using rcl_get_info_by_topic_func_t = rcl_ret_t (* )(
const rcl_node_t *,
rcutils_allocator_t *,
const char *,
bool,
rmw_topic_endpoint_info_array_t *);

NodeGraph::NodeGraph(rclcpp::node_interfaces::NodeBaseInterface * node_base)
: node_base_(node_base),
Expand Down Expand Up @@ -371,53 +377,39 @@ NodeGraph::count_graph_users()
}

static
rclcpp::TopicInfo
convert_to_topic_info(const rmw_topic_info_t * info)
std::vector<rclcpp::TopicEndpointInfo>
convert_to_topic_info_list(const rmw_topic_endpoint_info_array_t & info_array)
{
rclcpp::TopicInfo topic_info;
topic_info.node_name = info->node_name;
topic_info.node_namespace = info->node_namespace;
topic_info.topic_type = info->topic_type;
memcpy(topic_info.gid, info->gid, RMW_GID_STORAGE_SIZE);
memcpy(&topic_info.qos_profile, &info->qos_profile, sizeof(rmw_qos_profile_t));
return topic_info;
}

static
std::vector<rclcpp::TopicInfo>
convert_to_topic_info_list(const rmw_topic_info_array_t * info_array)
{
std::vector<rclcpp::TopicInfo> topic_info_list;
for (size_t i = 0; i < info_array->count; ++i) {
rmw_topic_info_t topic_info = info_array->info_array[i];
auto topic_info_item = convert_to_topic_info(&topic_info);
topic_info_list.push_back(topic_info_item);
std::vector<rclcpp::TopicEndpointInfo> topic_info_list;
for (size_t i = 0; i < info_array.count; ++i) {
topic_info_list.push_back(rclcpp::TopicEndpointInfo(info_array.info_array[i]));
}
return topic_info_list;
}

std::vector<rclcpp::TopicInfo>
NodeGraph::get_info_by_topic(
template <typename TypeT, typename FunctionT>
static std::vector<rclcpp::TopicEndpointInfo>
get_info_by_topic(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
const std::string & topic_name,
bool no_mangle,
const std::string & type,
rcl_get_info_by_topic_func_t rcl_get_info_by_topic) const
TypeT type,
FunctionT rcl_get_info_by_topic)
{
std::vector<rclcpp::TopicInfo> topic_info_list;
std::vector<rclcpp::TopicEndpointInfo> topic_info_list;

auto rcl_node_handle = node_base_->get_rcl_node_handle();
auto rcl_node_handle = node_base->get_rcl_node_handle();
auto fqdn = rclcpp::expand_topic_or_service_name(
topic_name,
rcl_node_get_name(rcl_node_handle),
rcl_node_get_namespace(rcl_node_handle),
false); // false = not a service

rcutils_allocator_t allocator = rcutils_get_default_allocator();
rmw_topic_info_array_t info_array = rmw_get_zero_initialized_topic_info_array();
rmw_topic_endpoint_info_array_t info_array = rmw_get_zero_initialized_topic_endpoint_info_array();
auto ret =
rcl_get_info_by_topic(rcl_node_handle, &allocator, fqdn.c_str(), no_mangle, &info_array);
if (ret != RCL_RET_OK) {
// *INDENT-OFF*
auto error_msg =
std::string("Failed to get information by topic for: ") + type + std::string(":");
if (ret == RCL_RET_UNSUPPORTED) {
Expand All @@ -426,44 +418,43 @@ NodeGraph::get_info_by_topic(
error_msg += rcl_get_error_string().str;
}
rcl_reset_error();
if (rmw_topic_info_array_fini(&info_array, &allocator) != RMW_RET_OK) {
if (rmw_topic_endpoint_info_array_fini(&info_array, &allocator) != RMW_RET_OK) {
error_msg += std::string(", failed also to cleanup topic info array, leaking memory: ")
+ rcl_get_error_string().str;
rcl_reset_error();
}
throw std::runtime_error(error_msg);
// *INDENT-ON*
throw_from_rcl_error(ret, error_msg);
}

topic_info_list = convert_to_topic_info_list(&info_array);
if (rmw_topic_info_array_fini(&info_array, &allocator) != RMW_RET_OK) {
// *INDENT-OFF*
throw std::runtime_error(
std::string("rmw_topic_info_array_fini failed."));
// *INDENT-ON*
topic_info_list = convert_to_topic_info_list(info_array);
ret = rmw_topic_endpoint_info_array_fini(&info_array, &allocator);
if (ret != RMW_RET_OK) {
throw_from_rcl_error(ret, "rmw_topic_info_array_fini failed.");
}

return topic_info_list;
}

std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
NodeGraph::get_publishers_info_by_topic(
const std::string & topic_name,
bool no_mangle) const
{
return get_info_by_topic(
return get_info_by_topic<const char*, rcl_get_info_by_topic_func_t>(
node_base_,
topic_name,
no_mangle,
"publishers",
"publisher",
rcl_get_publishers_info_by_topic);
}

std::vector<rclcpp::TopicInfo>
std::vector<rclcpp::TopicEndpointInfo>
NodeGraph::get_subscriptions_info_by_topic(
const std::string & topic_name,
bool no_mangle) const
{
return get_info_by_topic(
return get_info_by_topic<const char*, rcl_get_info_by_topic_func_t>(
node_base_,
topic_name,
no_mangle,
"subscriptions",
Expand Down
15 changes: 9 additions & 6 deletions rclcpp/test/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2547,8 +2547,9 @@ TEST_F(TestNode, get_publishers_subscriptions_info_by_topic) {
// Verify publisher list has the right data.
EXPECT_EQ(node->get_name(), publisher_list[0].node_name);
EXPECT_EQ(node->get_namespace(), publisher_list[0].node_namespace);
EXPECT_EQ("test_msgs::msg::dds_::BasicTypes_", publisher_list[0].topic_type);
auto actual_qos_profile = publisher_list[0].qos_profile;
EXPECT_EQ("test_msgs/msg/BasicTypes", publisher_list[0].topic_type);
EXPECT_EQ(RMW_ENDPOINT_PUBLISHER, publisher_list[0].endpoint_type);
auto actual_qos_profile = publisher_list[0].qos.get_rmw_qos_profile();

auto assert_qos_profile = [](const rmw_qos_profile_t & qos1, const rmw_qos_profile_t & qos2) {
// Depth and history are skipped because they are not retrieved.
Expand Down Expand Up @@ -2601,13 +2602,15 @@ TEST_F(TestNode, get_publishers_subscriptions_info_by_topic) {
// Verify publisher and subscription list has the right data.
EXPECT_EQ(node->get_name(), publisher_list[0].node_name);
EXPECT_EQ(node->get_namespace(), publisher_list[0].node_namespace);
EXPECT_EQ("test_msgs::msg::dds_::BasicTypes_", publisher_list[0].topic_type);
auto publisher_qos_profile = publisher_list[0].qos_profile;
EXPECT_EQ("test_msgs/msg/BasicTypes", publisher_list[0].topic_type);
EXPECT_EQ(RMW_ENDPOINT_PUBLISHER, publisher_list[0].endpoint_type);
auto publisher_qos_profile = publisher_list[0].qos.get_rmw_qos_profile();
assert_qos_profile(qos.get_rmw_qos_profile(), publisher_qos_profile);
EXPECT_EQ(node->get_name(), subscription_list[0].node_name);
EXPECT_EQ(node->get_namespace(), subscription_list[0].node_namespace);
EXPECT_EQ("test_msgs::msg::dds_::BasicTypes_", subscription_list[0].topic_type);
auto subscription_qos_profile = subscription_list[0].qos_profile;
EXPECT_EQ("test_msgs/msg/BasicTypes", subscription_list[0].topic_type);
EXPECT_EQ(RMW_ENDPOINT_SUBSCRIPTION, subscription_list[0].endpoint_type);
auto subscription_qos_profile = subscription_list[0].qos.get_rmw_qos_profile();
assert_qos_profile(qos2.get_rmw_qos_profile(), subscription_qos_profile);

// Error cases
Expand Down

0 comments on commit 40d24ef

Please sign in to comment.