rclcpp_lifecycle
master
C++ ROS Lifecycle Library API
|
Go to the documentation of this file.
36 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
37 #define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
45 #include "rcutils/macros.h"
47 #include "rcl/error_handling.h"
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"
97 template<
typename AllocatorT>
99 template<
typename AllocatorT>
102 template<
typename AllocatorT>
109 template<
typename AllocatorT>
110 SubscriptionOptionsWithAllocator<AllocatorT>
181 rclcpp::CallbackGroup::SharedPtr
199 template<
typename MessageT,
typename AllocatorT = std::allocator<
void>>
205 create_default_publisher_options<AllocatorT>()
222 typename CallbackMessageT =
233 CallbackT && callback,
235 create_default_subscription_options<AllocatorT>(),
236 typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
237 MessageMemoryStrategyT::create_default()
247 template<
typename DurationRepT =
int64_t,
typename DurationT = std::milli,
typename CallbackT>
252 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
258 template<
typename ServiceT>
263 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
269 template<
typename ServiceT,
typename CallbackT>
273 CallbackT && callback,
275 rclcpp::CallbackGroup::SharedPtr group =
nullptr);
286 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
287 rcl_interfaces::msg::ParameterDescriptor());
293 template<
typename ParameterT>
297 const ParameterT & default_value,
298 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
299 rcl_interfaces::msg::ParameterDescriptor());
305 template<
typename ParameterT>
315 template<
typename ParameterT>
345 rcl_interfaces::msg::SetParametersResult
361 rcl_interfaces::msg::SetParametersResult
386 template<
typename ParameterT>
394 template<
typename ParameterT>
399 const ParameterT & alternative_value)
const;
413 template<
typename MapValueT>
424 rcl_interfaces::msg::ParameterDescriptor
448 rcl_interfaces::msg::ListParametersResult
462 rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr
480 [[deprecated(
"use add_on_set_parameters_callback(OnParametersSetCallbackType callback) instead")]]
561 rclcpp::Event::SharedPtr
574 rclcpp::Event::SharedPtr event,
582 rclcpp::Clock::SharedPtr
590 rclcpp::Clock::ConstSharedPtr
606 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
614 rclcpp::node_interfaces::NodeClockInterface::SharedPtr
622 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
630 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
638 rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
646 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
654 rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
662 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
670 rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
678 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
732 const Transition & transition, LifecycleNodeInterface::CallbackReturn & cb_return_code);
750 uint8_t transition_id, LifecycleNodeInterface::CallbackReturn & cb_return_code);
768 configure(LifecycleNodeInterface::CallbackReturn & cb_return_code);
785 cleanup(LifecycleNodeInterface::CallbackReturn & cb_return_code);
802 activate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
819 deactivate(LifecycleNodeInterface::CallbackReturn & cb_return_code);
836 shutdown(LifecycleNodeInterface::CallbackReturn & cb_return_code);
912 group_in_node(rclcpp::CallbackGroup::SharedPtr group);
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_;
927 class LifecycleNodeInterfaceImpl;
933 #ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
938 #endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
const State & trigger_transition(const Transition &transition)
Trigger the specified transition.
const char * get_name() const
Get the name of the node.
rclcpp::Clock::SharedPtr get_clock()
Get a clock as a non-const shared pointer which is managed by the node.
rclcpp::Event::SharedPtr get_graph_event()
Return a graph event, which will be set anytime a graph change occurs.
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.
const State & get_current_state()
Return the current State.
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.
#define RCLCPP_DISABLE_COPY(...)
The Transition class abstract the Lifecycle's states.
Definition: transition.hpp:36
std::vector< ParameterT > declare_parameters(const std::string &namespace_, const std::map< std::string, ParameterT > ¶meters)
Declare and initialize several parameters with the same namespace and type.
Definition: lifecycle_node_impl.hpp:149
SubscriptionOptionsWithAllocator< AllocatorT > create_default_subscription_options()
Definition: lifecycle_node.hpp:111
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
Set a single parameter.
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::Time now() const
Returns current time from the time source specified by clock_type.
bool register_on_shutdown(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the shutdown callback.
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
Return the Node's internal NodeClockInterface implementation.
const State & activate()
Trigger the activate transition.
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::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
Return the Node's internal NodeLoggingInterface implementation.
size_t count_publishers(const std::string &topic_name) const
Return the number of publishers that are advertised on a given topic.
rclcpp::Logger get_logger() const
Get the logger of the node.
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
Return the Node's internal NodeGraphInterface implementation.
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
Return the Node's internal NodeBaseInterface implementation.
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
Return the Node's internal NodeParametersInterface implementation.
rclcpp::Parameter get_parameter(const std::string &name) const
Return the parameter by the given name.
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, all at once.
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.
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
Return the Node's internal NodeTimersInterface implementation.
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.
bool register_on_configure(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the configure callback.
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
Return the Node's internal NodeTopicsInterface implementation.
LifecycleNode(const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Create a new lifecycle node with the specified name.
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
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
const State & deactivate()
Trigger the deactivate transition.
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
Return the Node's internal NodeWaitablesInterface implementation.
Abstract class for the Lifecycle's states.
Definition: state.hpp:34
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
void remove_on_set_parameters_callback(const rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle *const handler)
Remove a callback registered with add_on_set_parameters_callback.
Definition: lifecycle_node.hpp:90
std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)
Set one or more parameters, one at a time.
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.
std::vector< State > get_available_states()
Return a list with the available states.
bool register_on_deactivate(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the deactivate callback.
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.
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::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type)
Create and return a callback group.
PublisherOptionsWithAllocator< AllocatorT > create_default_publisher_options()
Definition: lifecycle_node.hpp:104
void undeclare_parameter(const std::string &name)
Undeclare a previously declared parameter.
std::vector< std::string > get_node_names() const
Return a vector of existing node names (string).
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
void add_publisher_handle(std::shared_ptr< rclcpp_lifecycle::LifecyclePublisherInterface > pub)
const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value=rclcpp::ParameterValue(), const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor())
Declare and initialize a parameter, return the effective value.
const State & shutdown()
Trigger the shutdown transition.
size_t count_subscribers(const std::string &topic_name) const
Return the number of subscribers who have created a subscription for a given topic.
LifecycleNode for creating lifecycle components.
Definition: lifecycle_node.hpp:120
const std::vector< rclcpp::CallbackGroup::WeakPtr > & get_callback_groups() const
Return the list of callback groups in the node.
bool has_parameter(const std::string &name) const
Return true if a given parameter is declared.
const char * get_namespace() const
Get the namespace of the node.
bool register_on_error(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the error callback.
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
Return the parameter descriptor for the given parameter name.
#define RCLCPP_LIFECYCLE_PUBLIC
Definition: visibility_control.h:50
const State & cleanup()
Trigger the cleanup transition.
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
Return the Node's internal NodeParametersInterface implementation.
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.
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.
bool register_on_cleanup(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the cleanup callback.
void add_timer_handle(std::shared_ptr< rclcpp::TimerBase > timer)
const State & configure()
Trigger the configure transition.
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
bool register_on_activate(std::function< LifecycleNodeInterface::CallbackReturn(const State &)> fcn)
Register the activate callback.
std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const
Return the parameters by the given parameter names.
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
Return the Node's internal NodeServicesInterface implementation.
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.
std::vector< Transition > get_available_transitions()
Return a list with the available transitions.
Interface class for a managed node.
Definition: lifecycle_node_interface.hpp:42
OnSetParametersCallbackHandle::OnParametersSetCallbackType OnParametersSetCallbackType
const rclcpp::NodeOptions & get_node_options() const
Return the NodeOptions used when creating this node.
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