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));
 
 
  146  const geometry_msgs::msg::Pose & pose, 
double r, 
double g, 
double b)
 
  148  double phi = tf2::getYaw(pose.orientation);
 
  150  visualization_msgs::msg::Marker marker;
 
  151  marker.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
 
  152  marker.header.stamp = 
nh_->now();
 
  153  marker.ns = 
"my_namespace2";
 
  155  marker.type = visualization_msgs::msg::Marker::ARROW;
 
  156  marker.action = visualization_msgs::msg::Marker::ADD;
 
  157  marker.scale.x = 0.1;
 
  158  marker.scale.y = 0.3;
 
  159  marker.scale.z = 0.1;
 
  160  marker.color.a = 1.0;
 
  166  marker.lifetime = rclcpp::Duration(0s);
 
  168  geometry_msgs::msg::Point start, end;
 
  169  start.x = pose.position.x;
 
  170  start.y = pose.position.y;
 
  172  end.x = pose.position.x + 0.5 * cos(phi);
 
  173  end.y = pose.position.y + 0.5 * sin(phi);
 
  175  marker.points.push_back(start);
 
  176  marker.points.push_back(end);
 
  178  visualization_msgs::msg::MarkerArray ma;
 
  179  ma.markers.push_back(marker);
 
 
  189  const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & ,
 
  190  std::vector<geometry_msgs::msg::PoseStamped> & plan)
 
  196  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Transforming forward path");
 
  197  nav_msgs::msg::Path transformedPlan;
 
  201    geometry_msgs::msg::PoseStamped transformedPose;
 
  202    p.header.stamp = 
nh_->now();  
 
  203    transformedPose.header.stamp = 
nh_->now();
 
  204    transformedPose.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  205    nav_2d_utils::transformPose(
tf_, 
costmap_ros_->getGlobalFrameID(), p, transformedPose, ttol);
 
  206    transformedPlan.poses.push_back(transformedPose);
 
  212  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] finding goal closest point");
 
  214  double linear_mindist = std::numeric_limits<double>::max();
 
  215  int mindistindex = -1;
 
  216  double startPoseAngle = tf2::getYaw(start.pose.orientation);
 
  217  geometry_msgs::msg::Pose startPositionProjected;
 
  223  for (
auto & p : transformedPlan.poses )
 
  225    geometry_msgs::msg::PoseStamped pose = p;
 
  226    pose.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  228    double dx = pose.pose.position.x - start.pose.position.x;
 
  229    double dy = pose.pose.position.y - start.pose.position.y;
 
  231    double dist = sqrt(dx * dx + dy * dy);
 
  232    double angleOrientation = tf2::getYaw(pose.pose.orientation);
 
  233    double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
 
  234    if (dist <= linear_mindist)
 
  237      linear_mindist = dist;
 
  238      startPositionProjected = pose.pose;
 
  241        nh_->get_logger(), 
"[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= " 
  242                             << i << 
". error, linear: " << linear_mindist
 
  243                             << 
", angular: " << angleError);
 
  248        nh_->get_logger(), 
"[UndoPathGlobalPlanner] initial start point search, skipped= " 
  249                             << i << 
". best linear error: " << linear_mindist
 
  250                             << 
". current error, linear: " << dist << 
" angular: " << angleError);
 
  256  double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;
 
  261  RCLCPP_INFO(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] second angular pass");
 
  262  double angularMinDist = std::numeric_limits<double>::max();
 
  264  if (mindistindex >= (
int)transformedPlan.poses.size())
 
  266      transformedPlan.poses.size() -
 
  269    if (transformedPlan.poses.size() == 0)
 
  271      RCLCPP_WARN_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Warning possible bug");
 
  275    RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] second pass loop");
 
  276    for (
int i = mindistindex; i >= 0; i--)
 
  281        nh_->get_logger(), 
"[UndoPathGlobalPlanner] " << i << 
"/" << transformedPlan.poses.size());
 
  282      auto index = (int)transformedPlan.poses.size() - i - 1;
 
  283      if (index < 0 || (
size_t)index >= transformedPlan.poses.size())
 
  287          "[UndoPathGlobalPlanner] this should not happen. Check implementation.");
 
  290      geometry_msgs::msg::PoseStamped pose =
 
  291        transformedPlan.poses[transformedPlan.poses.size() - i - 1];
 
  293      RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] global frame");
 
  294      pose.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  296      double dx = pose.pose.position.x - start.pose.position.x;
 
  297      double dy = pose.pose.position.y - start.pose.position.y;
 
  299      double dist = sqrt(dx * dx + dy * dy);
 
  300      if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)
 
  302        double angleOrientation = tf2::getYaw(pose.pose.orientation);
 
  304          fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));
 
  305        if (angleError < angularMinDist)
 
  307          angularMinDist = angleError;
 
  311            "[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= " 
  312              << i << 
". error, linear: " << dist << 
"(" << linear_mindist << 
")" 
  313              << 
", angular: " << angleError << 
"(" << angularMinDist << 
")");
 
  319            "[UndoPathGlobalPlanner] initial start point search (angular update), skipped= " 
  320              << i << 
". error, linear: " << dist << 
"(" << linear_mindist << 
")" 
  321              << 
", angular: " << angleError << 
"(" << angularMinDist << 
")");
 
  328          "[UndoPathGlobalPlanner] initial start point search (angular update) not in linear " 
  330            << i << 
" linear error: " << dist << 
"(" << linear_mindist << 
")");
 
  336  if (mindistindex != -1)
 
  342      "[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (, " 
  343        << transformedPlan.poses.size() << 
") poses");
 
  346      nh_->get_logger(), 
"[UndoPathGlobalPlanner] closer point to goal i=" 
  347                           << mindistindex << 
" (linear min dist " << linear_mindist << 
")");
 
  350    for (
int i = transformedPlan.poses.size() - 1; i >= mindistindex; i--)
 
  352      auto & pose = transformedPlan.poses[i];
 
  354      rclcpp::Time t(pose.header.stamp);
 
  358        "[UndoPathGlobalPlanner] adding to plan i = " << i << 
" stamp:" << t.seconds());
 
  359      plan.push_back(pose);
 
  362      nh_->get_logger(), 
"[UndoPathGlobalPlanner] refined plan has " << plan.size() << 
"  points");
 
  367      nh_->get_logger(), 
"[UndoPathGlobalPlanner ] undo global plan size:  " << plan.size());
 
 
  377  const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & goal)
 
  381  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Undo global plan start ");
 
  382  nav_msgs::msg::Path planMsg;
 
  383  std::vector<geometry_msgs::msg::PoseStamped> & plan = planMsg.poses;
 
  387    "[UndoPathGlobalPlanner] last forward path msg size: " << 
lastForwardPathMsg_.poses.size());
 
  390    nh_->get_logger(), 
"[UndoPathGlobalPlanner] last forward path frame id: " 
  393    nh_->get_logger(), 
"[UndoPathGlobalPlanner] start pose frame id: " << start.header.frame_id);
 
  395    nh_->get_logger(), 
"[UndoPathGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
 
  403  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Inputs accommodation");
 
  404  geometry_msgs::msg::PoseStamped transformedStart, transformedGoal;
 
  408    geometry_msgs::msg::PoseStamped pstart = start;
 
  409    pstart.header.stamp = 
nh_->now();
 
  410    nav_2d_utils::transformPose(
 
  411      tf_, 
costmap_ros_->getGlobalFrameID(), pstart, transformedStart, ttol);
 
  412    transformedStart.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  420    RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Forced goal");
 
  423    forcedGoal.header.stamp = 
nh_->now();
 
  424    nav_2d_utils::transformPose(
 
  425      tf_, 
costmap_ros_->getGlobalFrameID(), forcedGoal, transformedGoal, ttol);
 
  426    transformedGoal.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  430  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] Creating undo plan");
 
  432  planMsg.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
 
  434  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] publishing goal markers");
 
  438  bool acceptedGlobalPlan = 
true;
 
  439  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[UndoPathGlobalPlanner] valid plan checking");
 
  442  for (
auto & p : plan)
 
  445    costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
 
  446    auto cost = costmap2d->getCost(mx, my);
 
  448    if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
 
  450      acceptedGlobalPlan = 
false;
 
  460    nh_->get_logger(), 
"[UndoPathGlobalPlanner] plan publishing. size: " << plan.size());
 
  462  if (!acceptedGlobalPlan)
 
  466      "[UndoPathGlobalPlanner] not accepted global plan because of possible collision");
 
  470    nh_->get_logger(), 
"[UndoPathGlobalPlanner] plan publishing. size: " << planMsg.poses.size());