Class ControllerMethodBase

Inheritance Relationships

Base Type

Class Documentation

class ControllerMethodBase : public easynav::MethodBase

Abstract base class for control methods in Easy Navigation.

This class defines the interface for control algorithm implementations. Derived classes must implement the control logic and provide access to the computed command.

Public Functions

ControllerMethodBase() = default

Default constructor.

virtual ~ControllerMethodBase() = default

Virtual destructor.

virtual std::expected<void, std::string> initialize(const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> parent_node, const std::string &plugin_name, const std::string &tf_prefix = "")

Initialize the controller method.

Creates required publishers, reads configuration parameters and forwards initialization to MethodBase.

Parameters:
  • parent_node – Reference to the parent lifecycle node.

  • plugin_name – Plugin identifier used for namespacing parameters.

  • tf_prefix – Optional TF prefix for frame resolution.

Returns:

An empty value on success, or an error message otherwise.

bool internal_update_rt(NavState &nav_state, bool trigger = false)

Helper to run the real-time control method if appropriate.

Invokes update_rt() only if the method is due or forced by trigger.

Parameters:
  • nav_state – The current state of the navigation system.

  • trigger – Force execution regardless of timing.

Returns:

True if update_rt() was called, false otherwise.

Protected Functions

inline virtual void update_rt(NavState &nav_state)

Run the control method and update the control command.

Called by the system to compute a new control command using the current navigation state.

Parameters:

nav_state – The current state of the navigation system.

bool is_inminent_collision(NavState &nav_state)

Detect whether an imminent collision is present.

The check uses the robot velocity, braking distance, safety margins and a filtered point cloud in the motion frame. It returns true if any point lies within the collision prediction region.

Parameters:

nav_state – Current navigation state containing velocity and perceptions.

Returns:

True if a collision is predicted, false otherwise.

virtual void on_inminent_collision(NavState &nav_state)

Callback executed when a collision is detected.

The default implementation stops the robot by setting a zero Twist.

Parameters:

nav_state – Reference to the navigation state to modify.

void publish_collision_zone_marker(const std::vector<double> &min, const std::vector<double> &max, const pcl::PointCloud<pcl::PointXYZ> &cloud, bool imminent_collision)

Publish visualization markers for the collision checking region.

Publishes a CUBE representing the bounding box [min, max] used for point cloud filtering, and a SPHERE_LIST containing the filtered points used during the collision evaluation.

Parameters:
  • min – Lower bound of the collision check region [x, y, z].

  • max – Upper bound of the collision check region [x, y, z].

  • cloud – Filtered point cloud used during collision evaluation.

  • imminent_collision – Whether the region is currently considered in collision.

Protected Attributes

bool debug_markers_ = {false}

Enable or disable visualization markers for debugging.

bool collision_checker_active_ = {false}

Enable or disable collision checking.

double robot_radius_ = {0.35}

Robot radius used for safety calculations (m).

double robot_height_ = {0.5}

Vertical extent of the robot used for filtering (m).

double z_min_filter_ = {0.0}

Minimum Z considered when filtering point clouds (m).

double brake_acc_ = {0.5}

Maximum braking deceleration (m/s²).

double safety_margin_ = {0.1}

Safety margin added to the braking distance (m).

double downsample_leaf_size_ = {0.1}

Leaf size used to downsample point clouds (m).

std::string motion_frame_ = {"base_footprint"}

Frame in which motion and collision checks are evaluated.

rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr collision_marker_pub_

Publisher for collision visualization markers.