Skip to content

Commit

Permalink
removed RPP dependency (ros-navigation#4222)
Browse files Browse the repository at this point in the history
Signed-off-by: jncfa <[email protected]>
  • Loading branch information
jncfa authored and Manos-G committed Aug 1, 2024
1 parent 2a4b8a7 commit 7a692ba
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions nav2_regulated_pure_pursuit_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5)
project(nav2_regulated_pure_pursuit_controller)

find_package(ament_cmake REQUIRED)
find_package(nav2_amcl REQUIRED)
find_package(angles REQUIRED)
find_package(nav2_common REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
Expand All @@ -27,7 +27,7 @@ set(dependencies
nav2_costmap_2d
pluginlib
nav_msgs
nav2_amcl
angles
nav2_util
nav2_core
tf2
Expand Down
2 changes: 1 addition & 1 deletion nav2_regulated_pure_pursuit_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>nav2_amcl</depend>
<depend>angles</depend>
<depend>nav2_common</depend>
<depend>nav2_core</depend>
<depend>nav2_util</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <vector>
#include <utility>

#include "nav2_amcl/angleutils.hpp"
#include "angles/angles.h"
#include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp"
#include "nav2_core/controller_exceptions.hpp"
#include "nav2_util/node_utils.hpp"
Expand Down Expand Up @@ -266,7 +266,7 @@ bool RegulatedPurePursuitController::shouldRotateToPath(
angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
// In case we are reversing
if (x_vel_sign < 0.0) {
angle_to_path = nav2_amcl::angleutils::normalize(angle_to_path + M_PI);
angle_to_path = angles::normalize_angle(angle_to_path + M_PI);
}
return params_->use_rotate_to_heading &&
fabs(angle_to_path) > params_->rotate_to_heading_min_angle;
Expand Down

0 comments on commit 7a692ba

Please sign in to comment.