From 1f32dcabcaad9643a9222cdbf2ae9e304514b37b Mon Sep 17 00:00:00 2001 From: Narahari Rahul Malayanur <60045406+Naraharirahul@users.noreply.github.com> Date: Fri, 15 Oct 2021 15:05:25 -0400 Subject: [PATCH] Modified the projection_time calculation (#2609) (cherry picked from commit 8faa0f0550027edc7bf2640f23cff13b2af60a8f) --- .../src/regulated_pure_pursuit_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp index 8a0a1034be..51d3f2c93f 100644 --- a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp @@ -346,7 +346,7 @@ bool RegulatedPurePursuitController::isCollisionImminent( pose_msg.header.frame_id = arc_pts_msg.header.frame_id; pose_msg.header.stamp = arc_pts_msg.header.stamp; - const double projection_time = costmap_->getResolution() / linear_vel; + const double projection_time = costmap_->getResolution() / fabs(linear_vel); geometry_msgs::msg::Pose2D curr_pose; curr_pose.x = robot_pose.pose.position.x;