rclcpp  master
C++ ROS Client Library API
node.hpp
Go to the documentation of this file.
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__NODE_HPP_
16 #define RCLCPP__NODE_HPP_
17 
18 #include <atomic>
19 #include <condition_variable>
20 #include <list>
21 #include <map>
22 #include <memory>
23 #include <mutex>
24 #include <string>
25 #include <tuple>
26 #include <utility>
27 #include <vector>
28 
29 #include "rcutils/macros.h"
30 
31 #include "rcl/error_handling.h"
32 #include "rcl/node.h"
33 
34 #include "rcl_interfaces/msg/list_parameters_result.hpp"
35 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
36 #include "rcl_interfaces/msg/parameter_event.hpp"
37 #include "rcl_interfaces/msg/set_parameters_result.hpp"
38 
40 #include "rclcpp/client.hpp"
41 #include "rclcpp/clock.hpp"
42 #include "rclcpp/context.hpp"
43 #include "rclcpp/event.hpp"
44 #include "rclcpp/logger.hpp"
45 #include "rclcpp/macros.hpp"
57 #include "rclcpp/node_options.hpp"
58 #include "rclcpp/parameter.hpp"
59 #include "rclcpp/publisher.hpp"
61 #include "rclcpp/qos.hpp"
62 #include "rclcpp/service.hpp"
63 #include "rclcpp/subscription.hpp"
66 #include "rclcpp/time.hpp"
67 #include "rclcpp/timer.hpp"
69 
70 namespace rclcpp
71 {
72 
74 class Node : public std::enable_shared_from_this<Node>
75 {
76 public:
78 
79 
80 
86  explicit Node(
87  const std::string & node_name,
88  const NodeOptions & options = NodeOptions());
89 
91 
98  explicit Node(
99  const std::string & node_name,
100  const std::string & namespace_,
101  const NodeOptions & options = NodeOptions());
102 
104  virtual ~Node();
105 
107 
109  const char *
110  get_name() const;
111 
113 
123  const char *
124  get_namespace() const;
125 
127 
132  const char *
133  get_fully_qualified_name() const;
134 
136 
139  get_logger() const;
140 
143  rclcpp::CallbackGroup::SharedPtr
145 
149  get_callback_groups() const;
150 
152 
179  template<
180  typename MessageT,
181  typename AllocatorT = std::allocator<void>,
182  typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
185  const std::string & topic_name,
186  const rclcpp::QoS & qos,
189  );
190 
192 
200  template<
201  typename MessageT,
202  typename CallbackT,
203  typename AllocatorT = std::allocator<void>,
204  typename CallbackMessageT =
207  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
208  CallbackMessageT,
209  AllocatorT
210  >
211  >
214  const std::string & topic_name,
215  const rclcpp::QoS & qos,
216  CallbackT && callback,
219  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
220  MessageMemoryStrategyT::create_default()
221  )
222  );
223 
225 
230  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
234  CallbackT callback,
235  rclcpp::CallbackGroup::SharedPtr group = nullptr);
236 
238 
244  template<typename ServiceT>
247  const std::string & service_name,
248  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
249  rclcpp::CallbackGroup::SharedPtr group = nullptr);
250 
252 
259  template<typename ServiceT, typename CallbackT>
262  const std::string & service_name,
263  CallbackT && callback,
264  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
265  rclcpp::CallbackGroup::SharedPtr group = nullptr);
266 
268 
308  const rclcpp::ParameterValue &
310  const std::string & name,
311  const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
312  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
313  rcl_interfaces::msg::ParameterDescriptor(),
314  bool ignore_override = false);
315 
317 
337  template<typename ParameterT>
338  auto
340  const std::string & name,
341  const ParameterT & default_value,
342  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
343  rcl_interfaces::msg::ParameterDescriptor(),
344  bool ignore_override = false);
345 
347 
382  template<typename ParameterT>
385  const std::string & namespace_,
386  const std::map<std::string, ParameterT> & parameters,
387  bool ignore_overrides = false);
388 
390 
396  template<typename ParameterT>
399  const std::string & namespace_,
400  const std::map<
401  std::string,
403  > & parameters,
404  bool ignore_overrides = false);
405 
407 
418  void
419  undeclare_parameter(const std::string & name);
420 
422 
427  bool
428  has_parameter(const std::string & name) const;
429 
431 
460  rcl_interfaces::msg::SetParametersResult
461  set_parameter(const rclcpp::Parameter & parameter);
462 
464 
500 
502 
532  rcl_interfaces::msg::SetParametersResult
534 
536 
553  get_parameter(const std::string & name) const;
554 
556 
571  bool
572  get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
573 
575 
587  template<typename ParameterT>
588  bool
589  get_parameter(const std::string & name, ParameterT & parameter) const;
590 
592 
606  template<typename ParameterT>
607  bool
609  const std::string & name,
610  ParameterT & parameter,
611  const ParameterT & alternative_value) const;
612 
614 
633  get_parameters(const std::vector<std::string> & names) const;
634 
636 
672  template<typename ParameterT>
673  bool
675  const std::string & prefix,
676  std::map<std::string, ParameterT> & values) const;
677 
679 
696  rcl_interfaces::msg::ParameterDescriptor
697  describe_parameter(const std::string & name) const;
698 
700 
720  describe_parameters(const std::vector<std::string> & names) const;
721 
723 
740  get_parameter_types(const std::vector<std::string> & names) const;
741 
743 
747  rcl_interfaces::msg::ListParametersResult
748  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
749 
754 
756 
818  OnSetParametersCallbackHandle::SharedPtr
820 
822 
845  void
847 
849 
863  [[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
867 
869 
875  get_node_names() const;
876 
878 
885 
887 
894 
896 
905  const std::string & node_name,
906  const std::string & namespace_) const;
907 
909  size_t
910  count_publishers(const std::string & topic_name) const;
911 
913 
919  size_t
920  count_subscribers(const std::string & topic_name) const;
921 
923 
946  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
947 
949 
972  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
973 
975  /* The graph Event object is a loan which must be returned.
976  * The Event object is scoped and therefore to return the loan just let it go
977  * out of scope.
978  */
980  rclcpp::Event::SharedPtr
981  get_graph_event();
982 
984 
995  void
997  rclcpp::Event::SharedPtr event,
998  std::chrono::nanoseconds timeout);
999 
1001 
1005  rclcpp::Clock::SharedPtr
1006  get_clock();
1007 
1009 
1013  rclcpp::Clock::ConstSharedPtr
1014  get_clock() const;
1015 
1017 
1021  Time
1022  now() const;
1023 
1026  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
1028 
1031  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
1033 
1036  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
1038 
1041  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
1043 
1046  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
1048 
1051  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
1053 
1056  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
1058 
1061  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
1063 
1066  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
1068 
1071  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
1073 
1075 
1103  const std::string &
1104  get_sub_namespace() const;
1105 
1107 
1131  const std::string &
1132  get_effective_namespace() const;
1133 
1135 
1173  rclcpp::Node::SharedPtr
1174  create_sub_node(const std::string & sub_namespace);
1175 
1178  const rclcpp::NodeOptions &
1179  get_node_options() const;
1180 
1181 protected:
1183 
1190  Node(
1191  const Node & other,
1192  const std::string & sub_namespace);
1193 
1194 private:
1196 
1198  bool
1199  group_in_node(CallbackGroup::SharedPtr group);
1200 
1201  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
1202  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
1203  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
1204  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
1205  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
1206  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
1207  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
1208  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
1209  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
1210  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1211 
1212  const rclcpp::NodeOptions node_options_;
1213  const std::string sub_namespace_;
1214  const std::string effective_namespace_;
1215 };
1216 
1217 } // namespace rclcpp
1218 
1219 #ifndef RCLCPP__NODE_IMPL_HPP_
1220 // Template implementations
1221 #include "node_impl.hpp"
1222 #endif
1223 
1224 #endif // RCLCPP__NODE_HPP_
rclcpp::Node::set_parameters_atomically
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, all at once.
rclcpp::Node::get_effective_namespace
const std::string & get_effective_namespace() const
Return the effective namespace that is used when creating entities.
node_graph_interface.hpp
node_impl.hpp
callback_group.hpp
rclcpp::Node::now
Time now() const
Returns current time from the time source specified by clock_type.
client.hpp
node_time_source_interface.hpp
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
rclcpp::Publisher
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:51
std::string
std::shared_ptr
rclcpp::Node::get_callback_groups
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
RCLCPP_DISABLE_COPY
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
rclcpp::Node::get_node_clock_interface
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
rclcpp::Node::get_publishers_info_by_topic
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 publishers on a given topic.
node_waitables_interface.hpp
rclcpp::Node::list_parameters
rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const
Return a list of parameters with any of the given prefixes, up to the given depth.
std::pair
rclcpp::Node::create_wall_timer
rclcpp::WallTimer< CallbackT >::SharedPtr create_wall_timer(std::chrono::duration< DurationRepT, DurationT > period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create a timer.
Definition: node_impl.hpp:109
rclcpp::Node::describe_parameter
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
std::vector< rclcpp::CallbackGroup::WeakPtr >
std::chrono::duration
rclcpp::Service
Definition: service.hpp:144
context.hpp
rclcpp::Node::get_node_waitables_interface
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
rclcpp::Node::create_subscription
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()))
Create and return a Subscription.
Definition: node_impl.hpp:91
rclcpp::Time
Definition: time.hpp:31
event.hpp
rclcpp::Node::count_publishers
size_t count_publishers(const std::string &topic_name) const
rclcpp::Node::create_client
rclcpp::Client< ServiceT >::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Client.
rclcpp::SubscriptionOptionsWithAllocator
Structure containing optional configuration for Subscriptions.
Definition: subscription_options.hpp:79
clock.hpp
rclcpp::Node::get_clock
rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
rclcpp::Node::declare_parameter
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value=rclcpp::ParameterValue(), const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false)
Declare and initialize a parameter, return the effective value.
rclcpp::Node::get_namespace
const char * get_namespace() const
Get the namespace of the node.
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &)>
rclcpp::CallbackGroupType
CallbackGroupType
Definition: callback_group.hpp:43
rclcpp::Node::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
publisher.hpp
qos.hpp
rclcpp::Node::create_publisher
std::shared_ptr< PublisherT > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=PublisherOptionsWithAllocator< AllocatorT >())
Create and return a Publisher.
Definition: node_impl.hpp:71
timer.hpp
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
node_topics_interface.hpp
rclcpp::Node::has_parameter
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::node_interfaces::OnSetParametersCallbackHandle
Definition: node_parameters_interface.hpp:36
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:59
rclcpp::Node::get_name
const char * get_name() const
Get the name of the node.
rclcpp::Node::get_node_options
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
rclcpp::Node::get_logger
rclcpp::Logger get_logger() const
Get the logger of the node.
rclcpp::Node::get_node_logging_interface
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
subscription_traits.hpp
macros.hpp
rclcpp::Node
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:74
rclcpp::Node::get_graph_event
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
rclcpp::Node::set_parameters
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)
Set one or more parameters, one at a time.
publisher_options.hpp
node_base_interface.hpp
rclcpp::Logger
Definition: logger.hpp:77
rclcpp::subscription_traits::extract_message_type< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type
typename std::remove_cv< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type type
Definition: subscription_traits.hpp:67
rclcpp::Node::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp::Node::create_service
rclcpp::Service< ServiceT >::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile=rmw_qos_profile_services_default, rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create and return a Service.
Definition: node_impl.hpp:140
rclcpp::Node::get_node_base_interface
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
node_services_interface.hpp
rclcpp::Node::get_node_timers_interface
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
rclcpp::Node::get_service_names_and_types
std::map< std::string, std::vector< std::string > > get_service_names_and_types() const
Return a map of existing service names to list of service types.
std::enable_shared_from_this
rclcpp::Node::get_parameter_or
bool get_parameter_or(const std::string &name, ParameterT &parameter, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
Definition: node_impl.hpp:242
rclcpp::Node::remove_on_set_parameters_callback
void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
rclcpp::Node::count_subscribers
size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers who have created a subscription for a given topic.
RCUTILS_WARN_UNUSED
#define RCUTILS_WARN_UNUSED
rclcpp::Node::get_node_graph_interface
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
std::map
rclcpp::Node::Node
Node(const std::string &node_name, const NodeOptions &options=NodeOptions())
Create a new node with the specified name.
rclcpp::Node::set_on_parameters_set_callback
OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
Register a callback to be called anytime a parameter is about to be changed.
rclcpp::Node::declare_parameters
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > &parameters, bool ignore_overrides=false)
Declare and initialize several parameters with the same namespace and type.
Definition: node_impl.hpp:177
node_clock_interface.hpp
parameter.hpp
subscription_options.hpp
rclcpp::PublisherOptionsWithAllocator
Structure containing optional configuration for Publishers.
Definition: publisher_options.hpp:57
rclcpp::Client
Definition: client.hpp:178
rclcpp::Node::get_topic_names_and_types
std::map< std::string, std::vector< std::string > > get_topic_names_and_types() const
Return a map of existing topic names to list of topic types.
rclcpp::Node::get_fully_qualified_name
const char * get_fully_qualified_name() const
Get the fully-qualified name of the node.
visibility_control.hpp
rclcpp::message_memory_strategy::MessageMemoryStrategy
Default allocation strategy for messages received by subscriptions.
Definition: message_memory_strategy.hpp:41
rclcpp::Node::get_node_services_interface
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
rclcpp::Node::get_sub_namespace
const std::string & get_sub_namespace() const
Return the sub-namespace, if this is a sub-node, otherwise an empty string.
rclcpp::Node::get_parameter_types
std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const
Return a vector of parameter types, one for each of the given names.
logger.hpp
rclcpp::Node::get_node_parameters_interface
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
node_timers_interface.hpp
rmw_qos_profile_t
rclcpp::NodeOptions
Encapsulation of options for node initialization.
Definition: node_options.hpp:34
rclcpp::WallTimer
Definition: timer.hpp:259
std::allocator
rclcpp::Node::get_node_time_source_interface
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeTimeSourceInterface implementation.
rclcpp::Node::wait_for_graph_change
void wait_for_graph_change(rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout)
Wait for a graph event to occur by waiting on an Event to become set.
rclcpp::Node::get_node_topics_interface
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
rclcpp::Parameter
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
rclcpp::Node::create_sub_node
rclcpp::Node::SharedPtr create_sub_node(const std::string &sub_namespace)
Create a sub-node, which will extend the namespace of all entities created with it.
message_memory_strategy.hpp
time.hpp
rclcpp::Node::get_subscriptions_info_by_topic
std::vector< rclcpp::TopicEndpointInfo > get_subscriptions_info_by_topic(const std::string &topic_name, bool no_mangle=false) const
Return the topic endpoint information about subscriptions on a given topic.
rclcpp::Node::create_callback_group
rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type)
Create and return a callback group.
rclcpp::Node::set_parameter
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
rclcpp::Node::get_service_names_and_types_by_node
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
Return the number of publishers that are advertised on a given topic.
macros.h
rclcpp::Node::~Node
virtual ~Node()
service.hpp
rclcpp::Node::add_on_set_parameters_callback
RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:174
subscription.hpp
node_parameters_interface.hpp
rclcpp::Node::describe_parameters
std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const
Return a vector of parameter descriptors, one for each of the given names.
node_logging_interface.hpp
node_options.hpp
rclcpp::Node::undeclare_parameter
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
rclcpp::Node::get_node_names
std::vector< std::string > get_node_names() const
Get the fully-qualified names of all available nodes.