obstacle_footprint.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
38 #include <nav_2d_utils/polygons.h>
39 #include <nav_2d_utils/footprint.h>
40 #include <nav_core2/exceptions.h>
42 #include <algorithm>
43 #include <vector>
44 
46 
47 namespace dwb_critics
48 {
49 
51 {
54 }
55 
56 bool ObstacleFootprintCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
57  const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)
58 {
59  if (footprint_spec_.points.size() == 0)
60  {
61  ROS_ERROR_NAMED("ObstacleFootprintCritic", "Footprint spec is empty, maybe missing call to setFootprint?");
62  return false;
63  }
64  return true;
65 }
66 
67 double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose)
68 {
69  unsigned int cell_x, cell_y;
70  if (!worldToGridBounded(costmap.getInfo(), pose.x, pose.y, cell_x, cell_y))
71  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid.");
73 }
74 
75 double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose,
76  const nav_2d_msgs::Polygon2D& footprint)
77 {
78  unsigned char footprint_cost = 0;
79  nav_grid::NavGridInfo info = costmap.getInfo();
80  for (nav_grid::Index index : nav_grid_iterators::PolygonOutline(&info, footprint))
81  {
82  unsigned char cost = costmap(index.x, index.y);
83  // if the cell is in an obstacle the path is invalid or unknown
84  if (cost == costmap.LETHAL_OBSTACLE)
85  {
86  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle.");
87  }
88  else if (cost == costmap.NO_INFORMATION)
89  {
90  throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Unknown Region.");
91  }
92  footprint_cost = std::max(cost, footprint_cost);
93  }
94 
95  // if all line costs are legal... then we can return that the footprint is legal
96  return footprint_cost;
97 }
98 
99 } // namespace dwb_critics
nav_grid_iterators::PolygonOutline
nav_core2::Costmap::NO_INFORMATION
static const unsigned char NO_INFORMATION
dwb_critics::BaseObstacleCritic::onInit
void onInit() override
Definition: base_obstacle.cpp:45
costmap
nav_core2::BasicCostmap costmap
nav_core2::IllegalTrajectoryException
dwb_local_planner::TrajectoryCritic::name_
std::string name_
nav_2d_utils::movePolygonToPose
nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D &polygon, const geometry_msgs::Pose2D &pose)
nav_2d_utils::footprintFromParams
nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle &nh, bool write=true)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
dwb_critics::ObstacleFootprintCritic::onInit
void onInit() override
Definition: obstacle_footprint.cpp:50
class_list_macros.h
polygon_outline.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
dwb_critics::ObstacleFootprintCritic::footprint_spec_
nav_2d_msgs::Polygon2D footprint_spec_
Definition: obstacle_footprint.h:66
worldToGridBounded
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)
nav_grid::GenericIndex
nav_core2::Costmap::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
dwb_critics::ObstacleFootprintCritic::prepare
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
Definition: obstacle_footprint.cpp:56
exceptions.h
nav_grid::NavGridInfo
coordinate_conversion.h
obstacle_footprint.h
dwb_critics::ObstacleFootprintCritic::scorePose
double scorePose(const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose) override
Return the obstacle score for a particular pose.
Definition: obstacle_footprint.cpp:67
dwb_local_planner::TrajectoryCritic::critic_nh_
ros::NodeHandle critic_nh_
footprint.h
polygons.h
dwb_critics::ObstacleFootprintCritic
Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajec...
Definition: obstacle_footprint.h:55
nav_core2::Costmap
dwb_critics
Definition: alignment_util.h:40
dwb_local_planner::TrajectoryCritic


dwb_critics
Author(s): David V. Lu!!
autogenerated on Sun May 18 2025 02:47:34