22 #include "nav2_regulated_pure_pursuit_controller/path_handler.hpp"
23 #include "nav2_core/controller_exceptions.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
27 namespace nav2_regulated_pure_pursuit_controller
30 using nav2_util::geometry_utils::euclidean_distance;
33 tf2::Duration transform_tolerance,
34 std::shared_ptr<tf2_ros::Buffer> tf,
35 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
36 : transform_tolerance_(transform_tolerance), tf_(tf), costmap_ros_(costmap_ros)
42 const double max_costmap_dim_meters = std::max(
43 costmap_ros_->getCostmap()->getSizeInMetersX(),
44 costmap_ros_->getCostmap()->getSizeInMetersY());
45 return max_costmap_dim_meters / 2.0;
49 const geometry_msgs::msg::PoseStamped & pose,
50 double max_robot_pose_search_dist,
51 bool reject_unit_path)
53 if (global_plan_.poses.empty()) {
57 if (reject_unit_path && global_plan_.poses.size() == 1) {
62 geometry_msgs::msg::PoseStamped robot_pose;
63 if (!
transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
67 auto closest_pose_upper_bound =
68 nav2_util::geometry_utils::first_after_integrated_distance(
69 global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist);
74 auto transformation_begin =
75 nav2_util::geometry_utils::min_by(
76 global_plan_.poses.begin(), closest_pose_upper_bound,
77 [&robot_pose](
const geometry_msgs::msg::PoseStamped & ps) {
78 return euclidean_distance(robot_pose, ps);
84 if (global_plan_.poses.begin() != closest_pose_upper_bound && global_plan_.poses.size() > 1 &&
85 transformation_begin == std::prev(closest_pose_upper_bound))
87 transformation_begin = std::prev(std::prev(closest_pose_upper_bound));
92 auto transformation_end = std::find_if(
93 transformation_begin, global_plan_.poses.end(),
94 [&](
const auto & global_plan_pose) {
95 return euclidean_distance(global_plan_pose, robot_pose) > max_costmap_extent;
99 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
100 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
101 stamped_pose.header.frame_id = global_plan_.header.frame_id;
102 stamped_pose.header.stamp = robot_pose.header.stamp;
103 stamped_pose.pose = global_plan_pose.pose;
104 if (!
transformPose(costmap_ros_->getBaseFrameID(), stamped_pose, transformed_pose)) {
107 transformed_pose.pose.position.z = 0.0;
108 return transformed_pose;
112 nav_msgs::msg::Path transformed_plan;
114 transformation_begin, transformation_end,
115 std::back_inserter(transformed_plan.poses),
116 transformGlobalPoseToLocal);
117 transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
118 transformed_plan.header.stamp = robot_pose.header.stamp;
122 global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
124 if (transformed_plan.poses.empty()) {
128 return transformed_plan;
132 const std::string frame,
133 const geometry_msgs::msg::PoseStamped & in_pose,
134 geometry_msgs::msg::PoseStamped & out_pose)
const
136 if (in_pose.header.frame_id == frame) {
142 tf_->transform(in_pose, out_pose, frame, transform_tolerance_);
143 out_pose.header.frame_id = frame;
145 }
catch (tf2::TransformException & ex) {
146 RCLCPP_ERROR(logger_,
"Exception in transformPose: %s", ex.what());
bool transformPose(const std::string frame, const geometry_msgs::msg::PoseStamped &in_pose, geometry_msgs::msg::PoseStamped &out_pose) const
Transform a pose to another frame.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist, bool reject_unit_path=false)
Transforms global plan into same frame as pose and clips poses ineligible for lookaheadPoint Points i...
double getCostmapMaxExtent() const
PathHandler(tf2::Duration transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_regulated_pure_pursuit_controller::PathHandler.