Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
regulated_pure_pursuit_controller.hpp
1 // Copyright (c) 2020 Shrijit Singh
2 // Copyright (c) 2020 Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__REGULATED_PURE_PURSUIT_CONTROLLER_HPP_
17 #define NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__REGULATED_PURE_PURSUIT_CONTROLLER_HPP_
18 
19 #include <string>
20 #include <vector>
21 #include <memory>
22 #include <algorithm>
23 #include <mutex>
24 
25 #include "nav2_core/controller.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "pluginlib/class_loader.hpp"
28 #include "pluginlib/class_list_macros.hpp"
29 #include "geometry_msgs/msg/pose2_d.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"
35 
36 namespace nav2_regulated_pure_pursuit_controller
37 {
38 
44 {
45 public:
50 
54  ~RegulatedPurePursuitController() override = default;
55 
63  void configure(
64  const rclcpp_lifecycle::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;
67 
71  void cleanup() override;
72 
76  void activate() override;
77 
81  void deactivate() override;
82 
95  geometry_msgs::msg::TwistStamped computeVelocityCommands(
96  const geometry_msgs::msg::PoseStamped & pose,
97  const geometry_msgs::msg::Twist & velocity,
98  nav2_core::GoalChecker * /*goal_checker*/) override;
99 
100  bool cancel() override;
101 
106  void setPlan(const nav_msgs::msg::Path & path) override;
107 
115  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
116 
117  void reset() override;
118 
119 protected:
125  double getLookAheadDistance(const geometry_msgs::msg::Twist &);
126 
132  std::unique_ptr<geometry_msgs::msg::PointStamped> createCarrotMsg(
133  const geometry_msgs::msg::PoseStamped & carrot_pose);
134 
142  bool shouldRotateToPath(
143  const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
144  double & x_vel_sign);
145 
151  bool shouldRotateToGoalHeading(const geometry_msgs::msg::PoseStamped & carrot_pose);
152 
160  void rotateToHeading(
161  double & linear_vel, double & angular_vel,
162  const double & angle_to_path, const geometry_msgs::msg::Twist & curr_speed);
163 
172  void applyConstraints(
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);
176 
186  static geometry_msgs::msg::Point circleSegmentIntersection(
187  const geometry_msgs::msg::Point & p1,
188  const geometry_msgs::msg::Point & p2,
189  double r);
190 
199  geometry_msgs::msg::PoseStamped getLookAheadPoint(
200  const double &, const nav_msgs::msg::Path &,
201  bool interpolate_after_goal = false);
202 
208  double findVelocitySignChange(const nav_msgs::msg::Path & transformed_plan);
209 
210  rclcpp_lifecycle::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_;
214  nav2_costmap_2d::Costmap2D * costmap_;
215  rclcpp::Logger logger_ {rclcpp::get_logger("RegulatedPurePursuitController")};
216 
217  Parameters * params_;
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;
224 
225  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
226  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
227  carrot_pub_;
228  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
229  curvature_carrot_pub_;
230  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Bool>>
231  is_rotating_to_heading_pub_;
232  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_;
233  std::unique_ptr<nav2_regulated_pure_pursuit_controller::PathHandler> path_handler_;
234  std::unique_ptr<nav2_regulated_pure_pursuit_controller::ParameterHandler> param_handler_;
235  std::unique_ptr<nav2_regulated_pure_pursuit_controller::CollisionChecker> collision_checker_;
236 };
237 
238 } // namespace nav2_regulated_pure_pursuit_controller
239 
240 #endif // NAV2_REGULATED_PURE_PURSUIT_CONTROLLER__REGULATED_PURE_PURSUIT_CONTROLLER_HPP_
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
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".
Definition: costmap_2d.hpp:68
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.
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.
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.
~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.
void configure(const rclcpp_lifecycle::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.
void reset() override
Reset the state of the controller if necessary after task is exited.