rclcpp_lifecycle  master
C++ ROS Lifecycle Library API
lifecycle_node.hpp
Go to the documentation of this file.
1 // Copyright 2016 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 
36 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
37 #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
38 
39 #include <map>
40 #include <memory>
41 #include <string>
42 #include <utility>
43 #include <vector>
44 
45 #include "rcutils/macros.h"
46 
47 #include "rcl/error_handling.h"
48 #include "rcl/node.h"
49 
50 #include "rcl_interfaces/msg/list_parameters_result.hpp"
51 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
52 #include "rcl_interfaces/msg/parameter_event.hpp"
53 #include "rcl_interfaces/msg/set_parameters_result.hpp"
54 
56 #include "rclcpp/client.hpp"
57 #include "rclcpp/clock.hpp"
58 #include "rclcpp/context.hpp"
59 #include "rclcpp/event.hpp"
60 #include "rclcpp/logger.hpp"
61 #include "rclcpp/macros.hpp"
63 #include "rclcpp/node_options.hpp"
74 #include "rclcpp/parameter.hpp"
75 #include "rclcpp/publisher.hpp"
77 #include "rclcpp/qos.hpp"
78 #include "rclcpp/service.hpp"
79 #include "rclcpp/subscription.hpp"
81 #include "rclcpp/time.hpp"
82 #include "rclcpp/timer.hpp"
83 
89 
91 {
92 
93 // include these here to work around an esoteric Windows error where the namespace
94 // cannot be used in the function declaration below without getting an error like:
95 // 'rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>':
96 // no appropriate default constructor available
97 template<typename AllocatorT>
99 template<typename AllocatorT>
101 
102 template<typename AllocatorT>
105 {
107 }
108 
109 template<typename AllocatorT>
110 SubscriptionOptionsWithAllocator<AllocatorT>
112 {
114 }
115 
117 
121  public std::enable_shared_from_this<LifecycleNode>
122 {
123 public:
125 
126 
127 
132  explicit LifecycleNode(
133  const std::string & node_name,
134  const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
135 
137 
144  const std::string & node_name,
145  const std::string & namespace_,
146  const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
147 
149  virtual ~LifecycleNode();
150 
152 
156  const char *
157  get_name() const;
158 
160 
164  const char *
165  get_namespace() const;
166 
168 
173  get_logger() const;
174 
176 
181  rclcpp::CallbackGroup::SharedPtr
183 
185 
190  get_callback_groups() const;
191 
193 
199  template<typename MessageT, typename AllocatorT = std::allocator<void>>
202  const std::string & topic_name,
203  const rclcpp::QoS & qos,
205  create_default_publisher_options<AllocatorT>()
206  )
207  );
208 
210 
218  template<
219  typename MessageT,
220  typename CallbackT,
221  typename AllocatorT = std::allocator<void>,
222  typename CallbackMessageT =
224  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
225  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
226  CallbackMessageT,
227  AllocatorT
228  >>
231  const std::string & topic_name,
232  const rclcpp::QoS & qos,
233  CallbackT && callback,
235  create_default_subscription_options<AllocatorT>(),
236  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
237  MessageMemoryStrategyT::create_default()
238  )
239  );
240 
242 
247  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
251  CallbackT callback,
252  rclcpp::CallbackGroup::SharedPtr group = nullptr);
253 
255 
258  template<typename ServiceT>
261  const std::string & service_name,
262  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
263  rclcpp::CallbackGroup::SharedPtr group = nullptr);
264 
266 
269  template<typename ServiceT, typename CallbackT>
272  const std::string & service_name,
273  CallbackT && callback,
274  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
275  rclcpp::CallbackGroup::SharedPtr group = nullptr);
276 
278 
282  const rclcpp::ParameterValue &
284  const std::string & name,
285  const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
286  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
287  rcl_interfaces::msg::ParameterDescriptor());
288 
290 
293  template<typename ParameterT>
294  auto
296  const std::string & name,
297  const ParameterT & default_value,
298  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
299  rcl_interfaces::msg::ParameterDescriptor());
300 
302 
305  template<typename ParameterT>
308  const std::string & namespace_,
309  const std::map<std::string, ParameterT> & parameters);
310 
312 
315  template<typename ParameterT>
318  const std::string & namespace_,
319  const std::map<
320  std::string,
322  > & parameters);
323 
325 
329  void
330  undeclare_parameter(const std::string & name);
331 
333 
337  bool
338  has_parameter(const std::string & name) const;
339 
341 
345  rcl_interfaces::msg::SetParametersResult
346  set_parameter(const rclcpp::Parameter & parameter);
347 
349 
355 
357 
361  rcl_interfaces::msg::SetParametersResult
363 
365 
370  get_parameter(const std::string & name) const;
371 
373 
377  bool
379  const std::string & name,
380  rclcpp::Parameter & parameter) const;
381 
383 
386  template<typename ParameterT>
387  bool
388  get_parameter(const std::string & name, ParameterT & parameter) const;
389 
391 
394  template<typename ParameterT>
395  bool
397  const std::string & name,
398  ParameterT & value,
399  const ParameterT & alternative_value) const;
400 
402 
407  get_parameters(const std::vector<std::string> & names) const;
408 
410 
413  template<typename MapValueT>
414  bool
416  const std::string & prefix,
417  std::map<std::string, MapValueT> & values) const;
418 
420 
424  rcl_interfaces::msg::ParameterDescriptor
425  describe_parameter(const std::string & name) const;
426 
428 
433  describe_parameters(const std::vector<std::string> & names) const;
434 
436 
441  get_parameter_types(const std::vector<std::string> & names) const;
442 
444 
448  rcl_interfaces::msg::ListParametersResult
449  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
450 
455 
457 
461  RCUTILS_WARN_UNUSED
462  rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr
465 
467 
471  void
474 
476 
480  [[deprecated("use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
485 
487 
492  get_node_names() const;
493 
495 
500  get_topic_names_and_types(bool no_demangle = false) const;
501 
503 
509 
511 
520  const std::string & node_name,
521  const std::string & namespace_) const;
522 
524 
528  size_t
529  count_publishers(const std::string & topic_name) const;
530 
532 
536  size_t
537  count_subscribers(const std::string & topic_name) const;
538 
540 
545  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
546 
548 
553  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
554 
556  /* The graph Event object is a loan which must be returned.
557  * The Event object is scoped and therefore to return the load just let it go
558  * out of scope.
559  */
561  rclcpp::Event::SharedPtr
562  get_graph_event();
563 
565  /* The given Event must be acquire through the get_graph_event() method.
566  *
567  * \throws InvalidEventError if the given event is nullptr
568  * \throws EventNotRegisteredError if the given event was not acquired with
569  * get_graph_event().
570  */
572  void
574  rclcpp::Event::SharedPtr event,
575  std::chrono::nanoseconds timeout);
576 
578 
582  rclcpp::Clock::SharedPtr
583  get_clock();
584 
586 
590  rclcpp::Clock::ConstSharedPtr
591  get_clock() const;
592 
594 
599  now() const;
600 
602 
606  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
608 
610 
614  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
616 
618 
622  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
624 
626 
630  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
632 
634 
638  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
640 
642 
646  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
648 
650 
654  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
656 
658 
662  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
664 
666 
670  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
672 
674 
678  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
680 
682 
686  const rclcpp::NodeOptions &
687  get_node_options() const;
688 
689  //
690  // LIFECYCLE COMPONENTS
691  //
693 
697  const State &
699 
701 
707 
709 
715 
717  /*
718  * \return the new state after this transition
719  */
721  const State &
722  trigger_transition(const Transition & transition);
723 
725  /*
726  * \param[out] cb_return_code transition callback return code
727  * \return the new state after this transition
728  */
730  const State &
732  const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code);
733 
735  /*
736  * \return the new state after this transition
737  */
739  const State &
740  trigger_transition(uint8_t transition_id);
741 
743  /*
744  * \param[out] cb_return_code transition callback return code
745  * \return the new state after this transition
746  */
748  const State &
750  uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code);
751 
753  /*
754  * \param[out] cb_return_code transition callback return code.
755  * \return the new state after this transition
756  */
758  const State &
759  configure();
760 
762  /*
763  * \param[out] cb_return_code transition callback return code
764  * \return the new state after this transition
765  */
767  const State &
768  configure(LifecycleNodeInterface::CallbackReturn & cb_return_code);
769 
771  /*
772  * \return the new state after this transition
773  */
775  const State &
776  cleanup();
777 
779  /*
780  * \param[out] cb_return_code transition callback return code
781  * \return the new state after this transition
782  */
784  const State &
785  cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code);
786 
788  /*
789  * \return the new state after this transition
790  */
792  const State &
793  activate();
794 
796  /*
797  * \param[out] cb_return_code transition callback return code
798  * \return the new state after this transition
799  */
801  const State &
802  activate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
803 
805  /*
806  * \return the new state after this transition
807  */
809  const State &
810  deactivate();
811 
813  /*
814  * \param[out] cb_return_code transition callback return code
815  * \return the new state after this transition
816  */
818  const State &
819  deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
820 
822  /*
823  * \return the new state after this transition
824  */
826  const State &
827  shutdown();
828 
830  /*
831  * \param[out] cb_return_code transition callback return code
832  * \return the new state after this transition
833  */
835  const State &
836  shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code);
837 
839 
845  bool
846  register_on_configure(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
847 
849 
855  bool
856  register_on_cleanup(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
857 
859 
865  bool
866  register_on_shutdown(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
867 
869 
875  bool
876  register_on_activate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
877 
879 
885  bool
886  register_on_deactivate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
887 
889 
895  bool
896  register_on_error(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
897 
898 protected:
900  void
902 
904  void
906 
907 private:
909 
911  bool
912  group_in_node(rclcpp::CallbackGroup::SharedPtr group);
913 
914  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
915  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
916  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
917  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
918  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
919  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
920  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
921  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
922  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
923  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
924 
925  const rclcpp::NodeOptions node_options_;
926 
927  class LifecycleNodeInterfaceImpl;
929 };
930 
931 } // namespace rclcpp_lifecycle
932 
933 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
934 // Template implementations
936 #endif
937 
938 #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
node_logging_interface.hpp
rclcpp_lifecycle::LifecycleNode::trigger_transition
const State & trigger_transition(const Transition &transition)
Trigger the specified transition.
rclcpp_lifecycle::LifecycleNode::get_name
const char * get_name() const
Get the name of the node.
rclcpp_lifecycle::LifecycleNode::get_clock
rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
rclcpp_lifecycle::LifecycleNode::get_graph_event
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
rclcpp_lifecycle::LifecycleNode::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.
rclcpp::ParameterValue
std::string
std::shared_ptr
callback_group.hpp
rclcpp_lifecycle::LifecycleNode::get_current_state
const State & get_current_state()
Return the current State.
rclcpp_lifecycle::LifecycleNode::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_DISABLE_COPY
#define RCLCPP_DISABLE_COPY(...)
service.hpp
rclcpp_lifecycle::Transition
The Transition class abstract the Lifecycle's states.
Definition: transition.hpp:36
rclcpp_lifecycle::LifecycleNode::declare_parameters
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > &parameters)
Declare and initialize several parameters with the same namespace and type.
Definition: lifecycle_node_impl.hpp:149
rclcpp_lifecycle::create_default_subscription_options
SubscriptionOptionsWithAllocator< AllocatorT > create_default_subscription_options()
Definition: lifecycle_node.hpp:111
std::pair
rclcpp_lifecycle::LifecycleNode::set_parameter
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)
Set a single parameter.
node_graph_interface.hpp
lifecycle_publisher.hpp
rclcpp_lifecycle::LifecycleNode::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.
std::vector
node_clock_interface.hpp
rclcpp_lifecycle::LifecycleNode::now
rclcpp::Time now() const
Returns current time from the time source specified by clock_type.
std::chrono::duration
rclcpp_lifecycle::LifecycleNode::register_on_shutdown
bool register_on_shutdown(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the shutdown callback.
rclcpp_lifecycle::LifecycleNode::get_node_clock_interface
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
node_parameters_interface.hpp
rclcpp::Service
rclcpp_lifecycle::LifecycleNode::activate
const State & activate()
Trigger the activate transition.
rclcpp::Time
rclcpp_lifecycle::LifecycleNode::set_on_parameters_set_callback
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType set_on_parameters_set_callback(rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback)
Register a callback to be called anytime a parameter is about to be changed.
rclcpp_lifecycle::LifecycleNode::get_node_logging_interface
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
rclcpp::SubscriptionOptionsWithAllocator
node_base_interface.hpp
rclcpp_lifecycle::LifecycleNode::count_publishers
size_t count_publishers(const std::string &topic_name) const
Return the number of publishers that are advertised on a given topic.
rclcpp_lifecycle::LifecycleNode::get_logger
rclcpp::Logger get_logger() const
Get the logger of the node.
rclcpp_lifecycle::LifecycleNode::get_node_graph_interface
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
rclcpp_lifecycle::LifecycleNode::get_node_base_interface
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
rclcpp_lifecycle::LifecycleNode::get_node_parameters_interface
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &)>
rclcpp_lifecycle::LifecycleNode::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
rclcpp_lifecycle::LifecycleNode::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_lifecycle::LifecycleNode::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 a map of existing service names to list of service types for a specific node.
node_timers_interface.hpp
rclcpp_lifecycle::LifecycleNode::get_node_timers_interface
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
node_options.hpp
rclcpp::CallbackGroupType
CallbackGroupType
rclcpp_lifecycle::LifecycleNode::add_on_set_parameters_callback
RCUTILS_WARN_UNUSED rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback)
Add a callback for when parameters are being set.
rclcpp_lifecycle::LifecycleNode::register_on_configure
bool register_on_configure(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the configure callback.
rclcpp_lifecycle::LifecycleNode::get_node_topics_interface
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
rclcpp_lifecycle::LifecycleNode::LifecycleNode
LifecycleNode(const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Create a new lifecycle node with the specified name.
rclcpp_lifecycle::LifecycleNode::create_publisher
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< MessageT, AllocatorT > > create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const PublisherOptionsWithAllocator< AllocatorT > &options=(create_default_publisher_options< AllocatorT >()))
Create and return a Publisher.
Definition: lifecycle_node_impl.hpp:44
timer.hpp
rclcpp::Subscription
rclcpp_lifecycle::LifecycleNode::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: lifecycle_node_impl.hpp:84
rclcpp::node_interfaces::OnSetParametersCallbackHandle
logger.hpp
rclcpp_lifecycle::LifecycleNode::deactivate
const State & deactivate()
Trigger the deactivate transition.
subscription_options.hpp
rclcpp::QoS
rclcpp_lifecycle::LifecycleNode::get_node_waitables_interface
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
rclcpp_lifecycle::State
Abstract class for the Lifecycle's states.
Definition: state.hpp:34
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
rclcpp_lifecycle::LifecycleNode::remove_on_set_parameters_callback
void remove_on_set_parameters_callback(const rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
rclcpp_lifecycle
Definition: lifecycle_node.hpp:90
rclcpp_lifecycle::LifecycleNode::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.
rclcpp_lifecycle::LifecycleNode::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.
rclcpp_lifecycle::LifecycleNode::get_available_states
std::vector< State > get_available_states()
Return a list with the available states.
rclcpp_lifecycle::LifecycleNode::~LifecycleNode
virtual ~LifecycleNode()
rclcpp_lifecycle::LifecycleNode::register_on_deactivate
bool register_on_deactivate(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the deactivate callback.
rclcpp_lifecycle::LifecycleNode::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 topic types.
rclcpp_lifecycle::LifecycleNode::create_subscription
std::shared_ptr< SubscriptionT > create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator< AllocatorT > &options=create_default_subscription_options< AllocatorT >(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat=(MessageMemoryStrategyT::create_default()))
Create and return a Subscription.
rclcpp_lifecycle::LifecycleNode::create_callback_group
rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type)
Create and return a callback group.
rclcpp::Logger
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
node_time_source_interface.hpp
rclcpp_lifecycle::create_default_publisher_options
PublisherOptionsWithAllocator< AllocatorT > create_default_publisher_options()
Definition: lifecycle_node.hpp:104
rclcpp_lifecycle::LifecycleNode::undeclare_parameter
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
rclcpp_lifecycle::LifecycleNode::get_node_names
std::vector< std::string > get_node_names() const
Return a vector of existing node names (string).
qos.hpp
rclcpp_lifecycle::LifecycleNode::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: lifecycle_node_impl.hpp:122
std::enable_shared_from_this
node_waitables_interface.hpp
rclcpp_lifecycle::LifecycleNode::add_publisher_handle
void add_publisher_handle(std::shared_ptr< rclcpp_lifecycle::LifecyclePublisherInterface > pub)
rclcpp_lifecycle::LifecycleNode::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())
Declare and initialize a parameter, return the effective value.
rclcpp_lifecycle::LifecycleNode::shutdown
const State & shutdown()
Trigger the shutdown transition.
rclcpp_lifecycle::LifecycleNode::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.
std::map
lifecycle_node_interface.hpp
parameter.hpp
rclcpp_lifecycle::LifecycleNode
LifecycleNode for creating lifecycle components.
Definition: lifecycle_node.hpp:120
lifecycle_node_impl.hpp
publisher.hpp
visibility_control.h
rclcpp_lifecycle::LifecycleNode::get_callback_groups
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
client.hpp
rclcpp_lifecycle::LifecycleNode::has_parameter
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
rclcpp_lifecycle::LifecycleNode::get_namespace
const char * get_namespace() const
Get the namespace of the node.
rclcpp_lifecycle::LifecycleNode::register_on_error
bool register_on_error(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the error callback.
clock.hpp
rclcpp::PublisherOptionsWithAllocator
publisher_options.hpp
rclcpp::Client
rclcpp_lifecycle::LifecycleNode::describe_parameter
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
event.hpp
RCLCPP_LIFECYCLE_PUBLIC
#define RCLCPP_LIFECYCLE_PUBLIC
Definition: visibility_control.h:50
rclcpp_lifecycle::LifecycleNode::cleanup
const State & cleanup()
Trigger the cleanup transition.
node_topics_interface.hpp
rclcpp::message_memory_strategy::MessageMemoryStrategy
rclcpp_lifecycle::LifecycleNode::get_node_time_source_interface
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeParametersInterface implementation.
time.hpp
rmw_qos_profile_t
rclcpp_lifecycle::LifecycleNode::get_topic_names_and_types
std::map< std::string, std::vector< std::string > > get_topic_names_and_types(bool no_demangle=false) const
Return a map of existing topic names to list of topic types.
subscription.hpp
rclcpp::NodeOptions
rclcpp::WallTimer
rclcpp_lifecycle::LifecycleNode::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.
std::allocator
rclcpp_lifecycle::LifecycleNode::register_on_cleanup
bool register_on_cleanup(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the cleanup callback.
state.hpp
rclcpp::Parameter
rclcpp_lifecycle::LifecycleNode::add_timer_handle
void add_timer_handle(std::shared_ptr< rclcpp::TimerBase > timer)
rclcpp_lifecycle::LifecycleNode::configure
const State & configure()
Trigger the configure transition.
rclcpp_lifecycle::LifecycleNode::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.
Definition: lifecycle_node_impl.hpp:98
message_memory_strategy.hpp
rclcpp_lifecycle::LifecycleNode::register_on_activate
bool register_on_activate(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the activate callback.
rclcpp_lifecycle::LifecycleNode::get_parameters
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp_lifecycle::LifecycleNode::get_node_services_interface
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
rclcpp_lifecycle::LifecycleNode::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.
rclcpp_lifecycle::LifecycleNode::get_available_transitions
std::vector< Transition > get_available_transitions()
Return a list with the available transitions.
std::unique_ptr< LifecycleNodeInterfaceImpl >
context.hpp
macros.hpp
node_services_interface.hpp
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Interface class for a managed node.
Definition: lifecycle_node_interface.hpp:42
transition.hpp
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
rclcpp_lifecycle::LifecycleNode::get_node_options
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
rclcpp_lifecycle::LifecycleNode::get_parameter_or
bool get_parameter_or(const std::string &name, ParameterT &value, const ParameterT &alternative_value) const
Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
Definition: lifecycle_node_impl.hpp:222