Class LifecycleNode
- Defined in File lifecycle_node.hpp 
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 OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle
 - 
using OnParametersSetCallbackType = rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType
 - 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 and a rclcpp::Context. - 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. 
 
 - 
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. 
 - 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. 
 
 - 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. 
 
 - Create a timer. - 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. 
 
 
 - Create and return a Client. - See also 
 - Create and return a Service. - See also 
 - Create and return a GenericPublisher. 
 - Create and return a GenericSubscription. 
 - 
const rclcpp::ParameterValue &declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)
- Declare and initialize a parameter, return the effective value. - See also 
 - 
const rclcpp::ParameterValue &declare_parameter(const std::string &name, rclcpp::ParameterType type, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor = rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override = false)
- Declare and initialize a parameter, return the effective value. - See also 
 - 
template<typename ParameterT>
 auto declare_parameter(const std::string &name, const ParameterT &default_value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor = rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override = false)
- Declare and initialize a parameter with a type. - See also 
 - 
template<typename ParameterT>
 auto declare_parameter(const std::string &name, const rcl_interfaces::msg::ParameterDescriptor ¶meter_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> ¶meters)
- Declare and initialize several parameters with the same namespace and type. - See also 
 - 
template<typename ParameterT>
 std::vector<ParameterT> declare_parameters(const std::string &namespace_, const std::map<std::string, std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>> ¶meters)
- Declare and initialize several parameters with the same namespace and type. - See also 
 - 
void undeclare_parameter(const std::string &name)
- Undeclare a previously declared parameter. - See also 
 - 
bool has_parameter(const std::string &name) const
- Return true if a given parameter is declared. - See also 
 - 
rcl_interfaces::msg::SetParametersResult set_parameter(const rclcpp::Parameter ¶meter)
- Set a single parameter. - See also 
 - 
std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(const std::vector<rclcpp::Parameter> ¶meters)
- Set one or more parameters, one at a time. - See also 
 - 
rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector<rclcpp::Parameter> ¶meters)
- Set one or more parameters, all at once. 
 - 
rclcpp::Parameter get_parameter(const std::string &name) const
- Return the parameter by the given name. - See also 
 - 
bool get_parameter(const std::string &name, rclcpp::Parameter ¶meter) const
- Get the value of a parameter by the given name, and return true if it was set. - See also 
 - 
template<typename ParameterT>
 bool get_parameter(const std::string &name, ParameterT ¶meter) const
- Get the value of a parameter by the given name, and return true if it was set. - See also 
 - 
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 
 - 
std::vector<rclcpp::Parameter> get_parameters(const std::vector<std::string> &names) const
- Return the parameters by the given parameter names. - See also 
 - 
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 
 - 
rcl_interfaces::msg::ParameterDescriptor describe_parameter(const std::string &name) const
- Return the parameter descriptor for the given parameter name. - See also 
 - 
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 
 - 
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 
 - 
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_lifecycle::LifecycleNode::OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback)
- Add a callback for when parameters are being set. 
 - 
void remove_on_set_parameters_callback(const rclcpp_lifecycle::LifecycleNode::OnSetParametersCallbackHandle *const handler)
- Remove a callback registered with - add_on_set_parameters_callback.
 - 
std::vector<std::string> get_node_names() const
- Return a vector of existing node names (string). - See also 
 - 
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::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::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 
 - 
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 
 - 
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<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::Event::SharedPtr get_graph_event()
- Return a graph event, which will be set anytime a graph change occurs. 
 - 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. 
 - 
rclcpp::Clock::ConstSharedPtr get_clock() const
- Get a clock as a const shared pointer which is managed by the node. 
 - 
rclcpp::Time now() const
- Returns current time from the time source specified by clock_type. - See also 
 - 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()
- Return the Node’s internal NodeBaseInterface implementation. 
 - 
rclcpp::node_interfaces::NodeClockInterface::SharedPtr get_node_clock_interface()
- Return the Node’s internal NodeClockInterface implementation. 
 - 
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr get_node_graph_interface()
- Return the Node’s internal NodeGraphInterface implementation. 
 - 
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr get_node_logging_interface()
- Return the Node’s internal NodeLoggingInterface implementation. 
 - 
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr get_node_timers_interface()
- Return the Node’s internal NodeTimersInterface implementation. 
 - 
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr get_node_topics_interface()
- Return the Node’s internal NodeTopicsInterface implementation. 
 - 
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr get_node_services_interface()
- Return the Node’s internal NodeServicesInterface implementation. 
 - 
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr get_node_parameters_interface()
- Return the Node’s internal NodeParametersInterface implementation. 
 - 
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr get_node_time_source_interface()
- Return the Node’s internal NodeParametersInterface implementation. 
 - 
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr get_node_waitables_interface()
- Return the Node’s internal NodeWaitablesInterface implementation. 
 - 
const rclcpp::NodeOptions &get_node_options() const
- Return the NodeOptions used when creating this node. - See also 
 - 
std::vector<State> get_available_states()
- Return a list with the available states. - Returns:
- list with the available states. 
 
 - 
std::vector<Transition> get_available_transitions()
- Return a list with the current available transitions. - Returns:
- list with the current available transitions. 
 
 - 
std::vector<Transition> get_transition_graph()
- 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(LifecycleNodeInterface::CallbackReturn &cb_return_code)
- Trigger the configure transition and get the callback return code. 
 - 
const State &cleanup(LifecycleNodeInterface::CallbackReturn &cb_return_code)
- Trigger the cleanup transition and get the callback return code. 
 - 
const State &activate(LifecycleNodeInterface::CallbackReturn &cb_return_code)
- Trigger the activate transition and get the callback return code. 
 - 
const State &deactivate(LifecycleNodeInterface::CallbackReturn &cb_return_code)
- Trigger the deactivate transition and get the callback return code. 
 - 
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. 
 - Protected Functions - 
void add_managed_entity(std::weak_ptr<rclcpp_lifecycle::ManagedEntityInterface> managed_entity)
 
- 
using OnSetParametersCallbackHandle = rclcpp::node_interfaces::OnSetParametersCallbackHandle