Skip to content

Commit

Permalink
Implement functions to get publisher and subcription informations lik…
Browse files Browse the repository at this point in the history
…e QoS policies from topic name (#960)

Signed-off-by: Barry Xu <Barry.Xu@sony.com>
Signed-off-by: Miaofei <miaofei@amazon.com>
Co-authored-by: Miaofei Mei <ameision@hotmail.com>
  • Loading branch information
Barry-Xu-2018 and mm318 committed Feb 14, 2020
1 parent 7c1721a commit 2d9c6ea
Show file tree
Hide file tree
Showing 9 changed files with 530 additions and 1 deletion.
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,7 @@ if(BUILD_TESTING)
"rmw"
"rosidl_generator_cpp"
"rosidl_typesupport_cpp"
"test_msgs"
)
target_link_libraries(test_node ${PROJECT_NAME})
endif()
Expand Down
52 changes: 52 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -867,6 +867,58 @@ class Node : public std::enable_shared_from_this<Node>
size_t
count_subscribers(const std::string & topic_name) const;

/// Return the topic endpoint information about publishers on a given topic.
/**
* The returned parameter is a list of topic endpoint information, where each item will contain
* the node name, node namespace, topic type, endpoint type, topic endpoint's GID, and its QoS
* profile.
*
* When the `no_mangle` parameter is `true`, the provided `topic_name` should be a valid topic
* name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps).
* When the `no_mangle` parameter is `false`, the provided `topic_name` should follow
* ROS topic name conventions.
*
* `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.
* The queried `topic_name` is not remapped.
*
* \param[in] topic_name the topic_name on which to find the publishers.
* \param[in] no_mangle if `true`, `topic_name` needs to be a valid middleware topic name,
* otherwise it should be a valid ROS topic name. Defaults to `false`.
* \return a list of TopicEndpointInfo 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::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;

/// Return the topic endpoint information about subscriptions on a given topic.
/**
* The returned parameter is a list of topic endpoint information, where each item will contain
* the node name, node namespace, topic type, endpoint type, topic endpoint's GID, and its QoS
* profile.
*
* When the `no_mangle` parameter is `true`, the provided `topic_name` should be a valid topic
* name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps).
* When the `no_mangle` parameter is `false`, the provided `topic_name` should follow
* ROS topic name conventions.
*
* `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.
* The queried `topic_name` is not remapped.
*
* \param[in] topic_name the topic_name on which to find the subscriptions.
* \param[in] no_mangle if `true`, `topic_name` needs to be a valid middleware topic name,
* otherwise it should be a valid ROS topic name. Defaults to `false`.
* \return a list of TopicEndpointInfo 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::TopicEndpointInfo>
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;

/// Return a graph event, which will be set anytime a graph change occurs.
/* The graph Event object is a loan which must be returned.
* The Event object is scoped and therefore to return the loan just let it go
Expand Down
13 changes: 13 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_graph.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +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_endpoint_info_array.h"

namespace rclcpp
{
Expand Down Expand Up @@ -117,6 +118,18 @@ class NodeGraph : public NodeGraphInterface
size_t
count_graph_users() override;

RCLCPP_PUBLIC
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::TopicEndpointInfo>
get_subscriptions_info_by_topic(
const std::string & topic_name,
bool no_mangle = false) const override;

private:
RCLCPP_DISABLE_COPY(NodeGraph)

Expand Down
118 changes: 118 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,20 +15,120 @@
#ifndef RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
#define RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_

#include <algorithm>
#include <array>
#include <chrono>
#include <map>
#include <string>
#include <utility>
#include <vector>

#include "rcl/graph.h"
#include "rcl/guard_condition.h"

#include "rclcpp/event.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"

namespace rclcpp
{

enum class EndpointType
{
Invalid = RMW_ENDPOINT_INVALID,
Publisher = RMW_ENDPOINT_PUBLISHER,
Subscription = RMW_ENDPOINT_SUBSCRIPTION
};

/**
* Struct that contains topic endpoint information like the associated node name, node namespace,
* topic type, endpoint type, endpoint GID, and its QoS.
*/
class TopicEndpointInfo
{
public:
/// Construct a TopicEndpointInfo from a rcl_topic_endpoint_info_t.
RCLCPP_PUBLIC
explicit TopicEndpointInfo(const rcl_topic_endpoint_info_t & info)
: node_name_(info.node_name),
node_namespace_(info.node_namespace),
topic_type_(info.topic_type),
endpoint_type_(static_cast<rclcpp::EndpointType>(info.endpoint_type)),
qos_profile_({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());
}

/// Get a mutable reference to the node name.
RCLCPP_PUBLIC
std::string &
node_name();

/// Get a const reference to the node name.
RCLCPP_PUBLIC
const std::string &
node_name() const;

/// Get a mutable reference to the node namespace.
RCLCPP_PUBLIC
std::string &
node_namespace();

/// Get a const reference to the node namespace.
RCLCPP_PUBLIC
const std::string &
node_namespace() const;

/// Get a mutable reference to the topic type string.
RCLCPP_PUBLIC
std::string &
topic_type();

/// Get a const reference to the topic type string.
RCLCPP_PUBLIC
const std::string &
topic_type() const;

/// Get a mutable reference to the topic endpoint type.
RCLCPP_PUBLIC
rclcpp::EndpointType &
endpoint_type();

/// Get a const reference to the topic endpoint type.
RCLCPP_PUBLIC
const rclcpp::EndpointType &
endpoint_type() const;

/// Get a mutable reference to the GID of the topic endpoint.
RCLCPP_PUBLIC
std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
endpoint_gid();

/// Get a const reference to the GID of the topic endpoint.
RCLCPP_PUBLIC
const std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
endpoint_gid() const;

/// Get a mutable reference to the QoS profile of the topic endpoint.
RCLCPP_PUBLIC
rclcpp::QoS &
qos_profile();

/// Get a const reference to the QoS profile of the topic endpoint.
RCLCPP_PUBLIC
const rclcpp::QoS &
qos_profile() const;

private:
std::string node_name_;
std::string node_namespace_;
std::string topic_type_;
rclcpp::EndpointType endpoint_type_;
std::array<uint8_t, RMW_GID_STORAGE_SIZE> endpoint_gid_;
rclcpp::QoS qos_profile_;
};

namespace node_interfaces
{

Expand Down Expand Up @@ -150,6 +250,24 @@ class NodeGraphInterface
virtual
size_t
count_graph_users() = 0;

/// Return the topic endpoint information about publishers on a given topic.
/**
* \sa rclcpp::Node::get_publishers_info_by_topic
*/
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;

/// Return the topic endpoint information about subscriptions on a given topic.
/**
* \sa rclcpp::Node::get_subscriptions_info_by_topic
*/
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::TopicEndpointInfo>
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
};

} // namespace node_interfaces
Expand Down
12 changes: 12 additions & 0 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,18 @@ Node::count_subscribers(const std::string & topic_name) const
return node_graph_->count_subscribers(topic_name);
}

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::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);
}

const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
Node::get_callback_groups() const
{
Expand Down
Loading

0 comments on commit 2d9c6ea

Please sign in to comment.