22 #include "nav2_core/controller_exceptions.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/geometry_utils.hpp"
25 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_graceful_controller/path_handler.hpp"
28 namespace nav2_graceful_controller
31 using nav2_util::geometry_utils::euclidean_distance;
34 double transform_tolerance,
35 std::shared_ptr<tf2_ros::Buffer> tf,
36 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
37 : transform_tolerance_(transform_tolerance), tf_buffer_(tf), costmap_ros_(costmap_ros)
42 const geometry_msgs::msg::PoseStamped & pose,
43 double max_robot_pose_search_dist)
46 if (global_plan_.poses.empty()) {
51 geometry_msgs::msg::PoseStamped robot_pose;
52 if (!nav2_util::transformPoseInTargetFrame(
53 pose, robot_pose, *tf_buffer_, global_plan_.header.frame_id,
54 transform_tolerance_))
61 auto closest_pose_upper_bound =
62 nav2_util::geometry_utils::first_after_integrated_distance(
63 global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist);
68 auto transformation_begin =
69 nav2_util::geometry_utils::min_by(
70 global_plan_.poses.begin(), closest_pose_upper_bound,
71 [&robot_pose](
const geometry_msgs::msg::PoseStamped & ps) {
72 return euclidean_distance(robot_pose, ps);
76 double dist_threshold = std::max(
77 costmap_ros_->getCostmap()->getSizeInMetersX(),
78 costmap_ros_->getCostmap()->getSizeInMetersY()) / 2.0;
79 auto transformation_end = std::find_if(
80 transformation_begin, global_plan_.poses.end(),
81 [&](
const auto & global_plan_pose) {
82 return euclidean_distance(global_plan_pose, robot_pose) > dist_threshold;
86 auto transformGlobalPoseToLocal = [&](
const auto & global_plan_pose) {
87 geometry_msgs::msg::PoseStamped stamped_pose, transformed_pose;
88 stamped_pose.header.frame_id = global_plan_.header.frame_id;
89 stamped_pose.header.stamp = robot_pose.header.stamp;
90 stamped_pose.pose = global_plan_pose.pose;
91 if (!nav2_util::transformPoseInTargetFrame(
92 stamped_pose, transformed_pose, *tf_buffer_,
93 costmap_ros_->getBaseFrameID(), transform_tolerance_))
97 transformed_pose.pose.position.z = 0.0;
98 return transformed_pose;
102 nav_msgs::msg::Path transformed_plan;
103 transformed_plan.header.frame_id = costmap_ros_->getBaseFrameID();
104 transformed_plan.header.stamp = robot_pose.header.stamp;
106 transformation_begin, transformation_end,
107 std::back_inserter(transformed_plan.poses),
108 transformGlobalPoseToLocal);
112 global_plan_.poses.erase(begin(global_plan_.poses), transformation_begin);
114 if (transformed_plan.poses.empty()) {
118 return transformed_plan;
PathHandler(double transform_tolerance, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)
Constructor for nav2_graceful_controller::PathHandler.
void setPlan(const nav_msgs::msg::Path &path)
Sets the global plan.
nav_msgs::msg::Path transformGlobalPlan(const geometry_msgs::msg::PoseStamped &pose, double max_robot_pose_search_dist)
Transforms global plan into same frame as pose and clips poses ineligible for motionTarget Points ine...