base_obstacle.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/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     // Optimized/branchless version of if (sum_scores_) score += pose_score, else score = pose_score;
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 }  // namespace dwb_critics


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