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 
00035 #include <dwb_critics/base_obstacle.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <pluginlib/class_list_macros.h>
00039 
00040 PLUGINLIB_EXPORT_CLASS(dwb_critics::BaseObstacleCritic, dwb_local_planner::TrajectoryCritic)
00041 
00042 namespace dwb_critics
00043 {
00044 
00045 void BaseObstacleCritic::onInit()
00046 {
00047   critic_nh_.param("sum_scores", sum_scores_, false);
00048 }
00049 
00050 double BaseObstacleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj)
00051 {
00052   const nav_core2::Costmap& costmap = *costmap_;
00053   double score = 0.0;
00054   for (unsigned int i = 0; i < traj.poses.size(); ++i)
00055   {
00056     double pose_score = scorePose(costmap, traj.poses[i]);
00057     
00058     score = static_cast<double>(sum_scores_) * score + pose_score;
00059   }
00060   return score;
00061 }
00062 
00063 double BaseObstacleCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose)
00064 {
00065   unsigned int cell_x, cell_y;
00066   if (!worldToGridBounded(costmap.getInfo(), pose.x, pose.y, cell_x, cell_y))
00067     throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
00068   unsigned char cost = costmap(cell_x, cell_y);
00069   if (!isValidCost(cost))
00070     throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
00071   return cost;
00072 }
00073 
00074 bool BaseObstacleCritic::isValidCost(const unsigned char cost)
00075 {
00076   return cost != costmap_->LETHAL_OBSTACLE &&
00077          cost != costmap_->INSCRIBED_INFLATED_OBSTACLE &&
00078          cost != costmap_->NO_INFORMATION;
00079 }
00080 
00081 void BaseObstacleCritic::addCriticVisualization(sensor_msgs::PointCloud& pc)
00082 {
00083   sensor_msgs::ChannelFloat32 grid_scores;
00084   grid_scores.name = name_;
00085 
00086   const nav_core2::Costmap& costmap = *costmap_;
00087   unsigned int size_x = costmap.getWidth();
00088   unsigned int size_y = costmap.getHeight();
00089   grid_scores.values.resize(size_x * size_y);
00090   unsigned int i = 0;
00091   for (unsigned int cy = 0; cy < size_y; cy++)
00092   {
00093     for (unsigned int cx = 0; cx < size_x; cx++)
00094     {
00095       grid_scores.values[i] = costmap(cx, cy);
00096       i++;
00097     }
00098   }
00099   pc.channels.push_back(grid_scores);
00100 }
00101 
00102 }