Nav2 Navigation Stack - humble  humble
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_costmap_2d/footprint_collision_checker.hpp"
26 #include "nav2_core/controller.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "pluginlib/class_loader.hpp"
29 #include "pluginlib/class_list_macros.hpp"
30 #include "nav2_util/odometry_utils.hpp"
31 #include "nav2_util/geometry_utils.hpp"
32 #include "geometry_msgs/msg/pose2_d.hpp"
33 
34 namespace nav2_regulated_pure_pursuit_controller
35 {
36 
42 {
43 public:
48 
52  ~RegulatedPurePursuitController() override = default;
53 
61  void configure(
62  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
63  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
64  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
65 
69  void cleanup() override;
70 
74  void activate() override;
75 
79  void deactivate() override;
80 
93  geometry_msgs::msg::TwistStamped computeVelocityCommands(
94  const geometry_msgs::msg::PoseStamped & pose,
95  const geometry_msgs::msg::Twist & velocity,
96  nav2_core::GoalChecker * /*goal_checker*/) override;
97 
102  void setPlan(const nav_msgs::msg::Path & path) override;
103 
111  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
112 
113 protected:
121  nav_msgs::msg::Path transformGlobalPlan(
122  const geometry_msgs::msg::PoseStamped & pose);
123 
131  bool transformPose(
132  const std::string frame,
133  const geometry_msgs::msg::PoseStamped & in_pose,
134  geometry_msgs::msg::PoseStamped & out_pose) const;
135 
141  double getLookAheadDistance(const geometry_msgs::msg::Twist &);
142 
148  std::unique_ptr<geometry_msgs::msg::PointStamped> createCarrotMsg(
149  const geometry_msgs::msg::PoseStamped & carrot_pose);
150 
157  bool shouldRotateToPath(
158  const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path);
159 
165  bool shouldRotateToGoalHeading(const geometry_msgs::msg::PoseStamped & carrot_pose);
166 
174  void rotateToHeading(
175  double & linear_vel, double & angular_vel,
176  const double & angle_to_path, const geometry_msgs::msg::Twist & curr_speed);
177 
187  bool isCollisionImminent(
188  const geometry_msgs::msg::PoseStamped &,
189  const double &, const double &,
190  const double &);
191 
199  bool inCollision(
200  const double & x,
201  const double & y,
202  const double & theta);
209  double costAtPose(const double & x, const double & y);
210 
211  double approachVelocityScalingFactor(
212  const nav_msgs::msg::Path & path
213  ) const;
214 
215  void applyApproachVelocityScaling(
216  const nav_msgs::msg::Path & path,
217  double & linear_vel
218  ) const;
219 
228  void applyConstraints(
229  const double & curvature, const geometry_msgs::msg::Twist & speed,
230  const double & pose_cost, const nav_msgs::msg::Path & path,
231  double & linear_vel, double & sign);
232 
242  static geometry_msgs::msg::Point circleSegmentIntersection(
243  const geometry_msgs::msg::Point & p1,
244  const geometry_msgs::msg::Point & p2,
245  double r);
246 
253  geometry_msgs::msg::PoseStamped getLookAheadPoint(const double &, const nav_msgs::msg::Path &);
254 
260  double findVelocitySignChange(const nav_msgs::msg::Path & transformed_plan);
261 
266  double getCostmapMaxExtent() const;
267 
272  rcl_interfaces::msg::SetParametersResult
273  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
274 
275  rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
276  std::shared_ptr<tf2_ros::Buffer> tf_;
277  std::string plugin_name_;
278  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
279  nav2_costmap_2d::Costmap2D * costmap_;
280  rclcpp::Logger logger_ {rclcpp::get_logger("RegulatedPurePursuitController")};
281  rclcpp::Clock::SharedPtr clock_;
282 
283  double desired_linear_vel_, base_desired_linear_vel_;
284  double lookahead_dist_;
285  double rotate_to_heading_angular_vel_;
286  double max_lookahead_dist_;
287  double min_lookahead_dist_;
288  double lookahead_time_;
289  bool use_velocity_scaled_lookahead_dist_;
290  tf2::Duration transform_tolerance_;
291  double min_approach_linear_velocity_;
292  double approach_velocity_scaling_dist_;
293  double control_duration_;
294  double max_allowed_time_to_collision_up_to_carrot_;
295  bool use_collision_detection_;
296  bool use_regulated_linear_velocity_scaling_;
297  bool use_cost_regulated_linear_velocity_scaling_;
298  double cost_scaling_dist_;
299  double cost_scaling_gain_;
300  double inflation_cost_scaling_factor_;
301  double regulated_linear_scaling_min_radius_;
302  double regulated_linear_scaling_min_speed_;
303  bool use_rotate_to_heading_;
304  double max_angular_accel_;
305  double rotate_to_heading_min_angle_;
306  double goal_dist_tol_;
307  bool allow_reversing_;
308  double max_robot_pose_search_dist_;
309  bool use_interpolation_;
310 
311  nav_msgs::msg::Path global_plan_;
312  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
313  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
314  carrot_pub_;
315  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_;
316  std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
317  collision_checker_;
318 
319  // Dynamic parameters handler
320  std::mutex mutex_;
321  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
322 };
323 
324 } // namespace nav2_regulated_pure_pursuit_controller
325 
326 #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.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool shouldRotateToPath(const geometry_msgs::msg::PoseStamped &carrot_pose, double &angle_to_path)
Whether robot should rotate to rough path heading.
double findVelocitySignChange(const nav_msgs::msg::Path &transformed_plan)
checks for the cusp position
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose)
Transforms global plan into same frame as pose and clips poses ineligible for lookaheadPoint Points i...
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....
bool isCollisionImminent(const geometry_msgs::msg::PoseStamped &, const double &, const double &, const double &)
Whether collision is imminent.
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.
bool transformPose(const std::string frame, const geometry_msgs::msg::PoseStamped &in_pose, geometry_msgs::msg::PoseStamped &out_pose) const
Transform a pose to another frame.
~RegulatedPurePursuitController() override=default
Destrructor for nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController.
geometry_msgs::msg::PoseStamped getLookAheadPoint(const double &, const nav_msgs::msg::Path &)
Get lookahead point.
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.
bool inCollision(const double &x, const double &y, const double &theta)
checks for collision at projected pose
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.