Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_util::LifecycleNode Class Reference

A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters. More...

#include <nav2_util/include/nav2_util/lifecycle_node.hpp>

Inheritance diagram for nav2_util::LifecycleNode:
Inheritance graph
[legend]
Collaboration diagram for nav2_util::LifecycleNode:
Collaboration graph
[legend]

Classes

struct  floating_point_range
 
struct  integer_range
 

Public Member Functions

 LifecycleNode (const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has no integer or floating point range constraints. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has a floating point range constraint. More...
 
void add_parameter (const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
 Declare a parameter that has an integer range constraint. More...
 
std::shared_ptr< nav2_util::LifecycleNodeshared_from_this ()
 Get a shared pointer of this.
 
nav2_util::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member Functions

void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::unique_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Detailed Description

A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.

Definition at line 38 of file lifecycle_node.hpp.

Constructor & Destructor Documentation

◆ LifecycleNode()

nav2_util::LifecycleNode::LifecycleNode ( const std::string &  node_name,
const std::string &  ns = "",
const rclcpp::NodeOptions &  options = rclcpp::NodeOptions() 
)

A lifecycle node constructor.

Parameters
node_nameName for the node
namespaceNamespace for the node, if any
optionsNode options

Definition at line 29 of file lifecycle_node.cpp.

References autostart(), printLifecycleNodeNotification(), and register_rcl_preshutdown_callback().

Here is the call graph for this function:

Member Function Documentation

◆ add_parameter() [1/3]

void nav2_util::LifecycleNode::add_parameter ( const std::string &  name,
const rclcpp::ParameterValue &  default_value,
const floating_point_range  fp_range,
const std::string &  description = "",
const std::string &  additional_constraints = "",
bool  read_only = false 
)
inline

Declare a parameter that has a floating point range constraint.

Parameters
node_nameName of parameter
default_valueDefault node value to add
fp_rangefloating point range
descriptionNode description
additional_constraintsAny additional constraints on the parameters to list
read_onlyWhether this param should be considered read only

Definition at line 99 of file lifecycle_node.hpp.

◆ add_parameter() [2/3]

void nav2_util::LifecycleNode::add_parameter ( const std::string &  name,
const rclcpp::ParameterValue &  default_value,
const integer_range  int_range,
const std::string &  description = "",
const std::string &  additional_constraints = "",
bool  read_only = false 
)
inline

Declare a parameter that has an integer range constraint.

Parameters
node_nameName of parameter
default_valueDefault node value to add
integer_rangeInteger range
descriptionNode description
additional_constraintsAny additional constraints on the parameters to list
read_onlyWhether this param should be considered read only

Definition at line 128 of file lifecycle_node.hpp.

◆ add_parameter() [3/3]

void nav2_util::LifecycleNode::add_parameter ( const std::string &  name,
const rclcpp::ParameterValue &  default_value,
const std::string &  description = "",
const std::string &  additional_constraints = "",
bool  read_only = false 
)
inline

Declare a parameter that has no integer or floating point range constraints.

Parameters
node_nameName of parameter
default_valueDefault node value to add
descriptionNode description
additional_constraintsAny additional constraints on the parameters to list
read_onlyWhether this param should be considered read only

Definition at line 75 of file lifecycle_node.hpp.

◆ on_error()

nav2_util::CallbackReturn nav2_util::LifecycleNode::on_error ( const rclcpp_lifecycle::State &  )
inline

Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine.

Parameters
stateState prior to error transition
Returns
Return type for success or failed transition to error state

Definition at line 163 of file lifecycle_node.hpp.

◆ register_rcl_preshutdown_callback()

void nav2_util::LifecycleNode::register_rcl_preshutdown_callback ( )
protected

Register our preshutdown callback for this Node's rcl Context. The callback fires before this Node's Context is shutdown. Note this is not directly related to the lifecycle state machine.

Definition at line 136 of file lifecycle_node.cpp.

References on_rcl_preshutdown().

Referenced by LifecycleNode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ runCleanups()

void nav2_util::LifecycleNode::runCleanups ( )
protected

Run some common cleanup steps shared between rcl preshutdown and destruction.

Definition at line 105 of file lifecycle_node.cpp.

Referenced by on_rcl_preshutdown(), and nav2_costmap_2d::Costmap2DROS::on_rcl_preshutdown().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: