84 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
85 std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
94 rclcpp::SensorDataQoS qos;
97 "odom_tracker_path", qos,
101 nh_->create_publisher<nav_msgs::msg::Path>(
"undo_path_planner/global_plan", rclcpp::QoS(1));
102 markersPub_ =
nh_->create_publisher<visualization_msgs::msg::MarkerArray>(
103 "undo_path_planner/markers", rclcpp::QoS(1));
145 const geometry_msgs::msg::Pose & pose,
double r,
double g,
double b)
147 double phi = tf2::getYaw(pose.orientation);
149 visualization_msgs::msg::Marker marker;
150 marker.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
151 marker.header.stamp =
nh_->now();
152 marker.ns =
"my_namespace2";
154 marker.type = visualization_msgs::msg::Marker::ARROW;
155 marker.action = visualization_msgs::msg::Marker::ADD;
156 marker.scale.x = 0.1;
157 marker.scale.y = 0.3;
158 marker.scale.z = 0.1;
159 marker.color.a = 1.0;
165 marker.lifetime = rclcpp::Duration(0s);
167 geometry_msgs::msg::Point start, end;
168 start.x = pose.position.x;
169 start.y = pose.position.y;
171 end.x = pose.position.x + 0.5 * cos(phi);
172 end.y = pose.position.y + 0.5 * sin(phi);
174 marker.points.push_back(start);
175 marker.points.push_back(end);
177 visualization_msgs::msg::MarkerArray ma;
178 ma.markers.push_back(marker);
188 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & ,
189 std::vector<geometry_msgs::msg::PoseStamped> & plan)
195 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Transforming forward path");
196 nav_msgs::msg::Path transformedPlan;
200 geometry_msgs::msg::PoseStamped transformedPose;
201 p.header.stamp =
nh_->now();
202 transformedPose.header.stamp =
nh_->now();
203 transformedPose.header.frame_id =
costmap_ros_->getGlobalFrameID();
204 nav_2d_utils::transformPose(
tf_,
costmap_ros_->getGlobalFrameID(), p, transformedPose, ttol);
205 transformedPlan.poses.push_back(transformedPose);
211 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] finding goal closest point");
213 double linear_mindist = std::numeric_limits<double>::max();
214 int mindistindex = -1;
215 double startPoseAngle = tf2::getYaw(start.pose.orientation);
216 geometry_msgs::msg::Pose startPositionProjected;
222 for (
auto & p : transformedPlan.poses )
224 geometry_msgs::msg::PoseStamped pose = p;
225 pose.header.frame_id =
costmap_ros_->getGlobalFrameID();
227 double dx = pose.pose.position.x - start.pose.position.x;
228 double dy = pose.pose.position.y - start.pose.position.y;
230 double dist = sqrt(dx * dx + dy * dy);
231 double angleOrientation = tf2::getYaw(pose.pose.orientation);
232 double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
233 if (dist <= linear_mindist)
236 linear_mindist = dist;
237 startPositionProjected = pose.pose;
240 nh_->get_logger(),
"[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= "
241 << i <<
". error, linear: " << linear_mindist
242 <<
", angular: " << angleError);
247 nh_->get_logger(),
"[UndoPathGlobalPlanner] initial start point search, skipped= "
248 << i <<
". best linear error: " << linear_mindist
249 <<
". current error, linear: " << dist <<
" angular: " << angleError);
255 double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;
260 RCLCPP_INFO(
nh_->get_logger(),
"[UndoPathGlobalPlanner] second angular pass");
261 double angularMinDist = std::numeric_limits<double>::max();
263 if (mindistindex >= (
int)transformedPlan.poses.size())
265 transformedPlan.poses.size() -
268 if (transformedPlan.poses.size() == 0)
270 RCLCPP_WARN_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Warning possible bug");
274 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] second pass loop");
275 for (
int i = mindistindex; i >= 0; i--)
280 nh_->get_logger(),
"[UndoPathGlobalPlanner] " << i <<
"/" << transformedPlan.poses.size());
281 auto index = (int)transformedPlan.poses.size() - i - 1;
282 if (index < 0 || (
size_t)index >= transformedPlan.poses.size())
286 "[UndoPathGlobalPlanner] this should not happen. Check implementation.");
289 geometry_msgs::msg::PoseStamped pose =
290 transformedPlan.poses[transformedPlan.poses.size() - i - 1];
292 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] global frame");
293 pose.header.frame_id =
costmap_ros_->getGlobalFrameID();
295 double dx = pose.pose.position.x - start.pose.position.x;
296 double dy = pose.pose.position.y - start.pose.position.y;
298 double dist = sqrt(dx * dx + dy * dy);
299 if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)
301 double angleOrientation = tf2::getYaw(pose.pose.orientation);
303 fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
304 if (angleError < angularMinDist)
306 angularMinDist = angleError;
310 "[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= "
311 << i <<
". error, linear: " << dist <<
"(" << linear_mindist <<
")"
312 <<
", angular: " << angleError <<
"(" << angularMinDist <<
")");
318 "[UndoPathGlobalPlanner] initial start point search (angular update), skipped= "
319 << i <<
". error, linear: " << dist <<
"(" << linear_mindist <<
")"
320 <<
", angular: " << angleError <<
"(" << angularMinDist <<
")");
327 "[UndoPathGlobalPlanner] initial start point search (angular update) not in linear "
329 << i <<
" linear error: " << dist <<
"(" << linear_mindist <<
")");
335 if (mindistindex != -1)
341 "[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (, "
342 << transformedPlan.poses.size() <<
") poses");
345 nh_->get_logger(),
"[UndoPathGlobalPlanner] closer point to goal i="
346 << mindistindex <<
" (linear min dist " << linear_mindist <<
")");
349 for (
int i = transformedPlan.poses.size() - 1; i >= mindistindex; i--)
351 auto & pose = transformedPlan.poses[i];
353 rclcpp::Time t(pose.header.stamp);
357 "[UndoPathGlobalPlanner] adding to plan i = " << i <<
" stamp:" << t.seconds());
358 plan.push_back(pose);
361 nh_->get_logger(),
"[UndoPathGlobalPlanner] refined plan has " << plan.size() <<
" points");
366 nh_->get_logger(),
"[UndoPathGlobalPlanner ] undo global plan size: " << plan.size());
376 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal)
380 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Undo global plan start ");
381 nav_msgs::msg::Path planMsg;
382 std::vector<geometry_msgs::msg::PoseStamped> & plan = planMsg.poses;
386 "[UndoPathGlobalPlanner] last forward path msg size: " <<
lastForwardPathMsg_.poses.size());
389 nh_->get_logger(),
"[UndoPathGlobalPlanner] last forward path frame id: "
392 nh_->get_logger(),
"[UndoPathGlobalPlanner] start pose frame id: " << start.header.frame_id);
394 nh_->get_logger(),
"[UndoPathGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
402 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Inputs accommodation");
403 geometry_msgs::msg::PoseStamped transformedStart, transformedGoal;
407 geometry_msgs::msg::PoseStamped pstart = start;
408 pstart.header.stamp =
nh_->now();
409 nav_2d_utils::transformPose(
410 tf_,
costmap_ros_->getGlobalFrameID(), pstart, transformedStart, ttol);
411 transformedStart.header.frame_id =
costmap_ros_->getGlobalFrameID();
419 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Forced goal");
422 forcedGoal.header.stamp =
nh_->now();
423 nav_2d_utils::transformPose(
424 tf_,
costmap_ros_->getGlobalFrameID(), forcedGoal, transformedGoal, ttol);
425 transformedGoal.header.frame_id =
costmap_ros_->getGlobalFrameID();
429 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] Creating undo plan");
431 planMsg.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
433 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] publishing goal markers");
437 bool acceptedGlobalPlan =
true;
438 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[UndoPathGlobalPlanner] valid plan checking");
441 for (
auto & p : plan)
444 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
445 auto cost = costmap2d->getCost(mx, my);
447 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
449 acceptedGlobalPlan =
false;
456 nh_->get_logger(),
"[UndoPathGlobalPlanner] plan publishing. size: " << plan.size());
458 if (!acceptedGlobalPlan)
462 "[UndoPathGlobalPlanner] not accepted global plan because of possible collision");
466 nh_->get_logger(),
"[UndoPathGlobalPlanner] plan publishing. size: " << planMsg.poses.size());