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 38adc7030c..6cda1b6faf 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 @@ -395,7 +395,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;