17 #include "nav2_util/controller_utils.hpp"
18 #include "nav2_util/geometry_utils.hpp"
22 geometry_msgs::msg::Point circleSegmentIntersection(
23 const geometry_msgs::msg::Point & p1,
24 const geometry_msgs::msg::Point & p2,
42 double dr2 = dx * dx + dy * dy;
43 double D = x1 * y2 - x2 * y1;
46 double d1 = x1 * x1 + y1 * y1;
47 double d2 = x2 * x2 + y2 * y2;
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;
57 geometry_msgs::msg::PoseStamped getLookAheadPoint(
58 double & lookahead_dist,
59 const nav_msgs::msg::Path & transformed_plan,
60 const bool interpolate_after_goal)
64 const auto & poses = transformed_plan.poses;
65 auto goal_pose_it = poses.begin();
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;
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;
82 goal_pose_it = poses.end();
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);
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);
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;
103 const auto interpolated_position = circleSegmentIntersection(
104 last_pose_it->pose.position, projected_position, lookahead_dist);
106 geometry_msgs::msg::PoseStamped interpolated_pose;
107 interpolated_pose.header = last_pose_it->header;
108 interpolated_pose.pose.position = interpolated_position;
110 return interpolated_pose;
113 goal_pose_it = std::prev(transformed_plan.poses.end());
115 }
else if (goal_pose_it != transformed_plan.poses.begin()) {
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);
129 point.y - prev_pose_it->pose.position.y,
130 point.x - prev_pose_it->pose.position.x);
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);
140 return *goal_pose_it;