Program Listing for File node.hpp
↰ Return to documentation for file (include/rclcpp/node.hpp
)
// Copyright 2014 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_HPP_
#define RCLCPP__NODE_HPP_
#include <atomic>
#include <condition_variable>
#include <functional>
#include <list>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <tuple>
#include <utility>
#include <vector>
#include "rcutils/macros.h"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl_interfaces/msg/list_parameters_result.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"
#include "rclcpp/callback_group.hpp"
#include "rclcpp/client.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/event.hpp"
#include "rclcpp/generic_publisher.hpp"
#include "rclcpp/generic_subscription.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/message_memory_strategy.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/node_interfaces/node_type_descriptions_interface.hpp"
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
#include "rclcpp/node_options.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/subscription_options.hpp"
#include "rclcpp/subscription_traits.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/timer.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
{
class Node : public std::enable_shared_from_this<Node>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Node)
RCLCPP_PUBLIC
explicit Node(
const std::string & node_name,
const NodeOptions & options = NodeOptions());
RCLCPP_PUBLIC
explicit Node(
const std::string & node_name,
const std::string & namespace_,
const NodeOptions & options = NodeOptions());
RCLCPP_PUBLIC
virtual ~Node();
RCLCPP_PUBLIC
const char *
get_name() const;
RCLCPP_PUBLIC
const char *
get_namespace() const;
RCLCPP_PUBLIC
const char *
get_fully_qualified_name() const;
RCLCPP_PUBLIC
rclcpp::Logger
get_logger() const;
RCLCPP_PUBLIC
rclcpp::CallbackGroup::SharedPtr
create_callback_group(
rclcpp::CallbackGroupType group_type,
bool automatically_add_to_executor_with_node = true);
RCLCPP_PUBLIC
void
for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name,
const rclcpp::QoS & qos,
const PublisherOptionsWithAllocator<AllocatorT> & options =
PublisherOptionsWithAllocator<AllocatorT>()
);
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
SubscriptionOptionsWithAllocator<AllocatorT>(),
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
);
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename ServiceT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename ServiceT, typename CallbackT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);
template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
);
template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
)
);
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor{},
bool ignore_override = false);
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const ParameterT & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<std::string, ParameterT> & parameters,
bool ignore_overrides = false);
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<
std::string,
std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
> & parameters,
bool ignore_overrides = false);
RCLCPP_PUBLIC
void
undeclare_parameter(const std::string & name);
RCLCPP_PUBLIC
bool
has_parameter(const std::string & name) const;
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameter(const rclcpp::Parameter & parameter);
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
rclcpp::Parameter
get_parameter(const std::string & name) const;
RCLCPP_PUBLIC
bool
get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
template<typename ParameterT>
bool
get_parameter(const std::string & name, ParameterT & parameter) const;
template<typename ParameterT>
bool
get_parameter_or(
const std::string & name,
ParameterT & parameter,
const ParameterT & alternative_value) const;
template<typename ParameterT>
ParameterT
get_parameter_or(
const std::string & name,
const ParameterT & alternative_value) const;
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
template<typename ParameterT>
bool
get_parameters(
const std::string & prefix,
std::map<std::string, ParameterT> & values) const;
RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterDescriptor
describe_parameter(const std::string & name) const;
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(const std::vector<std::string> & names) const;
RCLCPP_PUBLIC
std::vector<uint8_t>
get_parameter_types(const std::vector<std::string> & names) const;
RCLCPP_PUBLIC
rcl_interfaces::msg::ListParametersResult
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
using PreSetParametersCallbackHandle =
rclcpp::node_interfaces::PreSetParametersCallbackHandle;
using PreSetParametersCallbackType =
rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
using OnSetParametersCallbackHandle =
rclcpp::node_interfaces::OnSetParametersCallbackHandle;
using OnSetParametersCallbackType =
rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
using OnParametersSetCallbackType [[deprecated("use OnSetParametersCallbackType instead")]] =
OnSetParametersCallbackType;
using PostSetParametersCallbackHandle =
rclcpp::node_interfaces::PostSetParametersCallbackHandle;
using PostSetParametersCallbackType =
rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
RCLCPP_PUBLIC
RCUTILS_WARN_UNUSED
PreSetParametersCallbackHandle::SharedPtr
add_pre_set_parameters_callback(PreSetParametersCallbackType callback);
RCLCPP_PUBLIC
RCUTILS_WARN_UNUSED
OnSetParametersCallbackHandle::SharedPtr
add_on_set_parameters_callback(OnSetParametersCallbackType callback);
RCLCPP_PUBLIC
RCUTILS_WARN_UNUSED
PostSetParametersCallbackHandle::SharedPtr
add_post_set_parameters_callback(PostSetParametersCallbackType callback);
RCLCPP_PUBLIC
void
remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle * const handler);
RCLCPP_PUBLIC
void
remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler);
RCLCPP_PUBLIC
void
remove_post_set_parameters_callback(const PostSetParametersCallbackHandle * const handler);
RCLCPP_PUBLIC
std::vector<std::string>
get_node_names() const;
RCLCPP_PUBLIC
std::map<std::string, std::vector<std::string>>
get_topic_names_and_types() const;
RCLCPP_PUBLIC
std::map<std::string, std::vector<std::string>>
get_service_names_and_types() const;
RCLCPP_PUBLIC
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;
RCLCPP_PUBLIC
size_t
count_publishers(const std::string & topic_name) const;
RCLCPP_PUBLIC
size_t
count_subscribers(const std::string & topic_name) const;
RCLCPP_PUBLIC
std::vector<rclcpp::TopicEndpointInfo>
get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
RCLCPP_PUBLIC
std::vector<rclcpp::TopicEndpointInfo>
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
/* 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
* out of scope.
*/
RCLCPP_PUBLIC
rclcpp::Event::SharedPtr
get_graph_event();
RCLCPP_PUBLIC
void
wait_for_graph_change(
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout);
RCLCPP_PUBLIC
rclcpp::Clock::SharedPtr
get_clock();
RCLCPP_PUBLIC
rclcpp::Clock::ConstSharedPtr
get_clock() const;
RCLCPP_PUBLIC
Time
now() const;
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
get_node_base_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeClockInterface::SharedPtr
get_node_clock_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
get_node_graph_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
get_node_logging_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
get_node_timers_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
get_node_topics_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
get_node_services_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
get_node_waitables_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
get_node_parameters_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
get_node_time_source_interface();
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr
get_node_type_descriptions_interface();
RCLCPP_PUBLIC
const std::string &
get_sub_namespace() const;
RCLCPP_PUBLIC
const std::string &
get_effective_namespace() const;
RCLCPP_PUBLIC
rclcpp::Node::SharedPtr
create_sub_node(const std::string & sub_namespace);
RCLCPP_PUBLIC
const rclcpp::NodeOptions &
get_node_options() const;
protected:
RCLCPP_PUBLIC
Node(
const Node & other,
const std::string & sub_namespace);
private:
RCLCPP_DISABLE_COPY(Node)
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
const rclcpp::NodeOptions node_options_;
const std::string sub_namespace_;
const std::string effective_namespace_;
// See node.cpp for more details.
class BackportMembers;
static BackportMembers backport_members_;
};
} // namespace rclcpp
#ifndef RCLCPP__NODE_IMPL_HPP_
// Template implementations
#include "node_impl.hpp"
#endif
#endif // RCLCPP__NODE_HPP_