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"
25 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
26 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
32 auto node = parent.lock();
33 logger_ = node->get_logger();
34 parameters_handler_ = param_handler;
37 getParam(max_robot_pose_search_dist_,
"max_robot_pose_search_dist",
getMaxCostmapDist());
38 getParam(prune_distance_,
"prune_distance", 1.5);
39 getParam(transform_tolerance_,
"transform_tolerance", 0.1);
40 getParam(enforce_path_inversion_,
"enforce_path_inversion",
false);
41 if (enforce_path_inversion_) {
42 getParam(inversion_xy_tolerance_,
"inversion_xy_tolerance", 0.2);
43 getParam(inversion_yaw_tolerance,
"inversion_yaw_tolerance", 0.4);
44 inversion_locale_ = 0u;
48 std::pair<nav_msgs::msg::Path, PathIterator>
50 const geometry_msgs::msg::PoseStamped & global_pose)
52 using nav2_util::geometry_utils::euclidean_distance;
54 auto begin = global_plan_up_to_inversion_.poses.begin();
57 auto closest_pose_upper_bound =
58 nav2_util::geometry_utils::first_after_integrated_distance(
59 global_plan_up_to_inversion_.poses.begin(), global_plan_up_to_inversion_.poses.end(),
60 max_robot_pose_search_dist_);
63 auto closest_point = nav2_util::geometry_utils::min_by(
64 begin, closest_pose_upper_bound,
65 [&global_pose](
const geometry_msgs::msg::PoseStamped & ps) {
66 return euclidean_distance(global_pose, ps);
69 nav_msgs::msg::Path transformed_plan;
70 transformed_plan.header.frame_id = costmap_->getGlobalFrameID();
71 transformed_plan.header.stamp = global_pose.header.stamp;
73 auto pruned_plan_end =
74 nav2_util::geometry_utils::first_after_integrated_distance(
75 closest_point, global_plan_up_to_inversion_.poses.end(), prune_distance_);
81 for (
auto global_plan_pose = closest_point; global_plan_pose != pruned_plan_end;
85 geometry_msgs::msg::PoseStamped costmap_plan_pose;
86 global_plan_pose->header.stamp = global_pose.header.stamp;
87 global_plan_pose->header.frame_id = global_plan_.header.frame_id;
88 transformPose(costmap_->getGlobalFrameID(), *global_plan_pose, costmap_plan_pose);
91 if (!costmap_->getCostmap()->worldToMap(
92 costmap_plan_pose.pose.position.x, costmap_plan_pose.pose.position.y, mx, my))
94 return {transformed_plan, closest_point};
98 transformed_plan.poses.push_back(costmap_plan_pose);
101 return {transformed_plan, closest_point};
105 const geometry_msgs::msg::PoseStamped & pose)
107 if (global_plan_up_to_inversion_.poses.empty()) {
108 throw std::runtime_error(
"Received plan with zero length");
111 geometry_msgs::msg::PoseStamped robot_pose;
112 if (!
transformPose(global_plan_up_to_inversion_.header.frame_id, pose, robot_pose)) {
113 throw std::runtime_error(
114 "Unable to transform robot pose into global plan's frame");
121 const geometry_msgs::msg::PoseStamped & robot_pose)
124 geometry_msgs::msg::PoseStamped global_pose =
128 prunePlan(global_plan_up_to_inversion_, lower_bound);
130 if (enforce_path_inversion_ && inversion_locale_ != 0u) {
132 prunePlan(global_plan_, global_plan_.poses.begin() + inversion_locale_);
133 global_plan_up_to_inversion_ = global_plan_;
134 inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
138 if (transformed_plan.poses.empty()) {
139 throw std::runtime_error(
"Resulting plan has 0 poses in it.");
142 return transformed_plan;
146 const std::string & frame,
const geometry_msgs::msg::PoseStamped & in_pose,
147 geometry_msgs::msg::PoseStamped & out_pose)
const
149 if (in_pose.header.frame_id == frame) {
155 tf_buffer_->transform(
156 in_pose, out_pose, frame,
157 tf2::durationFromSec(transform_tolerance_));
158 out_pose.header.frame_id = frame;
160 }
catch (tf2::TransformException & ex) {
161 RCLCPP_ERROR(logger_,
"Exception in transformPose: %s", ex.what());
168 const auto & costmap = costmap_->getCostmap();
169 return static_cast<double>(std::max(costmap->getSizeInCellsX(), costmap->getSizeInCellsY())) *
170 costmap->getResolution() * 0.50;
176 global_plan_up_to_inversion_ = global_plan_;
177 if (enforce_path_inversion_) {
178 inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
186 plan.poses.erase(plan.poses.begin(), end);
190 const builtin_interfaces::msg::Time & stamp)
192 auto goal = global_plan_.poses.back();
193 goal.header.frame_id = global_plan_.header.frame_id;
194 goal.header.stamp = stamp;
195 if (goal.header.frame_id.empty()) {
196 throw std::runtime_error(
"Goal pose has an empty frame_id");
198 geometry_msgs::msg::PoseStamped transformed_goal;
199 if (!
transformPose(costmap_->getGlobalFrameID(), goal, transformed_goal)) {
200 throw std::runtime_error(
"Unable to transform goal pose into costmap frame");
202 return transformed_goal;
208 const auto last_pose = global_plan_up_to_inversion_.poses.back();
209 float distance = hypotf(
210 robot_pose.pose.position.x - last_pose.pose.position.x,
211 robot_pose.pose.position.y - last_pose.pose.position.y);
213 float angle_distance = angles::shortest_angular_distance(
214 tf2::getYaw(robot_pose.pose.orientation),
215 tf2::getYaw(last_pose.pose.orientation));
217 return distance <= inversion_xy_tolerance_ && fabs(angle_distance) <= inversion_yaw_tolerance;
Handles getting parameters and dynamic parmaeter changes.
auto getParamGetter(const std::string &ns)
Get an object to retreive 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)
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.
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.
void initialize(rclcpp_lifecycle::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.
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.