16 #ifndef NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__REGULATED_PURE_PURSUIT_CONTROLLER_HPP_
17 #define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__REGULATED_PURE_PURSUIT_CONTROLLER_HPP_
25 #include "nav2_core/controller.hpp"
26 #include "nav2_ros_common/lifecycle_node.hpp"
27 #include "pluginlib/class_loader.hpp"
28 #include "pluginlib/class_list_macros.hpp"
29 #include "geometry_msgs/msg/pose.hpp"
30 #include "std_msgs/msg/bool.hpp"
31 #include "nav2_regulated_pure_pursuit_controller/path_handler.hpp"
32 #include "nav2_regulated_pure_pursuit_controller/collision_checker.hpp"
33 #include "nav2_regulated_pure_pursuit_controller/parameter_handler.hpp"
34 #include "nav2_regulated_pure_pursuit_controller/regulation_functions.hpp"
36 namespace nav2_regulated_pure_pursuit_controller
64 const nav2::LifecycleNode::WeakPtr & parent,
65 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
66 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
96 const geometry_msgs::msg::PoseStamped & pose,
97 const geometry_msgs::msg::Twist & velocity,
106 void setPlan(
const nav_msgs::msg::Path & path)
override;
115 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
117 void reset()
override;
133 const geometry_msgs::msg::PoseStamped & carrot_pose);
143 const geometry_msgs::msg::PoseStamped & carrot_pose,
double & angle_to_path,
144 double & x_vel_sign);
161 double & linear_vel,
double & angular_vel,
162 const double & angle_to_path,
const geometry_msgs::msg::Twist & curr_speed);
173 const double & curvature,
const geometry_msgs::msg::Twist & speed,
174 const double & pose_cost,
const nav_msgs::msg::Path & path,
175 double & linear_vel,
double & sign);
187 const geometry_msgs::msg::Point & p1,
188 const geometry_msgs::msg::Point & p2,
200 const double &,
const nav_msgs::msg::Path &,
201 bool interpolate_after_goal =
false);
210 nav2::LifecycleNode::WeakPtr node_;
211 std::shared_ptr<tf2_ros::Buffer> tf_;
212 std::string plugin_name_;
213 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
215 rclcpp::Logger logger_ {rclcpp::get_logger(
"RegulatedPurePursuitController")};
218 double goal_dist_tol_;
219 double control_duration_;
220 bool cancelling_ =
false;
221 bool finished_cancelling_ =
false;
222 bool is_rotating_to_heading_ =
false;
223 bool has_reached_xy_tolerance_ =
false;
225 nav2::Publisher<nav_msgs::msg::Path>::SharedPtr global_path_pub_;
226 nav2::Publisher<geometry_msgs::msg::PointStamped>::SharedPtr carrot_pub_;
227 nav2::Publisher<geometry_msgs::msg::PointStamped>::SharedPtr curvature_carrot_pub_;
228 nav2::Publisher<std_msgs::msg::Bool>::SharedPtr is_rotating_to_heading_pub_;
229 nav2::Publisher<nav_msgs::msg::Path>::SharedPtr carrot_arc_pub_;
230 std::unique_ptr<nav2_regulated_pure_pursuit_controller::PathHandler> path_handler_;
231 std::unique_ptr<nav2_regulated_pure_pursuit_controller::ParameterHandler> param_handler_;
232 std::unique_ptr<nav2_regulated_pure_pursuit_controller::CollisionChecker> collision_checker_;
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Regulated pure pursuit controller plugin.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
Compute the best command given the current pose and velocity, with possible debug information.
void activate() override
Activate controller state machine.
double findVelocitySignChange(const nav_msgs::msg::Path &transformed_plan)
checks for the cusp position
bool shouldRotateToPath(const geometry_msgs::msg::PoseStamped &carrot_pose, double &angle_to_path, double &x_vel_sign)
Whether robot should rotate to rough path heading.
void deactivate() override
Deactivate controller state machine.
void cleanup() override
Cleanup controller state machine.
double getLookAheadDistance(const geometry_msgs::msg::Twist &)
Get lookahead distance.
static geometry_msgs::msg::Point circleSegmentIntersection(const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2, double r)
Find the intersection a circle and a line segment. This assumes the circle is centered at the origin....
void rotateToHeading(double &linear_vel, double &angular_vel, const double &angle_to_path, const geometry_msgs::msg::Twist &curr_speed)
Create a smooth and kinematically smoothed rotation command.
bool shouldRotateToGoalHeading(const geometry_msgs::msg::PoseStamped &carrot_pose)
Whether robot should rotate to final goal orientation.
void configure(const nav2::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configure controller state machine.
~RegulatedPurePursuitController() override=default
Destrructor for nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController.
RegulatedPurePursuitController()=default
Constructor for nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void applyConstraints(const double &curvature, const geometry_msgs::msg::Twist &speed, const double &pose_cost, const nav_msgs::msg::Path &path, double &linear_vel, double &sign)
apply regulation constraints to the system
std::unique_ptr< geometry_msgs::msg::PointStamped > createCarrotMsg(const geometry_msgs::msg::PoseStamped &carrot_pose)
Creates a PointStamped message for visualization.
geometry_msgs::msg::PoseStamped getLookAheadPoint(const double &, const nav_msgs::msg::Path &, bool interpolate_after_goal=false)
Get lookahead point.
bool cancel() override
Cancel the current control action.
void reset() override
Reset the state of the controller if necessary after task is exited.