EasyNav Simple Stack
Loading...
Searching...
No Matches
SimpleController Class Reference

A simple path-following controller using PID and look-ahead strategy. More...

#include <SimpleController.hpp>

Inheritance diagram for SimpleController:
Collaboration diagram for SimpleController:

Public Member Functions

std::expected< void, std::string > on_initialize () override
 Initializes parameters and PID controllers.
 
 SimpleController ()
 
void update_rt (NavState &nav_state) override
 Updates the controller using the given NavState.
 
 ~SimpleController () override
 Destructor.
 

Protected Member Functions

double get_angle (const geometry_msgs::msg::Point &from, const geometry_msgs::msg::Point &to)
 Computes the angle between two points.
 
double get_diff_angle (const geometry_msgs::msg::Quaternion &a, const geometry_msgs::msg::Quaternion &b)
 Computes the angular difference between two quaternions (yaw).
 
double get_distance (const geometry_msgs::msg::Pose &a, const geometry_msgs::msg::Pose &b)
 Computes the Euclidean distance between two poses.
 
geometry_msgs::msg::Pose get_ref_pose (const nav_msgs::msg::Path &path, double look_ahead)
 Gets the reference pose at look-ahead distance on the path.
 

Protected Attributes

std::shared_ptr< PIDControllerangular_pid_
 PID controller for angular velocity.
 
double k_rot_ {0.5}
 
rclcpp::Time last_update_ts_
 Timestamp of the last control update.
 
double last_vlin_ {0.0}
 Previous linear velocity for acceleration limiting.
 
double last_vrot_ {0.0}
 Previous angular velocity for acceleration limiting.
 
std::shared_ptr< PIDControllerlinear_pid_
 PID controller for linear velocity.
 
double look_ahead_dist_ {1.0}
 Distance ahead of the robot to track in meters.
 
double max_angular_acc_ {0.3}
 Maximum angular acceleration in rad/s².
 
double max_angular_speed_ {1.0}
 Maximum angular speed in rad/s.
 
double max_linear_acc_ {0.3}
 Maximum linear acceleration in m/s².
 
double max_linear_speed_ {1.0}
 Maximum linear speed in m/s.
 
double tolerance_dist_ {0.05}
 Distance threshold to switch to orientation tracking.
 
geometry_msgs::msg::TwistStamped twist_stamped_
 Current velocity command.
 

Detailed Description

A simple path-following controller using PID and look-ahead strategy.

Constructor & Destructor Documentation

◆ SimpleController()

◆ ~SimpleController()

~SimpleController ( )
overridedefault

Destructor.

Member Function Documentation

◆ get_angle()

double get_angle ( const geometry_msgs::msg::Point & from,
const geometry_msgs::msg::Point & to )
protected

Computes the angle between two points.

Parameters
fromStart point.
toEnd point.
Returns
Angle in radians.

◆ get_diff_angle()

double get_diff_angle ( const geometry_msgs::msg::Quaternion & a,
const geometry_msgs::msg::Quaternion & b )
protected

Computes the angular difference between two quaternions (yaw).

Parameters
aFirst quaternion.
bSecond quaternion.
Returns
Angle difference in radians within [-π, π].

◆ get_distance()

double get_distance ( const geometry_msgs::msg::Pose & a,
const geometry_msgs::msg::Pose & b )
protected

Computes the Euclidean distance between two poses.

Parameters
aFirst pose.
bSecond pose.
Returns
Distance in meters.

◆ get_ref_pose()

geometry_msgs::msg::Pose get_ref_pose ( const nav_msgs::msg::Path & path,
double look_ahead )
protected

Gets the reference pose at look-ahead distance on the path.

Parameters
pathThe planned path.
look_aheadDistance to look ahead in meters.
Returns
PoseStamped representing the goal reference.

◆ on_initialize()

std::expected< void, std::string > on_initialize ( )
override

Initializes parameters and PID controllers.

Returns
std::expected<void, std::string> success or error message.

◆ update_rt()

void update_rt ( NavState & nav_state)
override

Updates the controller using the given NavState.

Parameters
nav_stateCurrent navigation state, including odometry and planned path.

Member Data Documentation

◆ angular_pid_

std::shared_ptr<PIDController> angular_pid_
protected

PID controller for angular velocity.

◆ k_rot_

double k_rot_ {0.5}
protected

◆ last_update_ts_

rclcpp::Time last_update_ts_
protected

Timestamp of the last control update.

◆ last_vlin_

double last_vlin_ {0.0}
protected

Previous linear velocity for acceleration limiting.

◆ last_vrot_

double last_vrot_ {0.0}
protected

Previous angular velocity for acceleration limiting.

◆ linear_pid_

std::shared_ptr<PIDController> linear_pid_
protected

PID controller for linear velocity.

◆ look_ahead_dist_

double look_ahead_dist_ {1.0}
protected

Distance ahead of the robot to track in meters.

◆ max_angular_acc_

double max_angular_acc_ {0.3}
protected

Maximum angular acceleration in rad/s².

◆ max_angular_speed_

double max_angular_speed_ {1.0}
protected

Maximum angular speed in rad/s.

◆ max_linear_acc_

double max_linear_acc_ {0.3}
protected

Maximum linear acceleration in m/s².

◆ max_linear_speed_

double max_linear_speed_ {1.0}
protected

Maximum linear speed in m/s.

◆ tolerance_dist_

double tolerance_dist_ {0.05}
protected

Distance threshold to switch to orientation tracking.

◆ twist_stamped_

geometry_msgs::msg::TwistStamped twist_stamped_
protected

Current velocity command.


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