Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 #include <dwb_critics/goal_dist.h>
00035 #include <nav_grid/coordinate_conversion.h>
00036 #include <pluginlib/class_list_macros.h>
00037 #include <nav_2d_utils/path_ops.h>
00038 #include <vector>
00039 
00040 namespace dwb_critics
00041 {
00042 bool GoalDistCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00043                              const geometry_msgs::Pose2D& goal,
00044                              const nav_2d_msgs::Path2D& global_plan)
00045 {
00046   reset();
00047 
00048   unsigned int local_goal_x, local_goal_y;
00049   if (!getLastPoseOnCostmap(global_plan, local_goal_x, local_goal_y))
00050   {
00051     return false;
00052   }
00053 
00054   
00055   cell_values_.setValue(local_goal_x, local_goal_y, 0.0);
00056   queue_->enqueueCell(local_goal_x, local_goal_y);
00057 
00058   propogateManhattanDistances();
00059 
00060   return true;
00061 }
00062 
00063 bool GoalDistCritic::getLastPoseOnCostmap(const nav_2d_msgs::Path2D& global_plan, unsigned int& x, unsigned int& y)
00064 {
00065   const nav_core2::Costmap& costmap = *costmap_;
00066   const nav_grid::NavGridInfo& info = costmap.getInfo();
00067   nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution);
00068   bool started_path = false;
00069 
00070   
00071   for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); ++i)
00072   {
00073     double g_x = adjusted_global_plan.poses[i].x;
00074     double g_y = adjusted_global_plan.poses[i].y;
00075     unsigned int map_x, map_y;
00076     if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION)
00077     {
00078       
00079       x = map_x;
00080       y = map_y;
00081       started_path = true;
00082     }
00083     else if (started_path)
00084     {
00085       
00086       return true;
00087     }
00088     
00089   }
00090 
00091   if (started_path)
00092   {
00093     return true;
00094   }
00095   else
00096   {
00097     ROS_ERROR_NAMED("GoalDistCritic", "None of the points of the global plan were in the local costmap.");
00098     return false;
00099   }
00100 }
00101 
00102 }  
00103 
00104 PLUGINLIB_EXPORT_CLASS(dwb_critics::GoalDistCritic, dwb_local_planner::TrajectoryCritic)