point_grid.h
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 *********************************************************************/
37 #ifndef POINT_GRID_H_
38 #define POINT_GRID_H_
39 #include <vector>
40 #include <list>
41 #include <cfloat>
42 #include <geometry_msgs/Point.h>
43 #include <costmap_2d/observation.h>
45 
46 #include <sensor_msgs/PointCloud2.h>
47 
48 namespace base_local_planner {
57  class PointGrid : public WorldModel {
58  public:
69  PointGrid(double width, double height, double resolution, geometry_msgs::Point origin,
70  double max_z, double obstacle_range, double min_separation);
71 
75  virtual ~PointGrid(){}
76 
83  void getPointsInRange(const geometry_msgs::Point& lower_left, const geometry_msgs::Point& upper_right, std::vector< std::list<geometry_msgs::Point32>* >& points);
84 
93  virtual double footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
94  double inscribed_radius, double circumscribed_radius);
95 
97 
104  void updateWorld(const std::vector<geometry_msgs::Point>& footprint,
105  const std::vector<costmap_2d::Observation>& observations, const std::vector<PlanarLaserScan>& laser_scans);
106 
114  inline bool gridCoords(geometry_msgs::Point pt, unsigned int& gx, unsigned int& gy) const {
115  if(pt.x < origin_.x || pt.y < origin_.y){
116  gx = 0;
117  gy = 0;
118  return false;
119  }
120  gx = (int) ((pt.x - origin_.x)/resolution_);
121  gy = (int) ((pt.y - origin_.y)/resolution_);
122 
123  if(gx >= width_ || gy >= height_){
124  gx = 0;
125  gy = 0;
126  return false;
127  }
128 
129  return true;
130  }
131 
139  inline void getCellBounds(unsigned int gx, unsigned int gy, geometry_msgs::Point& lower_left, geometry_msgs::Point& upper_right) const {
140  lower_left.x = gx * resolution_ + origin_.x;
141  lower_left.y = gy * resolution_ + origin_.y;
142 
143  upper_right.x = lower_left.x + resolution_;
144  upper_right.y = lower_left.y + resolution_;
145  }
146 
147 
154  inline double sq_distance(const geometry_msgs::Point32& pt1, const geometry_msgs::Point32& pt2){
155  return (pt1.x - pt2.x) * (pt1.x - pt2.x) + (pt1.y - pt2.y) * (pt1.y - pt2.y);
156  }
157 
165  inline bool gridCoords(const geometry_msgs::Point32& pt, unsigned int& gx, unsigned int& gy) const {
166  if(pt.x < origin_.x || pt.y < origin_.y){
167  gx = 0;
168  gy = 0;
169  return false;
170  }
171  gx = (int) ((pt.x - origin_.x)/resolution_);
172  gy = (int) ((pt.y - origin_.y)/resolution_);
173 
174  if(gx >= width_ || gy >= height_){
175  gx = 0;
176  gy = 0;
177  return false;
178  }
179 
180  return true;
181  }
182 
189  inline unsigned int gridIndex(unsigned int gx, unsigned int gy) const {
190  /*
191  * (0, 0) ---------------------- (width, 0)
192  * | |
193  * | |
194  * | |
195  * | |
196  * | |
197  * (0, height) ----------------- (width, height)
198  */
199  return(gx + gy * width_);
200  }
201 
209  inline double orient(const geometry_msgs::Point& a, const geometry_msgs::Point& b, const geometry_msgs::Point32& c){
210  double acx = a.x - c.x;
211  double bcx = b.x - c.x;
212  double acy = a.y - c.y;
213  double bcy = b.y - c.y;
214  return acx * bcy - acy * bcx;
215  }
216 
224  template<typename T>
225  inline double orient(const T& a, const T& b, const T& c){
226  double acx = a.x - c.x;
227  double bcx = b.x - c.x;
228  double acy = a.y - c.y;
229  double bcy = b.y - c.y;
230  return acx * bcy - acy * bcx;
231  }
232 
241  inline bool segIntersect(const geometry_msgs::Point32& v1, const geometry_msgs::Point32& v2,
242  const geometry_msgs::Point32& u1, const geometry_msgs::Point32& u2){
243  return (orient(v1, v2, u1) * orient(v1, v2, u2) < 0) && (orient(u1, u2, v1) * orient(u1, u2, v2) < 0);
244  }
245 
254  void intersectionPoint(const geometry_msgs::Point& v1, const geometry_msgs::Point& v2,
255  const geometry_msgs::Point& u1, const geometry_msgs::Point& u2,
256  geometry_msgs::Point& result);
257 
264  bool ptInPolygon(const geometry_msgs::Point32& pt, const std::vector<geometry_msgs::Point>& poly);
265 
270  void insert(const geometry_msgs::Point32& pt);
271 
277  double nearestNeighborDistance(const geometry_msgs::Point32& pt);
278 
286  double getNearestInCell(const geometry_msgs::Point32& pt, unsigned int gx, unsigned int gy);
287 
292  void removePointsInPolygon(const std::vector<geometry_msgs::Point> poly);
293 
298  void removePointsInScanBoundry(const PlanarLaserScan& laser_scan);
299 
306  bool ptInScan(const geometry_msgs::Point32& pt, const PlanarLaserScan& laser_scan);
307 
312  void getPoints(sensor_msgs::PointCloud2& cloud);
313 
314  private:
315  double resolution_;
316  geometry_msgs::Point origin_;
317  unsigned int width_;
318  unsigned int height_;
319  std::vector< std::list<geometry_msgs::Point32> > cells_;
320  double max_z_;
321  double sq_obstacle_range_;
322  double sq_min_separation_;
323  std::vector< std::list<geometry_msgs::Point32>* > points_;
324  };
325 };
326 #endif
base_local_planner::PointGrid::~PointGrid
virtual ~PointGrid()
Destructor for a point grid.
Definition: point_grid.h:110
base_local_planner::PointGrid::getNearestInCell
double getNearestInCell(const geometry_msgs::Point32 &pt, unsigned int gx, unsigned int gy)
Find the distance between a point and its nearest neighbor in a cell.
Definition: point_grid.cpp:231
base_local_planner::WorldModel::footprintCost
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
base_local_planner::PointGrid::ptInPolygon
bool ptInPolygon(const geometry_msgs::Point32 &pt, const std::vector< geometry_msgs::Point > &poly)
Check if a point is in a polygon.
Definition: point_grid.cpp:118
base_local_planner::PointGrid::sq_min_separation_
double sq_min_separation_
The minimum square distance required between points in the grid.
Definition: point_grid.h:357
base_local_planner::PointGrid::segIntersect
bool segIntersect(const geometry_msgs::Point32 &v1, const geometry_msgs::Point32 &v2, const geometry_msgs::Point32 &u1, const geometry_msgs::Point32 &u2)
Check if two line segmenst intersect.
Definition: point_grid.h:276
observation.h
base_local_planner::PlanarLaserScan
Stores a scan from a planar laser that can be used to clear freespace.
Definition: planar_laser_scan.h:83
base_local_planner::PointGrid::getPointsInRange
void getPointsInRange(const geometry_msgs::Point &lower_left, const geometry_msgs::Point &upper_right, std::vector< std::list< geometry_msgs::Point32 > * > &points)
Returns the points that lie within the cells contained in the specified range. Some of these points m...
Definition: point_grid.cpp:154
base_local_planner::PointGrid::gridIndex
unsigned int gridIndex(unsigned int gx, unsigned int gy) const
Converts cell coordinates to an index value that can be used to look up the correct grid cell.
Definition: point_grid.h:224
base_local_planner::PointGrid::sq_obstacle_range_
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
Definition: point_grid.h:356
base_local_planner::PointGrid::PointGrid
PointGrid(double width, double height, double resolution, geometry_msgs::Point origin, double max_z, double obstacle_range, double min_separation)
Constuctor for a grid that stores points in the plane.
Definition: point_grid.cpp:53
base_local_planner::PointGrid::cells_
std::vector< std::list< geometry_msgs::Point32 > > cells_
Storage for the cells in the grid.
Definition: point_grid.h:354
base_local_planner::PointGrid::updateWorld
void updateWorld(const std::vector< geometry_msgs::Point > &footprint, const std::vector< costmap_2d::Observation > &observations, const std::vector< PlanarLaserScan > &laser_scans)
Inserts observations from sensors into the point grid.
Definition: point_grid.cpp:335
base_local_planner::PointGrid::height_
unsigned int height_
The height of the grid in cells.
Definition: point_grid.h:353
base_local_planner::PointGrid::width_
unsigned int width_
The width of the grid in cells.
Definition: point_grid.h:352
base_local_planner::PointGrid::intersectionPoint
void intersectionPoint(const geometry_msgs::Point &v1, const geometry_msgs::Point &v2, const geometry_msgs::Point &u1, const geometry_msgs::Point &u2, geometry_msgs::Point &result)
Find the intersection point of two lines.
Definition: point_grid.cpp:534
base_local_planner::PointGrid::removePointsInScanBoundry
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan)
Removes points from the grid that lie within a laser scan.
Definition: point_grid.cpp:378
base_local_planner::PointGrid::insert
void insert(const geometry_msgs::Point32 &pt)
Insert a point into the point grid.
Definition: point_grid.cpp:211
base_local_planner::PointGrid::footprintCost
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
Checks if any points in the grid lie inside a convex footprint.
Definition: point_grid.cpp:61
base_local_planner::PointGrid::sq_distance
double sq_distance(const geometry_msgs::Point32 &pt1, const geometry_msgs::Point32 &pt2)
Compute the squared distance between two points.
Definition: point_grid.h:189
base_local_planner::PointGrid::max_z_
double max_z_
The height cutoff for adding points as obstacles.
Definition: point_grid.h:355
base_local_planner::PointGrid::ptInScan
bool ptInScan(const geometry_msgs::Point32 &pt, const PlanarLaserScan &laser_scan)
Checks to see if a point is within a laser scan specification.
Definition: point_grid.cpp:421
base_local_planner::PointGrid::resolution_
double resolution_
The resolution of the grid in meters/cell.
Definition: point_grid.h:350
base_local_planner::PointGrid::origin_
geometry_msgs::Point origin_
The origin point of the grid.
Definition: point_grid.h:351
base_local_planner::PointGrid::nearestNeighborDistance
double nearestNeighborDistance(const geometry_msgs::Point32 &pt)
Find the distance between a point and its nearest neighbor in the grid.
Definition: point_grid.cpp:242
base_local_planner::PointGrid::getCellBounds
void getCellBounds(unsigned int gx, unsigned int gy, geometry_msgs::Point &lower_left, geometry_msgs::Point &upper_right) const
Get the bounds in world coordinates of a cell in the point grid, assumes a legal cell when called.
Definition: point_grid.h:174
base_local_planner
Definition: costmap_model.h:44
base_local_planner::PointGrid::orient
double orient(const geometry_msgs::Point &a, const geometry_msgs::Point &b, const geometry_msgs::Point32 &c)
Check the orientation of a pt c with respect to the vector a->b.
Definition: point_grid.h:244
base_local_planner::PointGrid::getPoints
void getPoints(sensor_msgs::PointCloud2 &cloud)
Get the points in the point grid.
Definition: point_grid.cpp:465
base_local_planner::PointGrid::points_
std::vector< std::list< geometry_msgs::Point32 > * > points_
The lists of points returned by a range search, made a member to save on memory allocation.
Definition: point_grid.h:358
base_local_planner::PointGrid::gridCoords
bool gridCoords(geometry_msgs::Point pt, unsigned int &gx, unsigned int &gy) const
Convert from world coordinates to grid coordinates.
Definition: point_grid.h:149
base_local_planner::PointGrid::removePointsInPolygon
void removePointsInPolygon(const std::vector< geometry_msgs::Point > poly)
Removes points from the grid that lie within the polygon.
Definition: point_grid.cpp:490
world_model.h


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24