Program Listing for File node_graph_interface.hpp
↰ Return to documentation for file (include/rclcpp/node_interfaces/node_graph_interface.hpp
)
// Copyright 2016-2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#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 <tuple>
#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
};
class TopicEndpointInfo
{
public:
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());
}
RCLCPP_PUBLIC
std::string &
node_name();
RCLCPP_PUBLIC
const std::string &
node_name() const;
RCLCPP_PUBLIC
std::string &
node_namespace();
RCLCPP_PUBLIC
const std::string &
node_namespace() const;
RCLCPP_PUBLIC
std::string &
topic_type();
RCLCPP_PUBLIC
const std::string &
topic_type() const;
RCLCPP_PUBLIC
rclcpp::EndpointType &
endpoint_type();
RCLCPP_PUBLIC
const rclcpp::EndpointType &
endpoint_type() const;
RCLCPP_PUBLIC
std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
endpoint_gid();
RCLCPP_PUBLIC
const std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
endpoint_gid() const;
RCLCPP_PUBLIC
rclcpp::QoS &
qos_profile();
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
{
class NodeGraphInterface
{
public:
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeGraphInterface)
RCLCPP_PUBLIC
virtual
~NodeGraphInterface() = default;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_topic_names_and_types(bool no_demangle = false) const = 0;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_service_names_and_types() const = 0;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_service_names_and_types_by_node(
const std::string & node_name,
const std::string & namespace_) const = 0;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_client_names_and_types_by_node(
const std::string & node_name,
const std::string & namespace_) const = 0;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_publisher_names_and_types_by_node(
const std::string & node_name,
const std::string & namespace_,
bool no_demangle = false) const = 0;
RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>>
get_subscriber_names_and_types_by_node(
const std::string & node_name,
const std::string & namespace_,
bool no_demangle = false) const = 0;
/*
* The returned names are the actual names after remap rules applied.
*/
RCLCPP_PUBLIC
virtual
std::vector<std::string>
get_node_names() const = 0;
/*
* The returned names are the actual names after remap rules applied.
* The enclaves contain the runtime security artifacts, those can be
* used to establish secured network.
* See https://design.ros2.org/articles/ros2_security_enclaves.html
*/
RCLCPP_PUBLIC
virtual
std::vector<std::tuple<std::string, std::string, std::string>>
get_node_names_with_enclaves() const = 0;
/*
* The returned names are the actual names after remap rules applied.
*/
RCLCPP_PUBLIC
virtual
std::vector<std::pair<std::string, std::string>>
get_node_names_and_namespaces() const = 0;
/*
* \param[in] topic_name the actual topic name used; it will not be automatically remapped.
*/
RCLCPP_PUBLIC
virtual
size_t
count_publishers(const std::string & topic_name) const = 0;
/*
* \param[in] topic_name the actual topic name used; it will not be automatically remapped.
*/
RCLCPP_PUBLIC
virtual
size_t
count_subscribers(const std::string & topic_name) const = 0;
RCLCPP_PUBLIC
virtual
const rcl_guard_condition_t *
get_graph_guard_condition() const = 0;
RCLCPP_PUBLIC
virtual
void
notify_graph_change() = 0;
RCLCPP_PUBLIC
virtual
void
notify_shutdown() = 0;
RCLCPP_PUBLIC
virtual
rclcpp::Event::SharedPtr
get_graph_event() = 0;
RCLCPP_PUBLIC
virtual
void
wait_for_graph_change(
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout) = 0;
RCLCPP_PUBLIC
virtual
size_t
count_graph_users() const = 0;
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
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
} // namespace rclcpp
#endif // RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_