43 const geometry_msgs::Pose2D& goal,
44 const nav_2d_msgs::Path2D& global_plan)
49 bool started_path =
false;
53 if (adjusted_global_plan.poses.size() != global_plan.poses.size())
55 ROS_DEBUG_NAMED(
"PathDistCritic",
"Adjusted global plan resolution, added %zu points",
56 adjusted_global_plan.poses.size() - global_plan.poses.size());
61 for (i = 0; i < adjusted_global_plan.poses.size(); ++i)
63 double g_x = adjusted_global_plan.poses[i].x;
64 double g_y = adjusted_global_plan.poses[i].y;
65 unsigned int map_x, map_y;
69 queue_->enqueueCell(map_x, map_y);
72 else if (started_path)
80 "None of the %d first of %zu (%zu) points of the global plan were in the local costmap and free",
81 i, adjusted_global_plan.poses.size(), global_plan.poses.size());