Class ControllerNode

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class ControllerNode : public rclcpp_lifecycle::LifecycleNode

ROS 2 lifecycle node that manages calculating speeds for the Easy Navigation system.

This node provides the interface between the controller module in EasyNav and the ROS 2 ecosystem. It handles lifecycle transitions, real-time scheduling of periodic tasks, and parameter setup.

Public Types

using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

Public Functions

explicit ControllerNode(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Constructs a ControllerNode lifecycle node with the specified options.

Parameters:

options – Node options to configure the ControllerNode node.

~ControllerNode()

Destroys the ControllerNode object.

CallbackReturnT on_configure(const rclcpp_lifecycle::State &state)

Configures the ControllerNode node. This is typically where parameters and interfaces are declared.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS if configuration is successful.

CallbackReturnT on_activate(const rclcpp_lifecycle::State &state)

Activates the ControllerNode node. This starts periodic navigation control cycles.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS if activation is successful.

CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state)

Deactivates the ControllerNode node. Control loops are stopped and interfaces are disabled.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS if deactivation is successful.

CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state)

Cleans up the ControllerNode node. Releases resources and resets the internal state.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS indicating cleanup is complete.

CallbackReturnT on_shutdown(const rclcpp_lifecycle::State &state)

Shuts down the ControllerNode node. Called on final shutdown of the node’s lifecycle.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS indicating shutdown is complete.

CallbackReturnT on_error(const rclcpp_lifecycle::State &state)

Handles errors in the ControllerNode node. This is called when a failure occurs during a lifecycle transition.

Parameters:

state – The current lifecycle state.

Returns:

CallbackReturnT::SUCCESS indicating error handling is complete.

rclcpp::CallbackGroup::SharedPtr get_real_time_cbg()

Returns the real-time callback group.

This callback group can be used to assign callbacks that require low latency or have real-time constraints.

Returns:

Shared pointer to the real-time callback group.

bool cycle_rt(std::shared_ptr<NavState> nav_state, bool trigger = false)

Executes one cycle of real-time controller logic.

This method is invoked periodically by a high-priority timer and is expected to compute control commands based on the current navigation state and input data.

Parameters:

nav_state – Shared pointer to the navigation state structure.

Returns:

Bool value to indicate if trigger subsequent processes