17 #include "nav2_mppi_controller/tools/path_handler.hpp"
18 #include "nav2_mppi_controller/tools/utils.hpp"
19 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
20 #include "nav2_util/robot_utils.hpp"
26 nav2::LifecycleNode::WeakPtr parent,
const std::string & name,
27 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
33 auto node = parent.lock();
34 logger_ = node->get_logger();
35 parameters_handler_ = param_handler;
38 getParam(max_robot_pose_search_dist_,
"max_robot_pose_search_dist",
getMaxCostmapDist());
39 getParam(prune_distance_,
"prune_distance", 1.5);
40 getParam(transform_tolerance_,
"transform_tolerance", 0.1);
41 getParam(enforce_path_inversion_,
"enforce_path_inversion",
false);
42 if (enforce_path_inversion_) {
43 getParam(inversion_xy_tolerance_,
"inversion_xy_tolerance", 0.2);
44 getParam(inversion_yaw_tolerance,
"inversion_yaw_tolerance", 0.4);
45 inversion_locale_ = 0u;
49 std::pair<nav_msgs::msg::Path, PathIterator>
51 const geometry_msgs::msg::PoseStamped & global_pose)
53 using nav2_util::geometry_utils::euclidean_distance;
55 auto begin = global_plan_up_to_inversion_.poses.begin();
58 auto closest_pose_upper_bound =
59 nav2_util::geometry_utils::first_after_integrated_distance(
60 global_plan_up_to_inversion_.poses.begin(), global_plan_up_to_inversion_.poses.end(),
61 max_robot_pose_search_dist_);
64 auto closest_point = nav2_util::geometry_utils::min_by(
65 begin, closest_pose_upper_bound,
66 [&global_pose](
const geometry_msgs::msg::PoseStamped & ps) {
67 return euclidean_distance(global_pose, ps);
70 nav_msgs::msg::Path transformed_plan;
71 transformed_plan.header.frame_id = costmap_->getGlobalFrameID();
72 transformed_plan.header.stamp = global_pose.header.stamp;
74 auto pruned_plan_end =
75 nav2_util::geometry_utils::first_after_integrated_distance(
76 closest_point, global_plan_up_to_inversion_.poses.end(), prune_distance_);
82 for (
auto global_plan_pose = closest_point; global_plan_pose != pruned_plan_end;
86 geometry_msgs::msg::PoseStamped costmap_plan_pose;
87 global_plan_pose->header.stamp = global_pose.header.stamp;
88 global_plan_pose->header.frame_id = global_plan_.header.frame_id;
89 nav2_util::transformPoseInTargetFrame(*global_plan_pose, costmap_plan_pose, *tf_buffer_,
90 costmap_->getGlobalFrameID(), transform_tolerance_);
93 if (!costmap_->getCostmap()->worldToMap(
94 costmap_plan_pose.pose.position.x, costmap_plan_pose.pose.position.y, mx, my))
96 return {transformed_plan, closest_point};
100 transformed_plan.poses.push_back(costmap_plan_pose);
103 return {transformed_plan, closest_point};
107 const geometry_msgs::msg::PoseStamped & pose)
109 if (global_plan_up_to_inversion_.poses.empty()) {
113 geometry_msgs::msg::PoseStamped robot_pose;
114 if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_buffer_,
115 global_plan_up_to_inversion_.header.frame_id, transform_tolerance_))
118 "Unable to transform robot pose into global plan's frame");
125 const geometry_msgs::msg::PoseStamped & robot_pose)
128 geometry_msgs::msg::PoseStamped global_pose =
132 prunePlan(global_plan_up_to_inversion_, lower_bound);
134 if (enforce_path_inversion_ && inversion_locale_ != 0u) {
136 prunePlan(global_plan_, global_plan_.poses.begin() + inversion_locale_);
137 global_plan_up_to_inversion_ = global_plan_;
138 inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
142 if (transformed_plan.poses.empty()) {
146 return transformed_plan;
151 const auto & costmap = costmap_->getCostmap();
152 return static_cast<double>(std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY())) *
153 costmap->getResolution() * 0.50;
159 global_plan_up_to_inversion_ = global_plan_;
160 if (enforce_path_inversion_) {
161 inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
169 plan.poses.erase(plan.poses.begin(), end);
173 const builtin_interfaces::msg::Time & stamp)
175 auto goal = global_plan_.poses.back();
176 goal.header.frame_id = global_plan_.header.frame_id;
177 goal.header.stamp = stamp;
178 if (goal.header.frame_id.empty()) {
181 geometry_msgs::msg::PoseStamped transformed_goal;
182 if (!nav2_util::transformPoseInTargetFrame(goal, transformed_goal, *tf_buffer_,
183 costmap_->getGlobalFrameID(), transform_tolerance_))
187 return transformed_goal;
193 const auto last_pose = global_plan_up_to_inversion_.poses.back();
194 float distance = hypotf(
195 robot_pose.pose.position.x - last_pose.pose.position.x,
196 robot_pose.pose.position.y - last_pose.pose.position.y);
198 float angle_distance = angles::shortest_angular_distance(
199 tf2::getYaw(robot_pose.pose.orientation),
200 tf2::getYaw(last_pose.pose.orientation));
202 return distance <= inversion_xy_tolerance_ && fabs(angle_distance) <= inversion_yaw_tolerance;
Handles getting parameters and dynamic parameter changes.
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped &robot_pose)
Check if the robot pose is within the set inversion tolerances.
std::pair< nav_msgs::msg::Path, PathIterator > getGlobalPlanConsideringBoundsInCostmapFrame(const geometry_msgs::msg::PoseStamped &global_pose)
Get global plan within window of the local costmap size.
nav_msgs::msg::Path & getPath()
Get reference path.
void setPath(const nav_msgs::msg::Path &plan)
Set new reference path.
double getMaxCostmapDist()
Get largest dimension of costmap (radially)
void initialize(nav2::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >, std::shared_ptr< tf2_ros::Buffer >, ParametersHandler *)
Initialize path handler on bringup.
geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time &stamp)
Get the global goal pose transformed to the local frame.
void prunePlan(nav_msgs::msg::Path &plan, const PathIterator end)
Prune a path to only interesting portions.
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped &robot_pose)
transform global plan to local applying constraints, then prune global plan
geometry_msgs::msg::PoseStamped transformToGlobalPlanFrame(const geometry_msgs::msg::PoseStamped &pose)
Transform a pose to the global reference frame.