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"
62 #include "rclcpp/logger.hpp"
63 #include "rclcpp/macros.hpp"
65 #include "rclcpp/node_options.hpp"
76 #include "rclcpp/parameter.hpp"
77 #include "rclcpp/publisher.hpp"
79 #include "rclcpp/qos.hpp"
80 #include "rclcpp/service.hpp"
81 #include "rclcpp/subscription.hpp"
83 #include "rclcpp/time.hpp"
84 #include "rclcpp/timer.hpp"
85 
91 
93 {
94 
95 // include these here to work around an esoteric Windows error where the namespace
96 // cannot be used in the function declaration below without getting an error like:
97 // 'rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>':
98 // no appropriate default constructor available
99 template<typename AllocatorT>
101 template<typename AllocatorT>
103 
104 template<typename AllocatorT>
107 {
109 }
110 
111 template<typename AllocatorT>
112 SubscriptionOptionsWithAllocator<AllocatorT>
114 {
116 }
117 
119 
123  public std::enable_shared_from_this<LifecycleNode>
124 {
125 public:
127 
128 
129 
135  explicit LifecycleNode(
136  const std::string & node_name,
137  const rclcpp::NodeOptions & options = rclcpp::NodeOptions(),
138  bool enable_communication_interface = true);
139 
141 
149  const std::string & node_name,
150  const std::string & namespace_,
151  const rclcpp::NodeOptions & options = rclcpp::NodeOptions(),
152  bool enable_communication_interface = true);
153 
155  virtual ~LifecycleNode();
156 
158 
162  const char *
163  get_name() const;
164 
166 
170  const char *
171  get_namespace() const;
172 
174 
179  get_logger() const;
180 
182 
190  rclcpp::CallbackGroup::SharedPtr
192  rclcpp::CallbackGroupType group_type,
193  bool automatically_add_to_executor_with_node = true);
194 
196 
201  get_callback_groups() const;
202 
204 
210  template<typename MessageT, typename AllocatorT = std::allocator<void>>
213  const std::string & topic_name,
214  const rclcpp::QoS & qos,
216  create_default_publisher_options<AllocatorT>()
217  )
218  );
219 
221 
229  template<
230  typename MessageT,
231  typename CallbackT,
232  typename AllocatorT = std::allocator<void>,
233  typename CallbackMessageT =
235  typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
236  typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
237  CallbackMessageT,
238  AllocatorT
239  >>
242  const std::string & topic_name,
243  const rclcpp::QoS & qos,
244  CallbackT && callback,
246  create_default_subscription_options<AllocatorT>(),
247  typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
248  MessageMemoryStrategyT::create_default()
249  )
250  );
251 
253 
258  template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
262  CallbackT callback,
263  rclcpp::CallbackGroup::SharedPtr group = nullptr);
264 
266 
269  template<typename ServiceT>
272  const std::string & service_name,
273  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
274  rclcpp::CallbackGroup::SharedPtr group = nullptr);
275 
277 
280  template<typename ServiceT, typename CallbackT>
283  const std::string & service_name,
284  CallbackT && callback,
285  const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
286  rclcpp::CallbackGroup::SharedPtr group = nullptr);
287 
289 
292  template<typename AllocatorT = std::allocator<void>>
294  const std::string & topic_name,
295  const std::string & topic_type,
296  const rclcpp::QoS & qos,
299  )
300  );
301 
303 
306  template<typename AllocatorT = std::allocator<void>>
308  const std::string & topic_name,
309  const std::string & topic_type,
310  const rclcpp::QoS & qos,
314  )
315  );
316 
318 
322  const rclcpp::ParameterValue &
324  const std::string & name,
325  const rclcpp::ParameterValue & default_value,
326  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
327  rcl_interfaces::msg::ParameterDescriptor(),
328  bool ignore_override = false);
329 
331 
335  const rclcpp::ParameterValue &
337  const std::string & name,
339  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
340  rcl_interfaces::msg::ParameterDescriptor{},
341  bool ignore_override = false);
342 
344  [[deprecated(
345  "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
346  "If you want to declare a parameter that won't change type without a default value use:\n" \
347  "`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
348  "If you want to declare a parameter that can dynamically change type use:\n" \
349  "```\n" \
350  "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
351  "descriptor.dynamic_typing = true;\n" \
352  "node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
353  "```"
354  )]]
356  const rclcpp::ParameterValue &
357  declare_parameter(const std::string & name);
358 
360 
363  template<typename ParameterT>
364  auto
366  const std::string & name,
367  const ParameterT & default_value,
368  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
369  rcl_interfaces::msg::ParameterDescriptor(),
370  bool ignore_override = false);
371 
373 
376  template<typename ParameterT>
377  auto
379  const std::string & name,
380  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
381  rcl_interfaces::msg::ParameterDescriptor(),
382  bool ignore_override = false);
383 
385 
388  template<typename ParameterT>
391  const std::string & namespace_,
392  const std::map<std::string, ParameterT> & parameters);
393 
395 
398  template<typename ParameterT>
401  const std::string & namespace_,
402  const std::map<
403  std::string,
405  > & parameters);
406 
408 
412  void
413  undeclare_parameter(const std::string & name);
414 
416 
420  bool
421  has_parameter(const std::string & name) const;
422 
424 
428  rcl_interfaces::msg::SetParametersResult
429  set_parameter(const rclcpp::Parameter & parameter);
430 
432 
438 
440 
444  rcl_interfaces::msg::SetParametersResult
446 
448 
453  get_parameter(const std::string & name) const;
454 
456 
460  bool
462  const std::string & name,
463  rclcpp::Parameter & parameter) const;
464 
466 
469  template<typename ParameterT>
470  bool
471  get_parameter(const std::string & name, ParameterT & parameter) const;
472 
474 
477  template<typename ParameterT>
478  bool
480  const std::string & name,
481  ParameterT & value,
482  const ParameterT & alternative_value) const;
483 
485 
490  get_parameters(const std::vector<std::string> & names) const;
491 
493 
496  template<typename MapValueT>
497  bool
499  const std::string & prefix,
500  std::map<std::string, MapValueT> & values) const;
501 
503 
507  rcl_interfaces::msg::ParameterDescriptor
508  describe_parameter(const std::string & name) const;
509 
511 
516  describe_parameters(const std::vector<std::string> & names) const;
517 
519 
524  get_parameter_types(const std::vector<std::string> & names) const;
525 
527 
531  rcl_interfaces::msg::ListParametersResult
532  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
533 
538 
540 
544  RCUTILS_WARN_UNUSED
545  rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr
548 
550 
554  void
557 
559 
564  get_node_names() const;
565 
567 
572  get_topic_names_and_types(bool no_demangle = false) const;
573 
575 
581 
583 
592  const std::string & node_name,
593  const std::string & namespace_) const;
594 
596 
600  size_t
601  count_publishers(const std::string & topic_name) const;
602 
604 
608  size_t
609  count_subscribers(const std::string & topic_name) const;
610 
612 
617  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
618 
620 
625  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
626 
628  /* The graph Event object is a loan which must be returned.
629  * The Event object is scoped and therefore to return the load just let it go
630  * out of scope.
631  */
633  rclcpp::Event::SharedPtr
634  get_graph_event();
635 
637  /* The given Event must be acquire through the get_graph_event() method.
638  *
639  * \throws InvalidEventError if the given event is nullptr
640  * \throws EventNotRegisteredError if the given event was not acquired with
641  * get_graph_event().
642  */
644  void
646  rclcpp::Event::SharedPtr event,
647  std::chrono::nanoseconds timeout);
648 
650 
654  rclcpp::Clock::SharedPtr
655  get_clock();
656 
658 
662  rclcpp::Clock::ConstSharedPtr
663  get_clock() const;
664 
666 
671  now() const;
672 
674 
678  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
680 
682 
686  rclcpp::node_interfaces::NodeClockInterface::SharedPtr
688 
690 
694  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
696 
698 
702  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
704 
706 
710  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
712 
714 
718  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
720 
722 
726  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
728 
730 
734  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
736 
738 
742  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
744 
746 
750  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
752 
754 
758  const rclcpp::NodeOptions &
759  get_node_options() const;
760 
761  //
762  // LIFECYCLE COMPONENTS
763  //
765 
769  const State &
771 
773 
779 
781 
787 
789 
795 
797  /*
798  * \return the new state after this transition
799  */
801  const State &
802  trigger_transition(const Transition & transition);
803 
805  /*
806  * \param[out] cb_return_code transition callback return code
807  * \return the new state after this transition
808  */
810  const State &
812  const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code);
813 
815  /*
816  * \return the new state after this transition
817  */
819  const State &
820  trigger_transition(uint8_t transition_id);
821 
823  /*
824  * \param[out] cb_return_code transition callback return code
825  * \return the new state after this transition
826  */
828  const State &
830  uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code);
831 
833  /*
834  * \param[out] cb_return_code transition callback return code.
835  * \return the new state after this transition
836  */
838  const State &
839  configure();
840 
842  /*
843  * \param[out] cb_return_code transition callback return code
844  * \return the new state after this transition
845  */
847  const State &
848  configure(LifecycleNodeInterface::CallbackReturn & cb_return_code);
849 
851  /*
852  * \return the new state after this transition
853  */
855  const State &
856  cleanup();
857 
859  /*
860  * \param[out] cb_return_code transition callback return code
861  * \return the new state after this transition
862  */
864  const State &
865  cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code);
866 
868  /*
869  * \return the new state after this transition
870  */
872  const State &
873  activate();
874 
876  /*
877  * \param[out] cb_return_code transition callback return code
878  * \return the new state after this transition
879  */
881  const State &
882  activate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
883 
885  /*
886  * \return the new state after this transition
887  */
889  const State &
890  deactivate();
891 
893  /*
894  * \param[out] cb_return_code transition callback return code
895  * \return the new state after this transition
896  */
898  const State &
899  deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
900 
902  /*
903  * \return the new state after this transition
904  */
906  const State &
907  shutdown();
908 
910  /*
911  * \param[out] cb_return_code transition callback return code
912  * \return the new state after this transition
913  */
915  const State &
916  shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code);
917 
919 
925  bool
926  register_on_configure(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
927 
929 
935  bool
936  register_on_cleanup(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
937 
939 
945  bool
946  register_on_shutdown(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
947 
949 
955  bool
956  register_on_activate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
957 
959 
965  bool
966  register_on_deactivate(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
967 
969 
975  bool
976  register_on_error(std::function<LifecycleNodeInterface::CallbackReturn(const State &)> fcn);
977 
978 protected:
980  void
982 
984  void
986 
987 private:
989 
990  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
991  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_;
992  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
993  rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
994  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
995  rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
996  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
997  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
998  rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
999  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
1000 
1001  const rclcpp::NodeOptions node_options_;
1002 
1003  class LifecycleNodeInterfaceImpl;
1005 };
1006 
1007 } // namespace rclcpp_lifecycle
1008 
1009 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
1010 // Template implementations
1012 #endif
1013 
1014 #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:211
rclcpp_lifecycle::create_default_subscription_options
SubscriptionOptionsWithAllocator< AllocatorT > create_default_subscription_options()
Definition: lifecycle_node.hpp:113
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.
generic_subscription.hpp
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::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.
rclcpp_lifecycle::LifecycleNode::get_parameter
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
std::function
rclcpp_lifecycle::LifecycleNode::create_generic_publisher
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 >()))
Create and return a GenericPublisher.
Definition: lifecycle_node_impl.hpp:137
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::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:46
timer.hpp
extract_message_type< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > >::type
typename std::remove_cv_t< std::remove_reference_t< rclcpp::function_traits::function_traits< CallbackT >::template argument_type< 0 > > > type
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:86
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::LifecycleNode::get_transition_graph
std::vector< Transition > get_transition_graph()
Return a list with all the transitions.
rclcpp_lifecycle
Definition: lifecycle_node.hpp:92
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.
generic_publisher.hpp
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::Logger
node_time_source_interface.hpp
rclcpp_lifecycle::create_default_publisher_options
PublisherOptionsWithAllocator< AllocatorT > create_default_publisher_options()
Definition: lifecycle_node.hpp:106
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:124
std::enable_shared_from_this
node_waitables_interface.hpp
rclcpp_lifecycle::LifecycleNode::LifecycleNode
LifecycleNode(const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions(), bool enable_communication_interface=true)
Create a new lifecycle node with the specified name.
rclcpp_lifecycle::LifecycleNode::add_publisher_handle
void add_publisher_handle(std::shared_ptr< rclcpp_lifecycle::LifecyclePublisherInterface > pub)
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:122
lifecycle_node_impl.hpp
publisher.hpp
rclcpp_lifecycle::LifecycleNode::create_callback_group
rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true)
Create and return a callback group.
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::ParameterType
ParameterType
rclcpp_lifecycle::LifecycleNode::get_namespace
const char * get_namespace() const
Get the namespace of the node.
rclcpp_lifecycle::LifecycleNode::declare_parameter
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)
Declare and initialize a parameter, return the effective value.
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< AllocatorT >
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.
rclcpp_lifecycle::LifecycleNode::create_generic_subscription
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 >()))
Create and return a GenericSubscription.
Definition: lifecycle_node_impl.hpp:156
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:100
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 current 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:284