Class LifecycleNode

Inheritance Relationships

Base Types

  • public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface (Class LifecycleNodeInterface)

  • public std::enable_shared_from_this< LifecycleNode >

Class Documentation

class LifecycleNode : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface, public std::enable_shared_from_this<LifecycleNode>

LifecycleNode for creating lifecycle components.

has lifecycle nodeinterface for configuring this node.

Public Types

using PreSetParametersCallbackHandle = rclcpp::node_interfaces::PreSetParametersCallbackHandle
using PreSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType
using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle
using OnSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType
using OnParametersSetCallbackType = OnSetParametersCallbackType
using PostSetParametersCallbackHandle = rclcpp::node_interfaces::PostSetParametersCallbackHandle
using PostSetParametersCallbackType = rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType

Public Functions

explicit 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.

Parameters:
  • node_name[in] Name of the node.

  • options[in] Additional options to control creation of the node.

  • enable_communication_interface[in] Deciding whether the communication interface of the underlying rcl_lifecycle_node shall be enabled.

LifecycleNode(const std::string &node_name, const std::string &namespace_, const rclcpp::NodeOptions &options = rclcpp::NodeOptions(), bool enable_communication_interface = true)

Create a node based on the node name.

Parameters:
  • node_name[in] Name of the node.

  • namespace_[in] Namespace of the node.

  • options[in] Additional options to control creation of the node.

  • enable_communication_interface[in] Deciding whether the communication interface of the underlying rcl_lifecycle_node shall be enabled.

virtual ~LifecycleNode()
const char *get_name() const

Get the name of the node.

Returns:

The name of the node.

const char *get_namespace() const

Get the namespace of the node.

Returns:

The namespace of the node.

const char *get_fully_qualified_name() const

Get the fully-qualified name of the node.

The fully-qualified name includes the local namespace and name of the node.

Returns:

fully-qualified name of the node.

rclcpp::Logger get_logger() const

Get the logger of the node.

Returns:

The logger of the node.

rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node = true)

Create and return a callback group.

Parameters:
  • group_type[in] callback group type to create by this method.

  • automatically_add_to_executor_with_node[in] A boolean that determines whether a callback group is automatically added to an executor with the node with which it is associated.

Returns:

a callback group

void for_each_callback_group(const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction &func)

Iterate over the callback groups in the node, calling func on each valid one.

template<typename MessageT, typename AllocatorT = std::allocator<void>>
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.

Parameters:
  • topic_name[in] The topic for this publisher to publish on.

  • qos[in] The Quality of Service settings for this publisher.

  • options[in] The publisher options for this publisher.

Returns:

Shared pointer to the created lifecycle publisher.

template<typename MessageT, typename CallbackT, typename AllocatorT = std::allocator<void>, typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>, typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType>
std::shared_ptr<SubscriptionT> create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const SubscriptionOptionsWithAllocator<AllocatorT> &options = create_default_subscription_options<AllocatorT>(), typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (MessageMemoryStrategyT::create_default()))

Create and return a Subscription.

Parameters:
  • topic_name[in] The topic to subscribe on.

  • callback[in] The user-defined callback function.

  • qos[in] The quality of service for this subscription.

  • options[in] The subscription options for this subscription.

  • msg_mem_strat[in] The message memory strategy to use for allocating messages.

Returns:

Shared pointer to the created subscription.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
rclcpp::WallTimer<CallbackT>::SharedPtr create_wall_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a timer that uses the wall clock to drive the callback.

Parameters:
  • period[in] Time interval between triggers of the callback.

  • callback[in] User-defined callback function.

  • group[in] Callback group to execute this timer’s callback in.

template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
rclcpp::GenericTimer<CallbackT>::SharedPtr create_timer(std::chrono::duration<DurationRepT, DurationT> period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create a timer that uses the node clock to drive the callback.

Parameters:
  • period[in] Time interval between triggers of the callback.

  • callback[in] User-defined callback function.

  • group[in] Callback group to execute this timer’s callback in.

template<typename ServiceT>
rclcpp::Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Client.

Deprecated:

use rclcpp::QoS instead of rmw_qos_profile_t

See also

rclcpp::Node::create_client

template<typename ServiceT>
rclcpp::Client<ServiceT>::SharedPtr create_client(const std::string &service_name, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Client.

Parameters:
  • service_name[in] The name on which the service is accessible.

  • qos[in] Quality of service profile for client.

  • group[in] Callback group to handle the reply to service calls.

Returns:

Shared pointer to the created client.

template<typename ServiceT, typename CallbackT>
rclcpp::Service<ServiceT>::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rmw_qos_profile_t &qos_profile, rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Service.

Deprecated:

use rclcpp::QoS instead of rmw_qos_profile_t

See also

rclcpp::Node::create_service

template<typename ServiceT, typename CallbackT>
rclcpp::Service<ServiceT>::SharedPtr create_service(const std::string &service_name, CallbackT &&callback, const rclcpp::QoS &qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr group = nullptr)

Create and return a Service.

See also

rclcpp::Node::create_service

template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options = (rclcpp::PublisherOptionsWithAllocator<AllocatorT>()))

Create and return a GenericPublisher.

See also

rclcpp::Node::create_generic_publisher

template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, std::function<void(std::shared_ptr<rclcpp::SerializedMessage>)> callback, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &options = (rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()))

Create and return a GenericSubscription.

See also

rclcpp::Node::create_generic_subscription

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.

See also

rclcpp::Node::declare_parameter

const rclcpp::ParameterValue &declare_parameter(const std::string &name, rclcpp::ParameterType type, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override = false)

Declare and initialize a parameter, return the effective value.

See also

rclcpp::Node::declare_parameter

template<typename ParameterT>
auto declare_parameter(const std::string &name, const ParameterT &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Declare and initialize a parameter with a type.

See also

rclcpp::Node::declare_parameter

template<typename ParameterT>
auto declare_parameter(const std::string &name, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)

Declare and initialize a parameter with a type.

See the non-templated declare_parameter() on this class for details.

template<typename ParameterT>
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.

See also

rclcpp::Node::declare_parameters

template<typename ParameterT>
std::vector<ParameterT> declare_parameters(const std::string &namespace_, const std::map<std::string, std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>> &parameters)

Declare and initialize several parameters with the same namespace and type.

See also

rclcpp::Node::declare_parameters

void undeclare_parameter(const std::string &name)

Undeclare a previously declared parameter.

See also

rclcpp::Node::undeclare_parameter

bool has_parameter(const std::string &name) const

Return true if a given parameter is declared.

See also

rclcpp::Node::has_parameter

rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter &parameter)

Set a single parameter.

See also

rclcpp::Node::set_parameter

std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(const std::vector<rclcpp::Parameter> &parameters)

Set one or more parameters, one at a time.

See also

rclcpp::Node::set_parameters

rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector<rclcpp::Parameter> &parameters)

Set one or more parameters, all at once.

See also

rclcpp::Node::set_parameters_atomically

rclcpp::Parameter get_parameter(const std::string &name) const

Return the parameter by the given name.

See also

rclcpp::Node::get_parameter

bool get_parameter(const std::string &name, rclcpp::Parameter &parameter) const

Get the value of a parameter by the given name, and return true if it was set.

See also

rclcpp::Node::get_parameter

template<typename ParameterT>
bool get_parameter(const std::string &name, ParameterT &parameter) const

Get the value of a parameter by the given name, and return true if it was set.

See also

rclcpp::Node::get_parameter

template<typename ParameterT>
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”.

See also

rclcpp::Node::get_parameter_or

std::vector<rclcpp::Parameter> get_parameters(const std::vector<std::string> &names) const

Return the parameters by the given parameter names.

See also

rclcpp::Node::get_parameters

template<typename MapValueT>
bool get_parameters(const std::string &prefix, std::map<std::string, MapValueT> &values) const

Get the parameter values for all parameters that have a given prefix.

See also

rclcpp::Node::get_parameters

rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const

Return the parameter descriptor for the given parameter name.

See also

rclcpp::Node::describe_parameter

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.

See also

rclcpp::Node::describe_parameters

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.

See also

rclcpp::Node::get_parameter_types

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.

See also

rclcpp::Node::list_parameters

rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackType callback)

Add a callback that gets triggered before parameters are validated.

See also

rclcpp::Node::add_pre_set_parameters_callback

rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackType callback)

Add a callback for when parameters are being set.

See also

rclcpp::Node::add_on_set_parameters_callback

rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackHandle::SharedPtr add_post_set_parameters_callback(rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackType callback)

Add a callback that gets triggered after parameters are set successfully.

See also

rclcpp::Node::add_post_set_parameters_callback

void remove_pre_set_parameters_callback(const rclcpp_lifecycle::LifecycleNode::PreSetParametersCallbackHandle *const handler)

Remove a callback registered with add_pre_set_parameters_callback.

See also

rclcpp::Node::remove_pre_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.

See also

rclcpp::Node::remove_on_set_parameters_callback

void remove_post_set_parameters_callback(const rclcpp_lifecycle::LifecycleNode::PostSetParametersCallbackHandle *const handler)

Remove a callback registered with add_post_set_parameters_callback.

See also

rclcpp::Node::remove_post_set_parameters_callback

std::vector<std::string> get_node_names() const

Return a vector of existing node names (string).

See also

rclcpp::Node::get_node_names

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.

See also

rclcpp::Node::get_topic_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.

See also

rclcpp::Node::get_service_names_and_types

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.

This function only considers services - not clients.

Parameters:
  • node_name[in] name of the node

  • namespace_[in] namespace of the node

size_t count_publishers(const std::string &topic_name) const

Return the number of publishers that are advertised on a given topic.

See also

rclcpp::Node::count_publishers

size_t count_subscribers(const std::string &topic_name) const

Return the number of subscribers who have created a subscription for a given topic.

See also

rclcpp::Node::count_subscribers

size_t count_clients(const std::string &service_name) const

Return the number of clients created for a given service.

See also

rclcpp::Node::count_clients

size_t count_services(const std::string &service_name) const

Return the number of services created for a given service.

See also

rclcpp::Node::count_services

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.

See also

rclcpp::Node::get_publishers_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.

See also

rclcpp::Node::get_subscriptions_info_by_topic

rclcpp::Event::SharedPtr get_graph_event()

Return a graph event, which will be set anytime a graph change occurs.

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::Clock::SharedPtr get_clock()

Get a clock as a non-const shared pointer which is managed by the node.

See also

rclcpp::node_interfaces::NodeClock::get_clock

rclcpp::Clock::ConstSharedPtr get_clock() const

Get a clock as a const shared pointer which is managed by the node.

See also

rclcpp::node_interfaces::NodeClock::get_clock

rclcpp::Time now() const

Returns current time from the time source specified by clock_type.

See also

rclcpp::Clock::now

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()

Return the Node’s internal NodeBaseInterface implementation.

See also

rclcpp::Node::get_node_base_interface

rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()

Return the Node’s internal NodeClockInterface implementation.

See also

rclcpp::Node::get_node_clock_interface

rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()

Return the Node’s internal NodeGraphInterface implementation.

See also

rclcpp::Node::get_node_graph_interface

rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()

Return the Node’s internal NodeLoggingInterface implementation.

See also

rclcpp::Node::get_node_logging_interface

rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()

Return the Node’s internal NodeTimersInterface implementation.

See also

rclcpp::Node::get_node_timers_interface

rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()

Return the Node’s internal NodeTopicsInterface implementation.

See also

rclcpp::Node::get_node_topics_interface

rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()

Return the Node’s internal NodeServicesInterface implementation.

See also

rclcpp::Node::get_node_services_interface

rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()

Return the Node’s internal NodeParametersInterface implementation.

See also

rclcpp::Node::get_node_parameters_interface

rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()

Return the Node’s internal NodeParametersInterface implementation.

See also

rclcpp::Node::get_node_time_source_interface

rclcpp::node_interfaces::NodeTypeDescriptionsInterface::SharedPtr get_node_type_descriptions_interface()

Return the Node’s internal NodeTypeDescriptionsInterface implementation.

See also

rclcpp::Node::get_node_type_descriptions_interface

rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()

Return the Node’s internal NodeWaitablesInterface implementation.

See also

rclcpp::Node::get_node_waitables_interface

const rclcpp::NodeOptions &get_node_options() const

Return the NodeOptions used when creating this node.

See also

rclcpp::Node::get_node_options

const State &get_current_state() const

Return the current State.

Returns:

the current state

std::vector<State> get_available_states() const

Return a list with the available states.

Returns:

list with the available states.

std::vector<Transition> get_available_transitions() const

Return a list with the current available transitions.

Returns:

list with the current available transitions.

std::vector<Transition> get_transition_graph() const

Return a list with all the transitions.

Returns:

list with all the transitions in the transition graph.

const State &trigger_transition(const Transition &transition)

Trigger the specified transition.

const State &trigger_transition(const Transition &transition, LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the specified transition and get the callback return code.

const State &trigger_transition(uint8_t transition_id)

Trigger the specified transition based on an id.

const State &trigger_transition(uint8_t transition_id, LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the specified transition based on an id and get the callback return code.

const State &configure()

Trigger the configure transition.

const State &configure(LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the configure transition and get the callback return code.

const State &cleanup()

Trigger the cleanup transition.

const State &cleanup(LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the cleanup transition and get the callback return code.

const State &activate()

Trigger the activate transition.

const State &activate(LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the activate transition and get the callback return code.

const State &deactivate()

Trigger the deactivate transition.

const State &deactivate(LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the deactivate transition and get the callback return code.

const State &shutdown()

Trigger the shutdown transition.

const State &shutdown(LifecycleNodeInterface::CallbackReturn &cb_return_code)

Trigger the shutdown transition and get the callback return code.

bool register_on_configure(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the configure callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

bool register_on_cleanup(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the cleanup callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

bool register_on_shutdown(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the shutdown callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

bool register_on_activate(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the activate callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

bool register_on_deactivate(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the deactivate callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

bool register_on_error(std::function<LifecycleNodeInterface::CallbackReturn(const State&)> fcn)

Register the error callback.

This callback will be called when the transition to this state is triggered

Parameters:

fcn[in] callback function to call

Returns:

always true

virtual CallbackReturn on_activate(const State &previous_state) override

Callback function for activate transition.

virtual CallbackReturn on_deactivate(const State &previous_state) override

Callback function for deactivate transition.

template<typename MessageT, typename AllocatorT>
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>> create_publisher(const std::string &topic_name, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options)
template<typename MessageT, typename CallbackT, typename AllocatorT, typename SubscriptionT, typename MessageMemoryStrategyT>
std::shared_ptr<SubscriptionT> create_subscription(const std::string &topic_name, const rclcpp::QoS &qos, CallbackT &&callback, const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> &options, typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)

Protected Functions

void add_managed_entity(std::weak_ptr<rclcpp_lifecycle::ManagedEntityInterface> managed_entity)
void add_timer_handle(std::shared_ptr<rclcpp::TimerBase> timer)