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/obstacle_footprint.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_grid_iterators/polygon_outline.h>
00038 #include <nav_2d_utils/polygons.h>
00039 #include <nav_2d_utils/footprint.h>
00040 #include <nav_core2/exceptions.h>
00041 #include <pluginlib/class_list_macros.h>
00042 #include <algorithm>
00043 #include <vector>
00044
00045 PLUGINLIB_EXPORT_CLASS(dwb_critics::ObstacleFootprintCritic, dwb_local_planner::TrajectoryCritic)
00046
00047 namespace dwb_critics
00048 {
00049
00050 void ObstacleFootprintCritic::onInit()
00051 {
00052 BaseObstacleCritic::onInit();
00053 footprint_spec_ = nav_2d_utils::footprintFromParams(critic_nh_);
00054 }
00055
00056 bool ObstacleFootprintCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00057 const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)
00058 {
00059 if (footprint_spec_.points.size() == 0)
00060 {
00061 ROS_ERROR_NAMED("ObstacleFootprintCritic", "Footprint spec is empty, maybe missing call to setFootprint?");
00062 return false;
00063 }
00064 return true;
00065 }
00066
00067 double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose)
00068 {
00069 unsigned int cell_x, cell_y;
00070 if (!worldToGridBounded(costmap.getInfo(), pose.x, pose.y, cell_x, cell_y))
00071 throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
00072 return scorePose(costmap, pose, nav_2d_utils::movePolygonToPose(footprint_spec_, pose));
00073 }
00074
00075 double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose,
00076 const nav_2d_msgs::Polygon2D& footprint)
00077 {
00078 unsigned char footprint_cost = 0;
00079 nav_grid::NavGridInfo info = costmap.getInfo();
00080 for (nav_grid::Index index : nav_grid_iterators::PolygonOutline(&info, footprint))
00081 {
00082 unsigned char cost = costmap(index.x, index.y);
00083
00084 if (cost == costmap.LETHAL_OBSTACLE)
00085 {
00086 throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
00087 }
00088 else if (cost == costmap.NO_INFORMATION)
00089 {
00090 throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Unknown Region.");
00091 }
00092 footprint_cost = std::max(cost, footprint_cost);
00093 }
00094
00095
00096 return footprint_cost;
00097 }
00098
00099 }