Class LifecycleNode

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class LifecycleNode : public rclcpp_lifecycle::LifecycleNode

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

Public Functions

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

A lifecycle node constructor.

Parameters:
  • node_name – Name for the node

  • namespace – Namespace for the node, if any

  • options – Node options

virtual ~LifecycleNode()
inline 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.

Parameters:
  • node_name – Name of parameter

  • default_value – Default node value to add

  • description – Node description

  • additional_constraints – Any additional constraints on the parameters to list

  • read_only – Whether this param should be considered read only

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

Parameters:
  • node_name – Name of parameter

  • default_value – Default node value to add

  • fp_range – floating point range

  • description – Node description

  • additional_constraints – Any additional constraints on the parameters to list

  • read_only – Whether this param should be considered read only

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

Parameters:
  • node_name – Name of parameter

  • default_value – Default node value to add

  • integer_range – Integer range

  • description – Node description

  • additional_constraints – Any additional constraints on the parameters to list

  • read_only – Whether this param should be considered read only

inline std::shared_ptr<nav2_util::LifecycleNode> shared_from_this()

Get a shared pointer of this.

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

Parameters:

state – State prior to error transition

Returns:

Return type for success or failed transition to error state

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 Functions

void printLifecycleNodeNotification()

Print notifications for lifecycle node.

void register_rcl_preshutdown_callback()

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.

void runCleanups()

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

Protected Attributes

std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_ = {nullptr}
std::unique_ptr<bond::Bond> bond_ = {nullptr}
struct floating_point_range

Public Members

double from_value
double to_value
double step
struct integer_range

Public Members

int from_value
int to_value
int step