point_grid.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 *********************************************************************/
37 
39 #include <ros/console.h>
40 #ifdef HAVE_SYS_TIME_H
41 #include <sys/time.h>
42 #endif
43 
44 #include <math.h>
45 #include <cstdio>
47 
48 using namespace std;
49 using namespace costmap_2d;
50 
51 namespace base_local_planner {
52 
53 PointGrid::PointGrid(double size_x, double size_y, double resolution, geometry_msgs::Point origin, double max_z, double obstacle_range, double min_seperation) :
54  resolution_(resolution), origin_(origin), max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range), sq_min_separation_(min_seperation * min_seperation)
55  {
56  width_ = (int) (size_x / resolution_);
57  height_ = (int) (size_y / resolution_);
58  cells_.resize(width_ * height_);
59  }
60 
61  double PointGrid::footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
62  double inscribed_radius, double circumscribed_radius){
63  //the half-width of the circumscribed sqaure of the robot is equal to the circumscribed radius
64  double outer_square_radius = circumscribed_radius;
65 
66  //get all the points inside the circumscribed square of the robot footprint
67  geometry_msgs::Point c_lower_left, c_upper_right;
68  c_lower_left.x = position.x - outer_square_radius;
69  c_lower_left.y = position.y - outer_square_radius;
70 
71  c_upper_right.x = position.x + outer_square_radius;
72  c_upper_right.y = position.y + outer_square_radius;
73 
74  //This may return points that are still outside of the cirumscribed square because it returns the cells
75  //contained by the range
76  getPointsInRange(c_lower_left, c_upper_right, points_);
77 
78  //if there are no points in the circumscribed square... we don't have to check against the footprint
79  if(points_.empty())
80  return 1.0;
81 
82  //compute the half-width of the inner square from the inscribed radius of the robot
83  double inner_square_radius = sqrt((inscribed_radius * inscribed_radius) / 2.0);
84 
85  //we'll also check against the inscribed square
86  geometry_msgs::Point i_lower_left, i_upper_right;
87  i_lower_left.x = position.x - inner_square_radius;
88  i_lower_left.y = position.y - inner_square_radius;
89 
90  i_upper_right.x = position.x + inner_square_radius;
91  i_upper_right.y = position.y + inner_square_radius;
92 
93  //if there are points, we have to do a more expensive check
94  for(unsigned int i = 0; i < points_.size(); ++i){
95  list<geometry_msgs::Point32>* cell_points = points_[i];
96  if(cell_points != NULL){
97  for(list<geometry_msgs::Point32>::iterator it = cell_points->begin(); it != cell_points->end(); ++it){
98  const geometry_msgs::Point32& pt = *it;
99  //first, we'll check to make sure we're in the outer square
100  //printf("(%.2f, %.2f) ... l(%.2f, %.2f) ... u(%.2f, %.2f)\n", pt.x, pt.y, c_lower_left.x, c_lower_left.y, c_upper_right.x, c_upper_right.y);
101  if(pt.x > c_lower_left.x && pt.x < c_upper_right.x && pt.y > c_lower_left.y && pt.y < c_upper_right.y){
102  //do a quick check to see if the point lies in the inner square of the robot
103  if(pt.x > i_lower_left.x && pt.x < i_upper_right.x && pt.y > i_lower_left.y && pt.y < i_upper_right.y)
104  return -1.0;
105 
106  //now we really have to do a full footprint check on the point
107  if(ptInPolygon(pt, footprint))
108  return -1.0;
109  }
110  }
111  }
112  }
113 
114  //if we get through all the points and none of them are in the footprint it's legal
115  return 1.0;
116  }
117 
118  bool PointGrid::ptInPolygon(const geometry_msgs::Point32& pt, const std::vector<geometry_msgs::Point>& poly){
119  if(poly.size() < 3)
120  return false;
121 
122  //a point is in a polygon iff the orientation of the point
123  //with respect to sides of the polygon is the same for every
124  //side of the polygon
125  bool all_left = false;
126  bool all_right = false;
127  for(unsigned int i = 0; i < poly.size() - 1; ++i){
128  //if pt left of a->b
129  if(orient(poly[i], poly[i + 1], pt) > 0){
130  if(all_right)
131  return false;
132  all_left = true;
133  }
134  //if pt right of a->b
135  else{
136  if(all_left)
137  return false;
138  all_right = true;
139  }
140  }
141  //also need to check the last point with the first point
142  if(orient(poly[poly.size() - 1], poly[0], pt) > 0){
143  if(all_right)
144  return false;
145  }
146  else{
147  if(all_left)
148  return false;
149  }
150 
151  return true;
152  }
153 
154  void PointGrid::getPointsInRange(const geometry_msgs::Point& lower_left, const geometry_msgs::Point& upper_right,
155  vector< list<geometry_msgs::Point32>* >& points){
156  points.clear();
157 
158  //compute the other corners of the box so we can get cells indicies for them
159  geometry_msgs::Point upper_left, lower_right;
160  upper_left.x = lower_left.x;
161  upper_left.y = upper_right.y;
162  lower_right.x = upper_right.x;
163  lower_right.y = lower_left.y;
164 
165  //get the grid coordinates of the cells matching the corners of the range
166  unsigned int gx, gy;
167 
168  //if the grid coordinates are outside the bounds of the grid... return
169  if(!gridCoords(lower_left, gx, gy))
170  return;
171  //get the associated index
172  unsigned int lower_left_index = gridIndex(gx, gy);
173 
174  if(!gridCoords(lower_right, gx, gy))
175  return;
176  unsigned int lower_right_index = gridIndex(gx, gy);
177 
178  if(!gridCoords(upper_left, gx, gy))
179  return;
180  unsigned int upper_left_index = gridIndex(gx, gy);
181 
182  //compute x_steps and y_steps
183  unsigned int x_steps = lower_right_index - lower_left_index + 1;
184  unsigned int y_steps = (upper_left_index - lower_left_index) / width_ + 1;
185  /*
186  * (0, 0) ---------------------- (width, 0)
187  * | |
188  * | |
189  * | |
190  * | |
191  * | |
192  * (0, height) ----------------- (width, height)
193  */
194  //get an iterator
195  vector< list<geometry_msgs::Point32> >::iterator cell_iterator = cells_.begin() + lower_left_index;
196  //printf("Index: %d, Width: %d, x_steps: %d, y_steps: %d\n", lower_left_index, width_, x_steps, y_steps);
197  for(unsigned int i = 0; i < y_steps; ++i){
198  for(unsigned int j = 0; j < x_steps; ++j){
199  list<geometry_msgs::Point32>& cell = *cell_iterator;
200  //if the cell contains any points... we need to push them back to our list
201  if(!cell.empty()){
202  points.push_back(&cell);
203  }
204  if(j < x_steps - 1)
205  cell_iterator++; //move a cell in the x direction
206  }
207  cell_iterator += width_ - (x_steps - 1); //move down a row
208  }
209  }
210 
211  void PointGrid::insert(const geometry_msgs::Point32& pt){
212  //get the grid coordinates of the point
213  unsigned int gx, gy;
214 
215  //if the grid coordinates are outside the bounds of the grid... return
216  if(!gridCoords(pt, gx, gy))
217  return;
218 
219  //if the point is too close to its nearest neighbor... return
221  return;
222 
223  //get the associated index
224  unsigned int pt_index = gridIndex(gx, gy);
225 
226  //insert the point into the grid at the correct location
227  cells_[pt_index].push_back(pt);
228  //printf("Index: %d, size: %d\n", pt_index, cells_[pt_index].size());
229  }
230 
231  double PointGrid::getNearestInCell(const geometry_msgs::Point32& pt, unsigned int gx, unsigned int gy){
232  unsigned int index = gridIndex(gx, gy);
233  double min_sq_dist = DBL_MAX;
234  //loop through the points in the cell and find the minimum distance to the passed point
235  for(list<geometry_msgs::Point32>::const_iterator it = cells_[index].begin(); it != cells_[index].end(); ++it){
236  min_sq_dist = min(min_sq_dist, sq_distance(pt, *it));
237  }
238  return min_sq_dist;
239  }
240 
241 
242  double PointGrid::nearestNeighborDistance(const geometry_msgs::Point32& pt){
243  //get the grid coordinates of the point
244  unsigned int gx, gy;
245 
246  gridCoords(pt, gx, gy);
247 
248  //get the bounds of the grid cell in world coords
249  geometry_msgs::Point lower_left, upper_right;
250  getCellBounds(gx, gy, lower_left, upper_right);
251 
252  //now we need to check what cells could contain the nearest neighbor
253  geometry_msgs::Point32 check_point;
254  double sq_dist = DBL_MAX;
255  double neighbor_sq_dist = DBL_MAX;
256 
257  //left
258  if(gx > 0){
259  check_point.x = lower_left.x;
260  check_point.y = pt.y;
261  sq_dist = sq_distance(pt, check_point);
262  if(sq_dist < sq_min_separation_)
263  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy));
264  }
265 
266  //upper left
267  if(gx > 0 && gy < height_ - 1){
268  check_point.x = lower_left.x;
269  check_point.y = upper_right.y;
270  sq_dist = sq_distance(pt, check_point);
271  if(sq_dist < sq_min_separation_)
272  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy + 1));
273  }
274 
275  //top
276  if(gy < height_ - 1){
277  check_point.x = pt.x;
278  check_point.y = upper_right.y;
279  sq_dist = sq_distance(pt, check_point);
280  if(sq_dist < sq_min_separation_)
281  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy + 1));
282  }
283 
284  //upper right
285  if(gx < width_ - 1 && gy < height_ - 1){
286  check_point.x = upper_right.x;
287  check_point.y = upper_right.y;
288  sq_dist = sq_distance(pt, check_point);
289  if(sq_dist < sq_min_separation_)
290  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy + 1));
291  }
292 
293  //right
294  if(gx < width_ - 1){
295  check_point.x = upper_right.x;
296  check_point.y = pt.y;
297  sq_dist = sq_distance(pt, check_point);
298  if(sq_dist < sq_min_separation_)
299  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy));
300  }
301 
302  //lower right
303  if(gx < width_ - 1 && gy > 0){
304  check_point.x = upper_right.x;
305  check_point.y = lower_left.y;
306  sq_dist = sq_distance(pt, check_point);
307  if(sq_dist < sq_min_separation_)
308  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy - 1));
309  }
310 
311  //bottom
312  if(gy > 0){
313  check_point.x = pt.x;
314  check_point.y = lower_left.y;
315  sq_dist = sq_distance(pt, check_point);
316  if(sq_dist < sq_min_separation_)
317  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy - 1));
318  }
319 
320  //lower left
321  if(gx > 0 && gy > 0){
322  check_point.x = lower_left.x;
323  check_point.y = lower_left.y;
324  sq_dist = sq_distance(pt, check_point);
325  if(sq_dist < sq_min_separation_)
326  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy - 1));
327  }
328 
329  //we must also check within the cell we're in for a nearest neighbor
330  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy));
331 
332  return neighbor_sq_dist;
333  }
334 
335  void PointGrid::updateWorld(const std::vector<geometry_msgs::Point>& footprint,
336  const vector<Observation>& observations, const vector<PlanarLaserScan>& laser_scans){
337  //for our 2D point grid we only remove freespace based on the first laser scan
338  if(laser_scans.empty())
339  return;
340 
341  removePointsInScanBoundry(laser_scans[0]);
342 
343  //iterate through all observations and update the grid
344  for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
345  const Observation& obs = *it;
346  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
347 
351 
352  geometry_msgs::Point32 pt;
353  for(; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z){
354  //filter out points that are too high
355  if(*iter_z > max_z_)
356  continue;
357 
358  //compute the squared distance from the hitpoint to the pointcloud's origin
359  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x)
360  + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y)
361  + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
362 
363  if(sq_dist >= sq_obstacle_range_)
364  continue;
365 
366  //insert the point
367  pt.x = *iter_x;
368  pt.y = *iter_y;
369  pt.z = *iter_z;
370  insert(pt);
371  }
372  }
373 
374  //remove the points that are in the footprint of the robot
375  removePointsInPolygon(footprint);
376  }
377 
379  if(laser_scan.cloud.points.size() == 0)
380  return;
381 
382  //compute the containing square of the scan
383  geometry_msgs::Point lower_left, upper_right;
384  lower_left.x = laser_scan.origin.x;
385  lower_left.y = laser_scan.origin.y;
386  upper_right.x = laser_scan.origin.x;
387  upper_right.y = laser_scan.origin.y;
388 
389  for(unsigned int i = 0; i < laser_scan.cloud.points.size(); ++i){
390  lower_left.x = min((double)lower_left.x, (double)laser_scan.cloud.points[i].x);
391  lower_left.y = min((double)lower_left.y, (double)laser_scan.cloud.points[i].y);
392  upper_right.x = max((double)upper_right.x, (double)laser_scan.cloud.points[i].x);
393  upper_right.y = max((double)upper_right.y, (double)laser_scan.cloud.points[i].y);
394  }
395 
396  getPointsInRange(lower_left, upper_right, points_);
397 
398  //if there are no points in the containing square... we don't have to do anything
399  if(points_.empty())
400  return;
401 
402  //if there are points, we have to check them against the scan explicitly to remove them
403  for(unsigned int i = 0; i < points_.size(); ++i){
404  list<geometry_msgs::Point32>* cell_points = points_[i];
405  if(cell_points != NULL){
406  list<geometry_msgs::Point32>::iterator it = cell_points->begin();
407  while(it != cell_points->end()){
408  const geometry_msgs::Point32& pt = *it;
409 
410  //check if the point is in the polygon and if it is, erase it from the grid
411  if(ptInScan(pt, laser_scan)){
412  it = cell_points->erase(it);
413  }
414  else
415  it++;
416  }
417  }
418  }
419  }
420 
421  bool PointGrid::ptInScan(const geometry_msgs::Point32& pt, const PlanarLaserScan& laser_scan){
422  if(!laser_scan.cloud.points.empty()){
423  //compute the angle of the point relative to that of the scan
424  double v1_x = laser_scan.cloud.points[0].x - laser_scan.origin.x;
425  double v1_y = laser_scan.cloud.points[0].y - laser_scan.origin.y;
426  double v2_x = pt.x - laser_scan.origin.x;
427  double v2_y = pt.y - laser_scan.origin.y;
428 
429  double perp_dot = v1_x * v2_y - v1_y * v2_x;
430  double dot = v1_x * v2_x + v1_y * v2_y;
431 
432  //get the signed angle
433  double vector_angle = atan2(perp_dot, dot);
434 
435  //we want all angles to be between 0 and 2PI
436  if(vector_angle < 0)
437  vector_angle = 2 * M_PI + vector_angle;
438 
439  double total_rads = laser_scan.angle_max - laser_scan.angle_min;
440 
441  //if this point lies outside of the scan field of view... it is not in the scan
442  if(vector_angle < 0 || vector_angle >= total_rads)
443  return false;
444 
445  //compute the index of the point in the scan
446  unsigned int index = (unsigned int) (vector_angle / laser_scan.angle_increment);
447 
448  //make sure we have a legal index... we always should at this point, but just in case
449  if(index >= laser_scan.cloud.points.size() - 1){
450  return false;
451  }
452 
453  //if the point lies to the left of the line between the two scan points bounding it, it is within the scan
454  if(orient(laser_scan.cloud.points[index], laser_scan.cloud.points[index + 1], pt) > 0){
455  return true;
456  }
457 
458  //otherwise it is not
459  return false;
460  }
461  else
462  return false;
463  }
464 
465  void PointGrid::getPoints(sensor_msgs::PointCloud2& cloud){
466  sensor_msgs::PointCloud2Modifier modifier(cloud);
467  modifier.setPointCloud2FieldsByString(1, "xyz");
468 
469  size_t n = 0;
470  for(unsigned int i = 0; i < cells_.size(); ++i){
471  for(list<geometry_msgs::Point32>::iterator it = cells_[i].begin(); it != cells_[i].end(); ++it){
472  ++n;
473  }
474  }
475  modifier.resize(n);
476 
477  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
478  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
479  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
480 
481  for(unsigned int i = 0; i < cells_.size(); ++i){
482  for(list<geometry_msgs::Point32>::iterator it = cells_[i].begin(); it != cells_[i].end(); ++it, ++iter_x, ++iter_y, ++iter_z){
483  *iter_x = it->x;
484  *iter_y = it->y;
485  *iter_z = it->z;
486  }
487  }
488  }
489 
490  void PointGrid::removePointsInPolygon(const std::vector<geometry_msgs::Point> poly){
491  if(poly.size() == 0)
492  return;
493 
494  geometry_msgs::Point lower_left, upper_right;
495  lower_left.x = poly[0].x;
496  lower_left.y = poly[0].y;
497  upper_right.x = poly[0].x;
498  upper_right.y = poly[0].y;
499 
500  //compute the containing square of the polygon
501  for(unsigned int i = 1; i < poly.size(); ++i){
502  lower_left.x = min(lower_left.x, poly[i].x);
503  lower_left.y = min(lower_left.y, poly[i].y);
504  upper_right.x = max(upper_right.x, poly[i].x);
505  upper_right.y = max(upper_right.y, poly[i].y);
506  }
507 
508  ROS_DEBUG("Lower: (%.2f, %.2f), Upper: (%.2f, %.2f)\n", lower_left.x, lower_left.y, upper_right.x, upper_right.y);
509  getPointsInRange(lower_left, upper_right, points_);
510 
511  //if there are no points in the containing square... we don't have to do anything
512  if(points_.empty())
513  return;
514 
515  //if there are points, we have to check them against the polygon explicitly to remove them
516  for(unsigned int i = 0; i < points_.size(); ++i){
517  list<geometry_msgs::Point32>* cell_points = points_[i];
518  if(cell_points != NULL){
519  list<geometry_msgs::Point32>::iterator it = cell_points->begin();
520  while(it != cell_points->end()){
521  const geometry_msgs::Point32& pt = *it;
522 
523  //check if the point is in the polygon and if it is, erase it from the grid
524  if(ptInPolygon(pt, poly)){
525  it = cell_points->erase(it);
526  }
527  else
528  it++;
529  }
530  }
531  }
532  }
533 
534  void PointGrid::intersectionPoint(const geometry_msgs::Point& v1, const geometry_msgs::Point& v2,
535  const geometry_msgs::Point& u1, const geometry_msgs::Point& u2, geometry_msgs::Point& result){
536  //generate the equation for line 1
537  double a1 = v2.y - v1.y;
538  double b1 = v1.x - v2.x;
539  double c1 = a1 * v1.x + b1 * v1.y;
540 
541  //generate the equation for line 2
542  double a2 = u2.y - u1.y;
543  double b2 = u1.x - u2.x;
544  double c2 = a2 * u1.x + b2 * u1.y;
545 
546  double det = a1 * b2 - a2 * b1;
547 
548  //the lines are parallel
549  if(det == 0)
550  return;
551 
552  result.x = (b2 * c1 - b1 * c2) / det;
553  result.y = (a1 * c2 - a2 * c1) / det;
554  }
555 
556 };
geometry_msgs::Point origin_
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:139
void getPoints(sensor_msgs::PointCloud2 &cloud)
Get the points in the point grid.
Definition: point_grid.cpp:465
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
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
double resolution_
The resolution of the grid in meters/cell.
Definition: point_grid.h:315
bool gridCoords(geometry_msgs::Point pt, unsigned int &gx, unsigned int &gy) const
Convert from world coordinates to grid coordinates.
Definition: point_grid.h:114
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:323
unsigned int width_
The width of the grid in cells.
Definition: point_grid.h:317
double sq_min_separation_
The minimum square distance required between points in the grid.
Definition: point_grid.h:322
std::vector< std::list< geometry_msgs::Point32 > > cells_
Storage for the cells in the grid.
Definition: point_grid.h:319
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
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
Definition: point_grid.h:321
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
void insert(const geometry_msgs::Point32 &pt)
Insert a point into the point grid.
Definition: point_grid.cpp:211
#define DBL_MAX
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan)
Removes points from the grid that lie within a laser scan.
Definition: point_grid.cpp:378
double sq_distance(const geometry_msgs::Point32 &pt1, const geometry_msgs::Point32 &pt2)
Compute the squared distance between two points.
Definition: point_grid.h:154
double min(double a, double b)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
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
unsigned int height_
The height of the grid in cells.
Definition: point_grid.h:318
void removePointsInPolygon(const std::vector< geometry_msgs::Point > poly)
Removes points from the grid that lie within the polygon.
Definition: point_grid.cpp:490
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:209
sensor_msgs::PointCloud2 * cloud_
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:189
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
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
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
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
Stores a scan from a planar laser that can be used to clear freespace.
void setPointCloud2FieldsByString(int n_fields,...)
double max(double a, double b)
double max_z_
The height cutoff for adding points as obstacles.
Definition: point_grid.h:320
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
#define ROS_DEBUG(...)


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:08