Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
controller_utils.cpp
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 #include <cmath>
17 #include "nav2_util/controller_utils.hpp"
18 #include "nav2_util/geometry_utils.hpp"
19 
20 namespace nav2_util
21 {
22 geometry_msgs::msg::Point circleSegmentIntersection(
23  const geometry_msgs::msg::Point & p1,
24  const geometry_msgs::msg::Point & p2,
25  double r)
26 {
27  // Formula for intersection of a line with a circle centered at the origin,
28  // modified to always return the point that is on the segment between the two points.
29  // https://mathworld.wolfram.com/Circle-LineIntersection.html
30  // This works because the poses are transformed into the robot frame.
31  // This can be derived from solving the system of equations of a line and a circle
32  // which results in something that is just a reformulation of the quadratic formula.
33  // Interactive illustration in doc/circle-segment-intersection.ipynb as well as at
34  // https://www.desmos.com/calculator/td5cwbuocd
35  double x1 = p1.x;
36  double x2 = p2.x;
37  double y1 = p1.y;
38  double y2 = p2.y;
39 
40  double dx = x2 - x1;
41  double dy = y2 - y1;
42  double dr2 = dx * dx + dy * dy;
43  double D = x1 * y2 - x2 * y1;
44 
45  // Augmentation to only return point within segment
46  double d1 = x1 * x1 + y1 * y1;
47  double d2 = x2 * x2 + y2 * y2;
48  double dd = d2 - d1;
49 
50  geometry_msgs::msg::Point p;
51  double sqrt_term = std::sqrt(r * r * dr2 - D * D);
52  p.x = (D * dy + std::copysign(1.0, dd) * dx * sqrt_term) / dr2;
53  p.y = (-D * dx + std::copysign(1.0, dd) * dy * sqrt_term) / dr2;
54  return p;
55 }
56 
57 geometry_msgs::msg::PoseStamped getLookAheadPoint(
58  double & lookahead_dist,
59  const nav_msgs::msg::Path & transformed_plan,
60  const bool interpolate_after_goal)
61 {
62  // Find the first pose which is at a distance greater than the lookahead distance
63  // Using distance along the path
64  const auto & poses = transformed_plan.poses;
65  auto goal_pose_it = poses.begin();
66  double d = 0.0;
67 
68  bool pose_found = false;
69  for (size_t i = 1; i < poses.size(); i++) {
70  const auto & prev_pose = poses[i - 1].pose.position;
71  const auto & curr_pose = poses[i].pose.position;
72 
73  d += std::hypot(curr_pose.x - prev_pose.x, curr_pose.y - prev_pose.y);
74  if (d >= lookahead_dist) {
75  goal_pose_it = poses.begin() + i;
76  pose_found = true;
77  break;
78  }
79  }
80 
81  if (!pose_found) {
82  goal_pose_it = poses.end();
83  }
84 
85  // If the no pose is not far enough, take the last pose
86  if (goal_pose_it == transformed_plan.poses.end()) {
87  if (interpolate_after_goal) {
88  auto last_pose_it = std::prev(transformed_plan.poses.end());
89  auto prev_last_pose_it = std::prev(last_pose_it);
90 
91  double end_path_orientation = atan2(
92  last_pose_it->pose.position.y - prev_last_pose_it->pose.position.y,
93  last_pose_it->pose.position.x - prev_last_pose_it->pose.position.x);
94 
95  // Project the last segment out to guarantee it is beyond the look ahead
96  // distance
97  auto projected_position = last_pose_it->pose.position;
98  projected_position.x += cos(end_path_orientation) * lookahead_dist;
99  projected_position.y += sin(end_path_orientation) * lookahead_dist;
100 
101  // Use the circle intersection to find the position at the correct look
102  // ahead distance
103  const auto interpolated_position = circleSegmentIntersection(
104  last_pose_it->pose.position, projected_position, lookahead_dist);
105 
106  geometry_msgs::msg::PoseStamped interpolated_pose;
107  interpolated_pose.header = last_pose_it->header;
108  interpolated_pose.pose.position = interpolated_position;
109 
110  return interpolated_pose;
111  } else {
112  lookahead_dist = d; // Updating lookahead distance since using the final point
113  goal_pose_it = std::prev(transformed_plan.poses.end());
114  }
115  } else if (goal_pose_it != transformed_plan.poses.begin()) {
116  // Find the point on the line segment between the two poses
117  // that is exactly the lookahead distance away from the robot pose (the origin)
118  // This can be found with a closed form for the intersection of a segment and a circle
119  // Because of the way we did the std::find_if, prev_pose is guaranteed to be inside the circle,
120  // and goal_pose is guaranteed to be outside the circle.
121  auto prev_pose_it = std::prev(goal_pose_it);
122  auto point = circleSegmentIntersection(
123  prev_pose_it->pose.position,
124  goal_pose_it->pose.position, lookahead_dist);
125 
126  // Calculate orientation towards interpolated position
127  // Convert yaw to quaternion
128  double yaw = atan2(
129  point.y - prev_pose_it->pose.position.y,
130  point.x - prev_pose_it->pose.position.x);
131 
132  geometry_msgs::msg::PoseStamped pose;
133  pose.header.frame_id = prev_pose_it->header.frame_id;
134  pose.header.stamp = goal_pose_it->header.stamp;
135  pose.pose.position = point;
136  pose.pose.orientation = geometry_utils::orientationAroundZAxis(yaw);
137  return pose;
138  }
139 
140  return *goal_pose_it;
141 }
142 } // namespace nav2_util