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 #include <sys/time.h>
41 #include <math.h>
42 #include <cstdio>
43 
44 using namespace std;
45 using namespace costmap_2d;
46 
47 void printPoint(pcl::PointXYZ pt){
48  printf("(%.2f, %.2f, %.2f)", pt.x, pt.y, pt.z);
49 }
50 
52  printf("%%!PS\n");
53  printf("%%%%Creator: Eitan Marder-Eppstein (Willow Garage)\n");
54  printf("%%%%EndComments\n");
55 }
56 
58  printf("showpage\n%%%%EOF\n");
59 }
60 
61 void printPolygonPS(const std::vector<geometry_msgs::Point>& poly, double line_width){
62  if(poly.size() < 2)
63  return;
64 
65  printf("%.2f setlinewidth\n", line_width);
66  printf("newpath\n");
67  printf("%.4f\t%.4f\tmoveto\n", poly[0].x * 10, poly[0].y * 10);
68  for(unsigned int i = 1; i < poly.size(); ++i)
69  printf("%.4f\t%.4f\tlineto\n", poly[i].x * 10, poly[i].y * 10);
70  printf("%.4f\t%.4f\tlineto\n", poly[0].x * 10, poly[0].y * 10);
71  printf("closepath stroke\n");
72 
73 }
74 
75 namespace base_local_planner {
76 
77 PointGrid::PointGrid(double size_x, double size_y, double resolution, geometry_msgs::Point origin, double max_z, double obstacle_range, double min_seperation) :
78  resolution_(resolution), origin_(origin), max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range), sq_min_separation_(min_seperation * min_seperation)
79  {
80  width_ = (int) (size_x / resolution_);
81  height_ = (int) (size_y / resolution_);
82  cells_.resize(width_ * height_);
83  }
84 
85  double PointGrid::footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
86  double inscribed_radius, double circumscribed_radius){
87  //the half-width of the circumscribed sqaure of the robot is equal to the circumscribed radius
88  double outer_square_radius = circumscribed_radius;
89 
90  //get all the points inside the circumscribed square of the robot footprint
91  geometry_msgs::Point c_lower_left, c_upper_right;
92  c_lower_left.x = position.x - outer_square_radius;
93  c_lower_left.y = position.y - outer_square_radius;
94 
95  c_upper_right.x = position.x + outer_square_radius;
96  c_upper_right.y = position.y + outer_square_radius;
97 
98  //This may return points that are still outside of the cirumscribed square because it returns the cells
99  //contained by the range
100  getPointsInRange(c_lower_left, c_upper_right, points_);
101 
102  //if there are no points in the circumscribed square... we don't have to check against the footprint
103  if(points_.empty())
104  return 1.0;
105 
106  //compute the half-width of the inner square from the inscribed radius of the robot
107  double inner_square_radius = sqrt((inscribed_radius * inscribed_radius) / 2.0);
108 
109  //we'll also check against the inscribed square
110  geometry_msgs::Point i_lower_left, i_upper_right;
111  i_lower_left.x = position.x - inner_square_radius;
112  i_lower_left.y = position.y - inner_square_radius;
113 
114  i_upper_right.x = position.x + inner_square_radius;
115  i_upper_right.y = position.y + inner_square_radius;
116 
117  //if there are points, we have to do a more expensive check
118  for(unsigned int i = 0; i < points_.size(); ++i){
119  list<pcl::PointXYZ>* cell_points = points_[i];
120  if(cell_points != NULL){
121  for(list<pcl::PointXYZ>::iterator it = cell_points->begin(); it != cell_points->end(); ++it){
122  const pcl::PointXYZ& pt = *it;
123  //first, we'll check to make sure we're in the outer square
124  //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);
125  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){
126  //do a quick check to see if the point lies in the inner square of the robot
127  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)
128  return -1.0;
129 
130  //now we really have to do a full footprint check on the point
131  if(ptInPolygon(pt, footprint))
132  return -1.0;
133  }
134  }
135  }
136  }
137 
138  //if we get through all the points and none of them are in the footprint it's legal
139  return 1.0;
140  }
141 
142  bool PointGrid::ptInPolygon(const pcl::PointXYZ& pt, const std::vector<geometry_msgs::Point>& poly){
143  if(poly.size() < 3)
144  return false;
145 
146  //a point is in a polygon iff the orientation of the point
147  //with respect to sides of the polygon is the same for every
148  //side of the polygon
149  bool all_left = false;
150  bool all_right = false;
151  for(unsigned int i = 0; i < poly.size() - 1; ++i){
152  //if pt left of a->b
153  if(orient(poly[i], poly[i + 1], pt) > 0){
154  if(all_right)
155  return false;
156  all_left = true;
157  }
158  //if pt right of a->b
159  else{
160  if(all_left)
161  return false;
162  all_right = true;
163  }
164  }
165  //also need to check the last point with the first point
166  if(orient(poly[poly.size() - 1], poly[0], pt) > 0){
167  if(all_right)
168  return false;
169  }
170  else{
171  if(all_left)
172  return false;
173  }
174 
175  return true;
176  }
177 
178  void PointGrid::getPointsInRange(const geometry_msgs::Point& lower_left, const geometry_msgs::Point& upper_right, vector< list<pcl::PointXYZ>* >& points){
179  points.clear();
180 
181  //compute the other corners of the box so we can get cells indicies for them
182  geometry_msgs::Point upper_left, lower_right;
183  upper_left.x = lower_left.x;
184  upper_left.y = upper_right.y;
185  lower_right.x = upper_right.x;
186  lower_right.y = lower_left.y;
187 
188  //get the grid coordinates of the cells matching the corners of the range
189  unsigned int gx, gy;
190 
191  //if the grid coordinates are outside the bounds of the grid... return
192  if(!gridCoords(lower_left, gx, gy))
193  return;
194  //get the associated index
195  unsigned int lower_left_index = gridIndex(gx, gy);
196 
197  if(!gridCoords(lower_right, gx, gy))
198  return;
199  unsigned int lower_right_index = gridIndex(gx, gy);
200 
201  if(!gridCoords(upper_left, gx, gy))
202  return;
203  unsigned int upper_left_index = gridIndex(gx, gy);
204 
205  //compute x_steps and y_steps
206  unsigned int x_steps = lower_right_index - lower_left_index + 1;
207  unsigned int y_steps = (upper_left_index - lower_left_index) / width_ + 1;
208  /*
209  * (0, 0) ---------------------- (width, 0)
210  * | |
211  * | |
212  * | |
213  * | |
214  * | |
215  * (0, height) ----------------- (width, height)
216  */
217  //get an iterator
218  vector< list<pcl::PointXYZ> >::iterator cell_iterator = cells_.begin() + lower_left_index;
219  //printf("Index: %d, Width: %d, x_steps: %d, y_steps: %d\n", lower_left_index, width_, x_steps, y_steps);
220  for(unsigned int i = 0; i < y_steps; ++i){
221  for(unsigned int j = 0; j < x_steps; ++j){
222  list<pcl::PointXYZ>& cell = *cell_iterator;
223  //if the cell contains any points... we need to push them back to our list
224  if(!cell.empty()){
225  points.push_back(&cell);
226  }
227  if(j < x_steps - 1)
228  cell_iterator++; //move a cell in the x direction
229  }
230  cell_iterator += width_ - (x_steps - 1); //move down a row
231  }
232  }
233 
234  void PointGrid::insert(pcl::PointXYZ pt){
235  //get the grid coordinates of the point
236  unsigned int gx, gy;
237 
238  //if the grid coordinates are outside the bounds of the grid... return
239  if(!gridCoords(pt, gx, gy))
240  return;
241 
242  //if the point is too close to its nearest neighbor... return
244  return;
245 
246  //get the associated index
247  unsigned int pt_index = gridIndex(gx, gy);
248 
249  //insert the point into the grid at the correct location
250  cells_[pt_index].push_back(pt);
251  //printf("Index: %d, size: %d\n", pt_index, cells_[pt_index].size());
252  }
253 
254  double PointGrid::getNearestInCell(pcl::PointXYZ& pt, unsigned int gx, unsigned int gy){
255  unsigned int index = gridIndex(gx, gy);
256  double min_sq_dist = DBL_MAX;
257  //loop through the points in the cell and find the minimum distance to the passed point
258  for(list<pcl::PointXYZ>::iterator it = cells_[index].begin(); it != cells_[index].end(); ++it){
259  min_sq_dist = min(min_sq_dist, sq_distance(pt, *it));
260  }
261  return min_sq_dist;
262  }
263 
264 
265  double PointGrid::nearestNeighborDistance(pcl::PointXYZ& pt){
266  //get the grid coordinates of the point
267  unsigned int gx, gy;
268 
269  gridCoords(pt, gx, gy);
270 
271  //get the bounds of the grid cell in world coords
272  geometry_msgs::Point lower_left, upper_right;
273  getCellBounds(gx, gy, lower_left, upper_right);
274 
275  //now we need to check what cells could contain the nearest neighbor
276  pcl::PointXYZ check_point;
277  double sq_dist = DBL_MAX;
278  double neighbor_sq_dist = DBL_MAX;
279 
280  //left
281  if(gx > 0){
282  check_point.x = lower_left.x;
283  check_point.y = pt.y;
284  sq_dist = sq_distance(pt, check_point);
285  if(sq_dist < sq_min_separation_)
286  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy));
287  }
288 
289  //upper left
290  if(gx > 0 && gy < height_ - 1){
291  check_point.x = lower_left.x;
292  check_point.y = upper_right.y;
293  sq_dist = sq_distance(pt, check_point);
294  if(sq_dist < sq_min_separation_)
295  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy + 1));
296  }
297 
298  //top
299  if(gy < height_ - 1){
300  check_point.x = pt.x;
301  check_point.y = upper_right.y;
302  sq_dist = sq_distance(pt, check_point);
303  if(sq_dist < sq_min_separation_)
304  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy + 1));
305  }
306 
307  //upper right
308  if(gx < width_ - 1 && gy < height_ - 1){
309  check_point.x = upper_right.x;
310  check_point.y = upper_right.y;
311  sq_dist = sq_distance(pt, check_point);
312  if(sq_dist < sq_min_separation_)
313  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy + 1));
314  }
315 
316  //right
317  if(gx < width_ - 1){
318  check_point.x = upper_right.x;
319  check_point.y = pt.y;
320  sq_dist = sq_distance(pt, check_point);
321  if(sq_dist < sq_min_separation_)
322  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy));
323  }
324 
325  //lower right
326  if(gx < width_ - 1 && gy > 0){
327  check_point.x = upper_right.x;
328  check_point.y = lower_left.y;
329  sq_dist = sq_distance(pt, check_point);
330  if(sq_dist < sq_min_separation_)
331  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy - 1));
332  }
333 
334  //bottom
335  if(gy > 0){
336  check_point.x = pt.x;
337  check_point.y = lower_left.y;
338  sq_dist = sq_distance(pt, check_point);
339  if(sq_dist < sq_min_separation_)
340  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy - 1));
341  }
342 
343  //lower left
344  if(gx > 0 && gy > 0){
345  check_point.x = lower_left.x;
346  check_point.y = lower_left.y;
347  sq_dist = sq_distance(pt, check_point);
348  if(sq_dist < sq_min_separation_)
349  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy - 1));
350  }
351 
352  //we must also check within the cell we're in for a nearest neighbor
353  neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy));
354 
355  return neighbor_sq_dist;
356  }
357 
358  void PointGrid::updateWorld(const std::vector<geometry_msgs::Point>& footprint,
359  const vector<Observation>& observations, const vector<PlanarLaserScan>& laser_scans){
360  //for our 2D point grid we only remove freespace based on the first laser scan
361  if(laser_scans.empty())
362  return;
363 
364  removePointsInScanBoundry(laser_scans[0]);
365 
366  //iterate through all observations and update the grid
367  for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
368  const Observation& obs = *it;
369  const pcl::PointCloud<pcl::PointXYZ>& cloud = *(obs.cloud_);
370  for(unsigned int i = 0; i < cloud.size(); ++i){
371  //filter out points that are too high
372  if(cloud[i].z > max_z_)
373  continue;
374 
375  //compute the squared distance from the hitpoint to the pointcloud's origin
376  double sq_dist = (cloud[i].x - obs.origin_.x) * (cloud[i].x - obs.origin_.x)
377  + (cloud[i].y - obs.origin_.y) * (cloud[i].y - obs.origin_.y)
378  + (cloud[i].z - obs.origin_.z) * (cloud[i].z - obs.origin_.z);
379 
380  if(sq_dist >= sq_obstacle_range_)
381  continue;
382 
383  //insert the point
384  insert(cloud[i]);
385  }
386  }
387 
388  //remove the points that are in the footprint of the robot
389  removePointsInPolygon(footprint);
390  }
391 
393  if(laser_scan.cloud.points.size() == 0)
394  return;
395 
396  //compute the containing square of the scan
397  geometry_msgs::Point lower_left, upper_right;
398  lower_left.x = laser_scan.origin.x;
399  lower_left.y = laser_scan.origin.y;
400  upper_right.x = laser_scan.origin.x;
401  upper_right.y = laser_scan.origin.y;
402 
403  for(unsigned int i = 0; i < laser_scan.cloud.points.size(); ++i){
404  lower_left.x = min((double)lower_left.x, (double)laser_scan.cloud.points[i].x);
405  lower_left.y = min((double)lower_left.y, (double)laser_scan.cloud.points[i].y);
406  upper_right.x = max((double)upper_right.x, (double)laser_scan.cloud.points[i].x);
407  upper_right.y = max((double)upper_right.y, (double)laser_scan.cloud.points[i].y);
408  }
409 
410  getPointsInRange(lower_left, upper_right, points_);
411 
412  //if there are no points in the containing square... we don't have to do anything
413  if(points_.empty())
414  return;
415 
416  //if there are points, we have to check them against the scan explicitly to remove them
417  for(unsigned int i = 0; i < points_.size(); ++i){
418  list<pcl::PointXYZ>* cell_points = points_[i];
419  if(cell_points != NULL){
420  list<pcl::PointXYZ>::iterator it = cell_points->begin();
421  while(it != cell_points->end()){
422  const pcl::PointXYZ& pt = *it;
423 
424  //check if the point is in the polygon and if it is, erase it from the grid
425  if(ptInScan(pt, laser_scan)){
426  it = cell_points->erase(it);
427  }
428  else
429  it++;
430  }
431  }
432  }
433  }
434 
435  bool PointGrid::ptInScan(const pcl::PointXYZ& pt, const PlanarLaserScan& laser_scan){
436  if(!laser_scan.cloud.points.empty()){
437  //compute the angle of the point relative to that of the scan
438  double v1_x = laser_scan.cloud.points[0].x - laser_scan.origin.x;
439  double v1_y = laser_scan.cloud.points[0].y - laser_scan.origin.y;
440  double v2_x = pt.x - laser_scan.origin.x;
441  double v2_y = pt.y - laser_scan.origin.y;
442 
443  double perp_dot = v1_x * v2_y - v1_y * v2_x;
444  double dot = v1_x * v2_x + v1_y * v2_y;
445 
446  //get the signed angle
447  double vector_angle = atan2(perp_dot, dot);
448 
449  //we want all angles to be between 0 and 2PI
450  if(vector_angle < 0)
451  vector_angle = 2 * M_PI + vector_angle;
452 
453  double total_rads = laser_scan.angle_max - laser_scan.angle_min;
454 
455  //if this point lies outside of the scan field of view... it is not in the scan
456  if(vector_angle < 0 || vector_angle >= total_rads)
457  return false;
458 
459  //compute the index of the point in the scan
460  unsigned int index = (unsigned int) (vector_angle / laser_scan.angle_increment);
461 
462  //make sure we have a legal index... we always should at this point, but just in case
463  if(index >= laser_scan.cloud.points.size() - 1){
464  return false;
465  }
466 
467  //if the point lies to the left of the line between the two scan points bounding it, it is within the scan
468  if(orient(laser_scan.cloud.points[index], laser_scan.cloud.points[index + 1], pt) > 0){
469  return true;
470  }
471 
472  //otherwise it is not
473  return false;
474  }
475  else
476  return false;
477  }
478 
479  void PointGrid::getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud){
480  for(unsigned int i = 0; i < cells_.size(); ++i){
481  for(list<pcl::PointXYZ>::iterator it = cells_[i].begin(); it != cells_[i].end(); ++it){
482  cloud.push_back(*it);
483  }
484  }
485  }
486 
487  void PointGrid::removePointsInPolygon(const std::vector<geometry_msgs::Point> poly){
488  if(poly.size() == 0)
489  return;
490 
491  geometry_msgs::Point lower_left, upper_right;
492  lower_left.x = poly[0].x;
493  lower_left.y = poly[0].y;
494  upper_right.x = poly[0].x;
495  upper_right.y = poly[0].y;
496 
497  //compute the containing square of the polygon
498  for(unsigned int i = 1; i < poly.size(); ++i){
499  lower_left.x = min(lower_left.x, poly[i].x);
500  lower_left.y = min(lower_left.y, poly[i].y);
501  upper_right.x = max(upper_right.x, poly[i].x);
502  upper_right.y = max(upper_right.y, poly[i].y);
503  }
504 
505  ROS_DEBUG("Lower: (%.2f, %.2f), Upper: (%.2f, %.2f)\n", lower_left.x, lower_left.y, upper_right.x, upper_right.y);
506  getPointsInRange(lower_left, upper_right, points_);
507 
508  //if there are no points in the containing square... we don't have to do anything
509  if(points_.empty())
510  return;
511 
512  //if there are points, we have to check them against the polygon explicitly to remove them
513  for(unsigned int i = 0; i < points_.size(); ++i){
514  list<pcl::PointXYZ>* cell_points = points_[i];
515  if(cell_points != NULL){
516  list<pcl::PointXYZ>::iterator it = cell_points->begin();
517  while(it != cell_points->end()){
518  const pcl::PointXYZ& pt = *it;
519 
520  //check if the point is in the polygon and if it is, erase it from the grid
521  if(ptInPolygon(pt, poly)){
522  it = cell_points->erase(it);
523  }
524  else
525  it++;
526  }
527  }
528  }
529  }
530 
531  void PointGrid::intersectionPoint(const geometry_msgs::Point& v1, const geometry_msgs::Point& v2,
532  const geometry_msgs::Point& u1, const geometry_msgs::Point& u2, geometry_msgs::Point& result){
533  //generate the equation for line 1
534  double a1 = v2.y - v1.y;
535  double b1 = v1.x - v2.x;
536  double c1 = a1 * v1.x + b1 * v1.y;
537 
538  //generate the equation for line 2
539  double a2 = u2.y - u1.y;
540  double b2 = u1.x - u2.x;
541  double c2 = a2 * u1.x + b2 * u1.y;
542 
543  double det = a1 * b2 - a2 * b1;
544 
545  //the lines are parallel
546  if(det == 0)
547  return;
548 
549  result.x = (b2 * c1 - b1 * c2) / det;
550  result.y = (a1 * c2 - a2 * c1) / det;
551  }
552 
553 };
554 
555 
556 using namespace base_local_planner;
557 
558 int main(int argc, char** argv){
559  geometry_msgs::Point origin;
560  origin.x = 0.0;
561  origin.y = 0.0;
562  PointGrid pg(50.0, 50.0, 0.2, origin, 2.0, 3.0, 0.0);
563  /*
564  double x = 10.0;
565  double y = 10.0;
566  for(int i = 0; i < 100; ++i){
567  for(int j = 0; j < 100; ++j){
568  pcl::PointXYZ pt;
569  pt.x = x;
570  pt.y = y;
571  pt.z = 1.0;
572  pg.insert(pt);
573  x += .03;
574  }
575  y += .03;
576  x = 10.0;
577  }
578  */
579  std::vector<geometry_msgs::Point> footprint, footprint2, footprint3;
580  geometry_msgs::Point pt;
581 
582  pt.x = 1.0;
583  pt.y = 1.0;
584  footprint.push_back(pt);
585 
586  pt.x = 1.0;
587  pt.y = 1.65;
588  footprint.push_back(pt);
589 
590  pt.x = 1.325;
591  pt.y = 1.75;
592  footprint.push_back(pt);
593 
594  pt.x = 1.65;
595  pt.y = 1.65;
596  footprint.push_back(pt);
597 
598  pt.x = 1.65;
599  pt.y = 1.0;
600  footprint.push_back(pt);
601 
602  pt.x = 1.325;
603  pt.y = 1.00;
604  footprint2.push_back(pt);
605 
606  pt.x = 1.325;
607  pt.y = 1.75;
608  footprint2.push_back(pt);
609 
610  pt.x = 1.65;
611  pt.y = 1.75;
612  footprint2.push_back(pt);
613 
614  pt.x = 1.65;
615  pt.y = 1.00;
616  footprint2.push_back(pt);
617 
618  pt.x = 0.99;
619  pt.y = 0.99;
620  footprint3.push_back(pt);
621 
622  pt.x = 0.99;
623  pt.y = 1.66;
624  footprint3.push_back(pt);
625 
626  pt.x = 1.3255;
627  pt.y = 1.85;
628  footprint3.push_back(pt);
629 
630  pt.x = 1.66;
631  pt.y = 1.66;
632  footprint3.push_back(pt);
633 
634  pt.x = 1.66;
635  pt.y = 0.99;
636  footprint3.push_back(pt);
637 
638  pt.x = 1.325;
639  pt.y = 1.325;
640 
641  pcl::PointXYZ point;
642  point.x = 1.2;
643  point.y = 1.2;
644  point.z = 1.0;
645 
646  struct timeval start, end;
647  double start_t, end_t, t_diff;
648 
649  printPSHeader();
650 
651  gettimeofday(&start, NULL);
652  for(unsigned int i = 0; i < 2000; ++i){
653  pg.insert(point);
654  }
655  gettimeofday(&end, NULL);
656  start_t = start.tv_sec + double(start.tv_usec) / 1e6;
657  end_t = end.tv_sec + double(end.tv_usec) / 1e6;
658  t_diff = end_t - start_t;
659  printf("%%Insertion Time: %.9f \n", t_diff);
660 
661  vector<Observation> obs;
662  vector<PlanarLaserScan> scan;
663 
664  gettimeofday(&start, NULL);
665  pg.updateWorld(footprint, obs, scan);
666  double legal = pg.footprintCost(pt, footprint, 0.0, .95);
667  pg.updateWorld(footprint, obs, scan);
668  double legal2 = pg.footprintCost(pt, footprint, 0.0, .95);
669  gettimeofday(&end, NULL);
670  start_t = start.tv_sec + double(start.tv_usec) / 1e6;
671  end_t = end.tv_sec + double(end.tv_usec) / 1e6;
672  t_diff = end_t - start_t;
673 
674  printf("%%Footprint calc: %.9f \n", t_diff);
675 
676  if(legal >= 0.0)
677  printf("%%Legal footprint %.4f, %.4f\n", legal, legal2);
678  else
679  printf("%%Illegal footprint\n");
680 
681  printPSFooter();
682 
683  return 0;
684 }
geometry_msgs::Point origin_
void printPoint(pcl::PointXYZ pt)
Definition: point_grid.cpp:47
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:358
double resolution_
The resolution of the grid in meters/cell.
Definition: point_grid.h:346
pcl::PointCloud< pcl::PointXYZ > * cloud_
unsigned int width_
The width of the grid in cells.
Definition: point_grid.h:348
double sq_min_separation_
The minimum square distance required between points in the grid.
Definition: point_grid.h:353
A class that implements the WorldModel interface to provide free-space collision checks for the traje...
Definition: point_grid.h:58
void printPSFooter()
Definition: point_grid.cpp:57
bool gridCoords(geometry_msgs::Point pt, unsigned int &gx, unsigned int &gy) const
Convert from world coordinates to grid coordinates.
Definition: point_grid.h:115
int main(int argc, char **argv)
Definition: point_grid.cpp:558
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
Definition: point_grid.h:352
TFSIMD_FORCE_INLINE const tfScalar & y() const
void insert(pcl::PointXYZ pt)
Insert a point into the point grid.
Definition: point_grid.cpp:234
#define DBL_MAX
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan)
Removes points from the grid that lie within a laser scan.
Definition: point_grid.cpp:392
bool ptInPolygon(const pcl::PointXYZ &pt, const std::vector< geometry_msgs::Point > &poly)
Check if a point is in a polygon.
Definition: point_grid.cpp:142
bool ptInScan(const pcl::PointXYZ &pt, const PlanarLaserScan &laser_scan)
Checks to see if a point is within a laser scan specification.
Definition: point_grid.cpp:435
double nearestNeighborDistance(pcl::PointXYZ &pt)
Find the distance between a point and its nearest neighbor in the grid.
Definition: point_grid.cpp:265
std::vector< std::list< pcl::PointXYZ > * > points_
The lists of points returned by a range search, made a member to save on memory allocation.
Definition: point_grid.h:354
void getPoints(pcl::PointCloud< pcl::PointXYZ > &cloud)
Get the points in the point grid.
Definition: point_grid.cpp:479
TFSIMD_FORCE_INLINE const tfScalar & x() const
void getPointsInRange(const geometry_msgs::Point &lower_left, const geometry_msgs::Point &upper_right, std::vector< std::list< pcl::PointXYZ > * > &points)
Returns the points that lie within the cells contained in the specified range. Some of these points m...
Definition: point_grid.cpp:178
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
unsigned int height_
The height of the grid in cells.
Definition: point_grid.h:349
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::vector< std::list< pcl::PointXYZ > > cells_
Storage for the cells in the grid.
Definition: point_grid.h:350
void removePointsInPolygon(const std::vector< geometry_msgs::Point > poly)
Removes points from the grid that lie within the polygon.
Definition: point_grid.cpp:487
double sq_distance(pcl::PointXYZ &pt1, pcl::PointXYZ &pt2)
Compute the squared distance between two points.
Definition: point_grid.h:155
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:190
int min(int a, int b)
void printPolygonPS(const std::vector< geometry_msgs::Point > &poly, double line_width)
Definition: point_grid.cpp:61
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:85
void printPSHeader()
Definition: point_grid.cpp:51
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:531
double orient(const geometry_msgs::Point &a, const geometry_msgs::Point &b, const pcl::PointXYZ &c)
Check the orientation of a pt c with respect to the vector a->b.
Definition: point_grid.h:210
Stores a scan from a planar laser that can be used to clear freespace.
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:140
double max_z_
The height cutoff for adding points as obstacles.
Definition: point_grid.h:351
double getNearestInCell(pcl::PointXYZ &pt, unsigned int gx, unsigned int gy)
Find the distance between a point and its nearest neighbor in a cell.
Definition: point_grid.cpp:254
#define ROS_DEBUG(...)


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