Skip to content

Commit 4d28c13

Browse files
silanus23CopilotSteveMacenski
authored
Path distance feature (#5387)
* geometry utils Signed-off-by: silanus23 <[email protected]> * fixed geometry utils adding 2d Signed-off-by: silanus23 <[email protected]> * created path_utils Signed-off-by: silanus23 <[email protected]> * added tests Signed-off-by: silanus23 <[email protected]> * minor changes in tests Signed-off-by: silanus23 <[email protected]> * lint issue Signed-off-by: silanus23 <[email protected]> * fixed reviews Signed-off-by: silanus23 <[email protected]> * doxygen fix Signed-off-by: silanus23 <[email protected]> * Last fixes. Signed-off-by: silanus23 <[email protected]> * Last fixes cpp. Signed-off-by: silanus23 <[email protected]> * Update nav2_util/include/nav2_util/path_utils.hpp Co-authored-by: Copilot <[email protected]> Signed-off-by: silanus <[email protected]> Signed-off-by: silanus23 <[email protected]> * Update nav2_util/include/nav2_util/path_utils.hpp Co-authored-by: Copilot <[email protected]> Signed-off-by: silanus <[email protected]> Signed-off-by: silanus23 <[email protected]> * Update nav2_util/test/test_path_utils.cpp Co-authored-by: Copilot <[email protected]> Signed-off-by: silanus <[email protected]> Signed-off-by: silanus23 <[email protected]> * Frame check fix Signed-off-by: silanus23 <[email protected]> * msg Signed-off-by: silanus23 <[email protected]> * controller server publisher Signed-off-by: silanus23 <[email protected]> * controller server publisher fix Signed-off-by: silanus23 <[email protected]> * cross_product Signed-off-by: silanus23 <[email protected]> * handled last_fixes Signed-off-by: silanus23 <[email protected]> * tracking error added to follow path side from side added to tracking error Signed-off-by: silanus23 <[email protected]> * arranged msgs Signed-off-by: silanus23 <[email protected]> * linting of msgs Signed-off-by: silanus23 <[email protected]> * last cpplint Signed-off-by: silanus23 <[email protected]> * frame check for distance_to_goal Signed-off-by: silanus23 <[email protected]> * fixes for follow_path Signed-off-by: silanus23 <[email protected]> * controller linting Signed-off-by: silanus23 <[email protected]> * changing tracking_error to tracking_error_feedback Signed-off-by: silanus23 <[email protected]> * adding remaining_path_length in tracking_error_feedback Signed-off-by: silanus23 <[email protected]> * Last fix Signed-off-by: silanus23 <[email protected]> * start_index_ Signed-off-by: silanus23 <[email protected]> * Name changes and optimizations in controller_server and nav2_util Signed-off-by: silanus23 <[email protected]> * Changing name to tracking_feedback Signed-off-by: silanus23 <[email protected]> * Documentation changes Signed-off-by: silanus23 <[email protected]> * Last lint Signed-off-by: silanus23 <[email protected]> * Update nav2_util/include/nav2_util/path_utils.hpp Co-authored-by: Copilot <[email protected]> Signed-off-by: silanus <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Last updates Signed-off-by: silanus23 <[email protected]> * update example_follow_path.py Signed-off-by: silanus23 <[email protected]> * update example_follow_path.py lint Signed-off-by: silanus23 <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_util/src/path_utils.cpp Signed-off-by: Steve Macenski <[email protected]> * ordering problem Signed-off-by: silanus23 <[email protected]> * added deactivate to tracking_feedback_pub_ Signed-off-by: silanus23 <[email protected]> * typo Signed-off-by: silanus23 <[email protected]> * end_pose transform Signed-off-by: silanus23 <[email protected]> * creating the member variable end_pose_global_ and deleting nav_2d_msgs Signed-off-by: silanus23 <[email protected]> * deleting unnecessary transform Signed-off-by: silanus23 <[email protected]> * typo in controller Signed-off-by: silanus23 <[email protected]> * readding remaining path Signed-off-by: silanus23 <[email protected]> * placement of transformation Signed-off-by: silanus23 <[email protected]> * unnecessary comments Signed-off-by: silanus23 <[email protected]> * tests added Signed-off-by: silanus23 <[email protected]> * Increased test coverage Signed-off-by: silanus23 <[email protected]> * Every part of the result is covered Signed-off-by: silanus23 <[email protected]> * Increasing out of bounds index Signed-off-by: silanus23 <[email protected]> * lint Signed-off-by: silanus23 <[email protected]> * add missing line to cmake Signed-off-by: silanus23 <[email protected]> * unnecessary test Signed-off-by: silanus23 <[email protected]> * unexptected styling and last functional change Signed-off-by: silanus23 <[email protected]> * simplifying the tranformation of end_pose Signed-off-by: silanus23 <[email protected]> * doxygen fix Signed-off-by: silanus23 <[email protected]> * doxygen fix Signed-off-by: silanus23 <[email protected]> * doxygen fix Signed-off-by: silanus23 <[email protected]> * doxygen fix Signed-off-by: silanus23 <[email protected]> * Update nav2_controller/src/controller_server.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: silanus23 <[email protected]> Signed-off-by: silanus <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Copilot <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent 04a3e22 commit 4d28c13

File tree

13 files changed

+706
-40
lines changed

13 files changed

+706
-40
lines changed

nav2_controller/include/nav2_controller/controller_server.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
2929
#include "tf2_ros/transform_listener.hpp"
3030
#include "nav2_msgs/action/follow_path.hpp"
31+
#include "nav2_msgs/msg/tracking_feedback.hpp"
3132
#include "nav2_msgs/msg/speed_limit.hpp"
3233
#include "nav2_ros_common/lifecycle_node.hpp"
3334
#include "nav2_ros_common/simple_action_server.hpp"
@@ -236,6 +237,7 @@ class ControllerServer : public nav2::LifecycleNode
236237
std::unique_ptr<nav2_util::OdomSmoother> odom_sub_;
237238
std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
238239
nav2::Subscription<nav2_msgs::msg::SpeedLimit>::SharedPtr speed_limit_sub_;
240+
nav2::Publisher<nav2_msgs::msg::TrackingFeedback>::SharedPtr tracking_feedback_pub_;
239241

240242
// Progress Checker Plugin
241243
pluginlib::ClassLoader<nav2_core::ProgressChecker> progress_checker_loader_;
@@ -268,6 +270,8 @@ class ControllerServer : public nav2::LifecycleNode
268270
double min_x_velocity_threshold_;
269271
double min_y_velocity_threshold_;
270272
double min_theta_velocity_threshold_;
273+
double search_window_;
274+
size_t start_index_;
271275

272276
double failure_tolerance_;
273277
bool use_realtime_priority_;
@@ -277,6 +281,8 @@ class ControllerServer : public nav2::LifecycleNode
277281
// Whether we've published the single controller warning yet
278282
geometry_msgs::msg::PoseStamped end_pose_;
279283

284+
geometry_msgs::msg::PoseStamped transformed_end_pose_;
285+
280286
// Last time the controller generated a valid command
281287
rclcpp::Time last_valid_cmd_time_;
282288

nav2_controller/src/controller_server.cpp

Lines changed: 52 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "nav2_core/controller_exceptions.hpp"
2424
#include "nav2_ros_common/node_utils.hpp"
2525
#include "nav2_util/geometry_utils.hpp"
26+
#include "nav2_util/path_utils.hpp"
2627
#include "nav2_controller/controller_server.hpp"
2728

2829
using namespace std::chrono_literals;
@@ -43,6 +44,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
4344
lp_loader_("nav2_core", "nav2_core::Controller"),
4445
default_ids_{"FollowPath"},
4546
default_types_{"dwb_core::DWBLocalPlanner"},
47+
start_index_(0),
4648
costmap_update_timeout_(300ms)
4749
{
4850
RCLCPP_INFO(get_logger(), "Creating controller server");
@@ -65,6 +67,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6567

6668
declare_parameter("odom_topic", rclcpp::ParameterValue("odom"));
6769
declare_parameter("odom_duration", rclcpp::ParameterValue(0.3));
70+
declare_parameter("search_window", rclcpp::ParameterValue(2.0));
6871

6972
// The costmap node is used in the implementation of the controller
7073
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -134,6 +137,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
134137
get_parameter("failure_tolerance", failure_tolerance_);
135138
get_parameter("use_realtime_priority", use_realtime_priority_);
136139
get_parameter("publish_zero_velocity", publish_zero_velocity_);
140+
get_parameter("search_window", search_window_);
137141

138142
costmap_ros_->configure();
139143
// Launch a thread to run the costmap node
@@ -225,6 +229,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
225229

226230
odom_sub_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration, odom_topic);
227231
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel");
232+
tracking_feedback_pub_ = create_publisher<nav2_msgs::msg::TrackingFeedback>("tracking_feedback");
228233

229234
double costmap_update_timeout_dbl;
230235
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
@@ -267,8 +272,8 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
267272
it->second->activate();
268273
}
269274
vel_publisher_->on_activate();
275+
tracking_feedback_pub_->on_activate();
270276
action_server_->activate();
271-
272277
auto node = shared_from_this();
273278
// Add callback for dynamic parameters
274279
dyn_params_handler_ = node->add_on_set_parameters_callback(
@@ -302,6 +307,7 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
302307

303308
publishZeroVelocity();
304309
vel_publisher_->on_deactivate();
310+
tracking_feedback_pub_->on_deactivate();
305311

306312
remove_on_set_parameters_callback(dyn_params_handler_.get());
307313
dyn_params_handler_.reset();
@@ -613,6 +619,7 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
613619
get_logger(), "Path end point is (%.2f, %.2f)",
614620
end_pose_.pose.position.x, end_pose_.pose.position.y);
615621

622+
start_index_ = 0;
616623
current_path_ = path;
617624
}
618625

@@ -667,38 +674,56 @@ void ControllerServer::computeAndPublishVelocity()
667674
RCLCPP_DEBUG(get_logger(), "Publishing velocity at time %.2f", now().seconds());
668675
publishVelocity(cmd_vel_2d);
669676

670-
// Find the closest pose to current pose on global path
671-
geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
677+
nav2_msgs::msg::TrackingFeedback current_tracking_feedback;
678+
679+
// Use the current robot pose's timestamp for the transformation
680+
end_pose_.header.stamp = pose.header.stamp;
681+
672682
if (!nav2_util::transformPoseInTargetFrame(
673-
pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer(),
674-
current_path_.header.frame_id, costmap_ros_->getTransformTolerance()))
683+
end_pose_, transformed_end_pose_, *costmap_ros_->getTfBuffer(),
684+
costmap_ros_->getGlobalFrameID(), costmap_ros_->getTransformTolerance()))
675685
{
676-
throw nav2_core::ControllerTFError("Failed to transform robot pose to path frame");
686+
throw nav2_core::ControllerTFError("Failed to transform end pose to global frame");
677687
}
678688

679-
std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
680-
feedback->speed = std::hypot(cmd_vel_2d.twist.linear.x, cmd_vel_2d.twist.linear.y);
689+
if (current_path_.poses.size() >= 2) {
690+
double current_distance_to_goal = nav2_util::geometry_utils::euclidean_distance(
691+
pose, transformed_end_pose_);
681692

682-
nav_msgs::msg::Path & current_path = current_path_;
683-
auto find_closest_pose_idx = [&robot_pose_in_path_frame, &current_path]()
693+
// Transform robot pose to path frame for path tracking calculations
694+
geometry_msgs::msg::PoseStamped robot_pose_in_path_frame;
695+
if (!nav2_util::transformPoseInTargetFrame(
696+
pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer(),
697+
current_path_.header.frame_id, costmap_ros_->getTransformTolerance()))
684698
{
685-
size_t closest_pose_idx = 0;
686-
double curr_min_dist = std::numeric_limits<double>::max();
687-
for (size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
688-
double curr_dist =
689-
nav2_util::geometry_utils::euclidean_distance(robot_pose_in_path_frame,
690-
current_path.poses[curr_idx]);
691-
if (curr_dist < curr_min_dist) {
692-
curr_min_dist = curr_dist;
693-
closest_pose_idx = curr_idx;
694-
}
695-
}
696-
return closest_pose_idx;
697-
};
699+
throw nav2_core::ControllerTFError("Failed to transform robot pose to path frame");
700+
}
701+
702+
const auto path_search_result = nav2_util::distance_from_path(
703+
current_path_, robot_pose_in_path_frame.pose, start_index_, search_window_);
704+
705+
// Create tracking error message
706+
auto tracking_feedback_msg = std::make_unique<nav2_msgs::msg::TrackingFeedback>();
707+
tracking_feedback_msg->header = pose.header;
708+
tracking_feedback_msg->tracking_error = path_search_result.distance;
709+
tracking_feedback_msg->current_path_index = path_search_result.closest_segment_index;
710+
tracking_feedback_msg->robot_pose = pose;
711+
tracking_feedback_msg->distance_to_goal = current_distance_to_goal;
712+
tracking_feedback_msg->speed = std::hypot(twist.linear.x, twist.linear.y);
713+
tracking_feedback_msg->remaining_path_length =
714+
nav2_util::geometry_utils::calculate_path_length(current_path_, start_index_);
715+
start_index_ = path_search_result.closest_segment_index;
716+
717+
// Update current tracking error and publish
718+
current_tracking_feedback = *tracking_feedback_msg;
719+
if (tracking_feedback_pub_->get_subscription_count() > 0) {
720+
tracking_feedback_pub_->publish(std::move(tracking_feedback_msg));
721+
}
722+
}
698723

699-
const std::size_t closest_pose_idx = find_closest_pose_idx();
700-
feedback->distance_to_goal = nav2_util::geometry_utils::calculate_path_length(current_path_,
701-
closest_pose_idx);
724+
// Publish action feedback
725+
std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
726+
feedback->tracking_feedback = current_tracking_feedback;
702727
action_server_->publish_feedback(feedback);
703728
}
704729

@@ -798,14 +823,8 @@ bool ControllerServer::isGoalReached()
798823

799824
geometry_msgs::msg::Twist velocity = getThresholdedTwist(odom_sub_->getRawTwist());
800825

801-
geometry_msgs::msg::PoseStamped transformed_end_pose;
802-
end_pose_.header.stamp = pose.header.stamp;
803-
nav2_util::transformPoseInTargetFrame(
804-
end_pose_, transformed_end_pose, *costmap_ros_->getTfBuffer(),
805-
costmap_ros_->getGlobalFrameID(), costmap_ros_->getTransformTolerance());
806-
807826
return goal_checkers_[current_goal_checker_]->isGoalReached(
808-
pose.pose, transformed_end_pose.pose,
827+
pose.pose, transformed_end_pose_.pose,
809828
velocity);
810829
}
811830

nav2_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
3939
"msg/RouteNode.msg"
4040
"msg/RouteEdge.msg"
4141
"msg/EdgeCost.msg"
42+
"msg/TrackingFeedback.msg"
4243
"msg/Trajectory.msg"
4344
"msg/TrajectoryPoint.msg"
4445
"srv/GetCosts.srv"

nav2_msgs/action/FollowPath.action

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,10 @@
1-
#goal definition
1+
# goal definition
22
nav_msgs/Path path
33
string controller_id
44
string goal_checker_id
55
string progress_checker_id
66
---
7-
#result definition
7+
# result definition
88

99
# Error codes
1010
# Note: The expected priority order of the errors should match the message order
@@ -22,6 +22,7 @@ std_msgs/Empty result
2222
uint16 error_code
2323
string error_msg
2424
---
25-
#feedback definition
26-
float32 distance_to_goal
27-
float32 speed
25+
# feedback definition
26+
# Real-time tracking error indicating which side of the path the robot is on
27+
# If the tracking_error is positive, the robot is to the left of the path
28+
nav2_msgs/TrackingFeedback tracking_feedback

nav2_msgs/msg/TrackingFeedback.msg

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# Real-time tracking error for Nav2 controller
2+
3+
std_msgs/Header header
4+
# The sign of the tracking error indicates which side of the path the robot is on
5+
# Positive sign indicates the robot is to the left of the path, negative to the right
6+
float32 tracking_error
7+
uint32 current_path_index
8+
geometry_msgs/PoseStamped robot_pose
9+
float32 distance_to_goal
10+
float32 speed
11+
float32 remaining_path_length

nav2_simple_commander/nav2_simple_commander/example_follow_path.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,9 +69,9 @@ def main() -> None:
6969
if feedback and i % 5 == 0:
7070
print(
7171
'Estimated distance remaining to goal position: '
72-
+ f'{feedback.distance_to_goal:.3f}'
72+
+ f'{feedback.tracking_feedback.distance_to_goal:.3f}'
7373
+ '\nCurrent speed of the robot: '
74-
+ f'{feedback.speed:.3f}'
74+
+ f'{feedback.tracking_feedback.speed:.3f}'
7575
)
7676

7777
# Do something depending on the return code

nav2_util/include/nav2_util/geometry_utils.hpp

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -231,6 +231,78 @@ inline bool isPointInsidePolygon(
231231
return res;
232232
}
233233

234+
/**
235+
* @brief Computes the shortest (perpendicular) distance from a point to a path segment.
236+
*
237+
* Given a point and a line segment defined by two poses, calculates the minimum distance
238+
* from the point to the segment in the XY plane. If the segment is too short,
239+
* returns the distance from the point to the segment's start.
240+
*
241+
* See: https://en.wikipedia.org/wiki/Distance_from_a_point_to_a_line
242+
*
243+
* @param point The point to measure from (geometry_msgs::msg::Point).
244+
* @param start The starting pose of the segment (geometry_msgs::msg::Pose).
245+
* @param end The ending pose of the segment (geometry_msgs::msg::Pose).
246+
* @return The shortest distance from the point to the segment in meters.
247+
*/
248+
inline double distance_to_path_segment(
249+
const geometry_msgs::msg::Point & point,
250+
const geometry_msgs::msg::Pose & start,
251+
const geometry_msgs::msg::Pose & end)
252+
{
253+
const auto & p = point;
254+
const auto & a = start.position;
255+
const auto & b = end.position;
256+
257+
const double dx_seg = b.x - a.x;
258+
const double dy_seg = b.y - a.y;
259+
260+
const double seg_len_sq = (dx_seg * dx_seg) + (dy_seg * dy_seg);
261+
262+
if (seg_len_sq <= 1e-9) {
263+
return euclidean_distance(point, a);
264+
}
265+
266+
const double dot = ((p.x - a.x) * dx_seg) + ((p.y - a.y) * dy_seg);
267+
const double t = std::clamp(dot / seg_len_sq, 0.0, 1.0);
268+
269+
const double proj_x = a.x + t * dx_seg;
270+
const double proj_y = a.y + t * dy_seg;
271+
272+
const double dx_proj = p.x - proj_x;
273+
const double dy_proj = p.y - proj_y;
274+
return std::hypot(dx_proj, dy_proj);
275+
}
276+
277+
/**
278+
* @brief Computes the 2D cross product between the vector from start to end and the vector from start to point.
279+
* The sign of this calculation's result can be used to determine which side are you on of the track.
280+
*
281+
* See: https://en.wikipedia.org/wiki/Cross_product
282+
*
283+
* @param point The point to check relative to the segment.
284+
* @param start The starting pose of the segment.
285+
* @param end The ending pose of the segment.
286+
* @return The signed 2D cross product value.
287+
*/
288+
inline double cross_product_2d(
289+
const geometry_msgs::msg::Point & point,
290+
const geometry_msgs::msg::Pose & start,
291+
const geometry_msgs::msg::Pose & end)
292+
{
293+
const auto & p = point;
294+
const auto & a = start.position;
295+
const auto & b = end.position;
296+
297+
const double path_vec_x = b.x - a.x;
298+
const double path_vec_y = b.y - a.y;
299+
300+
const double robot_vec_x = p.x - a.x;
301+
const double robot_vec_y = p.y - a.y;
302+
303+
return (path_vec_x * robot_vec_y) - (path_vec_y * robot_vec_x);
304+
}
305+
234306
} // namespace geometry_utils
235307
} // namespace nav2_util
236308

Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
// Copyright (c) 2025 Berkan Tali
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_UTIL__PATH_UTILS_HPP_
16+
#define NAV2_UTIL__PATH_UTILS_HPP_
17+
18+
#include <algorithm>
19+
#include <cmath>
20+
#include <limits>
21+
22+
#include "geometry_msgs/msg/pose.hpp"
23+
#include "geometry_msgs/msg/pose_stamped.hpp"
24+
#include "geometry_msgs/msg/point.hpp"
25+
#include "geometry_msgs/msg/quaternion.hpp"
26+
#include "nav_msgs/msg/path.hpp"
27+
#include "nav2_util/geometry_utils.hpp"
28+
namespace nav2_util
29+
{
30+
31+
/**
32+
* @brief Result of searching for the closest segment on a path.
33+
*/
34+
struct PathSearchResult
35+
{
36+
double distance;
37+
size_t closest_segment_index;
38+
};
39+
/**
40+
* @brief Finds the minimum distance from the robot's pose to the closest segment of a path.
41+
*
42+
* This function searches for the closest segment on the given path to the robot's pose.
43+
* By default, it finds the globally nearest path point. Optionally, you can specify
44+
* the index to start searching from (useful for path tracking tasks) and a maximum
45+
* search window length (in meters) to limit the search range.
46+
*
47+
* @param path The path to search (sequence of poses).
48+
* @param robot_pose The robot's current pose.
49+
* @param start_index The index in the path to start searching from (default: 0).
50+
* @param search_window_length The maximum length (in meters) to search along the path (default: unlimited).
51+
* @return PathSearchResult Struct containing the minimum distance and the index of the closest segment.
52+
*/
53+
PathSearchResult distance_from_path(
54+
const nav_msgs::msg::Path & path,
55+
const geometry_msgs::msg::Pose & robot_pose,
56+
const size_t start_index = 0,
57+
const double search_window_length = std::numeric_limits<double>::max());
58+
59+
} // namespace nav2_util
60+
61+
#endif // NAV2_UTIL__PATH_UTILS_HPP_

0 commit comments

Comments
 (0)