costmap_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
39 #include <costmap_2d/cost_values.h>
40 
41 using namespace std;
42 using namespace costmap_2d;
43 
44 namespace base_local_planner {
45  CostmapModel::CostmapModel(const Costmap2D& ma) : costmap_(ma) {}
46 
47  double CostmapModel::footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
48  double inscribed_radius, double circumscribed_radius){
49 
50  //used to put things into grid coordinates
51  unsigned int cell_x, cell_y;
52 
53  //get the cell coord of the center point of the robot
54  if(!costmap_.worldToMap(position.x, position.y, cell_x, cell_y))
55  return -1.0;
56 
57  //if number of points in the footprint is less than 3, we'll just assume a circular robot
58  if(footprint.size() < 3){
59  unsigned char cost = costmap_.getCost(cell_x, cell_y);
60  //if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE)
61  if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION)
62  return -1.0;
63  return cost;
64  }
65 
66  //now we really have to lay down the footprint in the costmap grid
67  unsigned int x0, x1, y0, y1;
68  double line_cost = 0.0;
69  double footprint_cost = 0.0;
70 
71  //we need to rasterize each line in the footprint
72  for(unsigned int i = 0; i < footprint.size() - 1; ++i){
73  //get the cell coord of the first point
74  if(!costmap_.worldToMap(footprint[i].x, footprint[i].y, x0, y0))
75  return -1.0;
76 
77  //get the cell coord of the second point
78  if(!costmap_.worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
79  return -1.0;
80 
81  line_cost = lineCost(x0, x1, y0, y1);
82  footprint_cost = std::max(line_cost, footprint_cost);
83 
84  //if there is an obstacle that hits the line... we know that we can return false right away
85  if(line_cost < 0)
86  return -1.0;
87  }
88 
89  //we also need to connect the first point in the footprint to the last point
90  //get the cell coord of the last point
91  if(!costmap_.worldToMap(footprint.back().x, footprint.back().y, x0, y0))
92  return -1.0;
93 
94  //get the cell coord of the first point
95  if(!costmap_.worldToMap(footprint.front().x, footprint.front().y, x1, y1))
96  return -1.0;
97 
98  line_cost = lineCost(x0, x1, y0, y1);
99  footprint_cost = std::max(line_cost, footprint_cost);
100 
101  if(line_cost < 0)
102  return -1.0;
103 
104  //if all line costs are legal... then we can return that the footprint is legal
105  return footprint_cost;
106 
107  }
108 
109  //calculate the cost of a ray-traced line
110  double CostmapModel::lineCost(int x0, int x1, int y0, int y1) const {
111  double line_cost = 0.0;
112  double point_cost = -1.0;
113 
114  for( LineIterator line( x0, y0, x1, y1 ); line.isValid(); line.advance() )
115  {
116  point_cost = pointCost( line.getX(), line.getY() ); //Score the current point
117 
118  if(point_cost < 0)
119  return -1;
120 
121  if(line_cost < point_cost)
122  line_cost = point_cost;
123  }
124 
125  return line_cost;
126  }
127 
128  double CostmapModel::pointCost(int x, int y) const {
129  unsigned char cost = costmap_.getCost(x, y);
130  //if the cell is in an obstacle the path is invalid
131  //if(cost == LETHAL_OBSTACLE){
132  if(cost == LETHAL_OBSTACLE || cost == NO_INFORMATION){
133  return -1;
134  }
135 
136  return cost;
137  }
138 
139 };
const costmap_2d::Costmap2D & costmap_
Allows access of costmap obstacle information.
Definition: costmap_model.h:95
double pointCost(int x, int y) const
Checks the cost of a point in the costmap.
unsigned char getCost(unsigned int mx, unsigned int my) const
double lineCost(int x0, int x1, int y0, int y1) const
Rasterizes a line in the costmap grid and checks for collisions.
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid...
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25