obstacle_footprint.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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     // if the cell is in an obstacle the path is invalid or unknown
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   // if all line costs are legal... then we can return that the footprint is legal
00096   return footprint_cost;
00097 }
00098 
00099 }  // namespace dwb_critics


dwb_critics
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:47