48 printf(
"(%.2f, %.2f, %.2f)", pt.x, pt.y, pt.z);
53 printf(
"%%%%Creator: Eitan Marder-Eppstein (Willow Garage)\n");
54 printf(
"%%%%EndComments\n");
58 printf(
"showpage\n%%%%EOF\n");
61 void printPolygonPS(
const std::vector<geometry_msgs::Point>& poly,
double line_width){
65 printf(
"%.2f setlinewidth\n", line_width);
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");
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)
86 double inscribed_radius,
double circumscribed_radius){
88 double outer_square_radius = circumscribed_radius;
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;
95 c_upper_right.x = position.x + outer_square_radius;
96 c_upper_right.y = position.y + outer_square_radius;
107 double inner_square_radius = sqrt((inscribed_radius * inscribed_radius) / 2.0);
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;
114 i_upper_right.x = position.x + inner_square_radius;
115 i_upper_right.y = position.y + inner_square_radius;
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;
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){
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)
149 bool all_left =
false;
150 bool all_right =
false;
151 for(
unsigned int i = 0; i < poly.size() - 1; ++i){
153 if(
orient(poly[i], poly[i + 1], pt) > 0){
166 if(
orient(poly[poly.size() - 1], poly[0], pt) > 0){
178 void PointGrid::getPointsInRange(
const geometry_msgs::Point& lower_left,
const geometry_msgs::Point& upper_right, vector< list<pcl::PointXYZ>* >& points){
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;
195 unsigned int lower_left_index =
gridIndex(gx, gy);
199 unsigned int lower_right_index =
gridIndex(gx, gy);
203 unsigned int upper_left_index =
gridIndex(gx, gy);
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;
218 vector< list<pcl::PointXYZ> >::iterator cell_iterator =
cells_.begin() + lower_left_index;
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;
225 points.push_back(&cell);
230 cell_iterator +=
width_ - (x_steps - 1);
247 unsigned int pt_index =
gridIndex(gx, gy);
250 cells_[pt_index].push_back(pt);
258 for(list<pcl::PointXYZ>::iterator it =
cells_[index].begin(); it !=
cells_[index].end(); ++it){
272 geometry_msgs::Point lower_left, upper_right;
276 pcl::PointXYZ check_point;
278 double neighbor_sq_dist =
DBL_MAX;
282 check_point.x = lower_left.x;
283 check_point.y = pt.y;
290 if(gx > 0 && gy <
height_ - 1){
291 check_point.x = lower_left.x;
292 check_point.y = upper_right.y;
300 check_point.x = pt.x;
301 check_point.y = upper_right.y;
309 check_point.x = upper_right.x;
310 check_point.y = upper_right.y;
318 check_point.x = upper_right.x;
319 check_point.y = pt.y;
326 if(gx < width_ - 1 && gy > 0){
327 check_point.x = upper_right.x;
328 check_point.y = lower_left.y;
336 check_point.x = pt.x;
337 check_point.y = lower_left.y;
344 if(gx > 0 && gy > 0){
345 check_point.x = lower_left.x;
346 check_point.y = lower_left.y;
355 return neighbor_sq_dist;
359 const vector<Observation>& observations,
const vector<PlanarLaserScan>& laser_scans){
361 if(laser_scans.empty())
367 for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
369 const pcl::PointCloud<pcl::PointXYZ>& cloud = *(obs.
cloud_);
370 for(
unsigned int i = 0; i < cloud.size(); ++i){
376 double sq_dist = (cloud[i].x - obs.
origin_.x) * (cloud[i].
x - obs.
origin_.x)
393 if(laser_scan.
cloud.points.size() == 0)
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;
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);
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;
426 it = cell_points->erase(it);
436 if(!laser_scan.
cloud.points.empty()){
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;
443 double perp_dot = v1_x * v2_y - v1_y * v2_x;
444 double dot = v1_x * v2_x + v1_y * v2_y;
447 double vector_angle = atan2(perp_dot, dot);
451 vector_angle = 2 * M_PI + vector_angle;
456 if(vector_angle < 0 || vector_angle >= total_rads)
460 unsigned int index = (
unsigned int) (vector_angle / laser_scan.
angle_increment);
463 if(index >= laser_scan.
cloud.points.size() - 1){
468 if(
orient(laser_scan.
cloud.points[index], laser_scan.
cloud.points[index + 1], pt) > 0){
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);
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;
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);
505 ROS_DEBUG(
"Lower: (%.2f, %.2f), Upper: (%.2f, %.2f)\n", lower_left.x, lower_left.y, upper_right.x, upper_right.y);
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;
522 it = cell_points->erase(it);
532 const geometry_msgs::Point& u1,
const geometry_msgs::Point& u2, geometry_msgs::Point& result){
534 double a1 = v2.y - v1.y;
535 double b1 = v1.x - v2.x;
536 double c1 = a1 * v1.x + b1 * v1.y;
539 double a2 = u2.y - u1.y;
540 double b2 = u1.x - u2.x;
541 double c2 = a2 * u1.x + b2 * u1.y;
543 double det = a1 * b2 - a2 * b1;
549 result.x = (b2 * c1 - b1 * c2) / det;
550 result.y = (a1 * c2 - a2 * c1) / det;
558 int main(
int argc,
char** argv){
559 geometry_msgs::Point origin;
562 PointGrid pg(50.0, 50.0, 0.2, origin, 2.0, 3.0, 0.0);
579 std::vector<geometry_msgs::Point> footprint, footprint2, footprint3;
580 geometry_msgs::Point pt;
584 footprint.push_back(pt);
588 footprint.push_back(pt);
592 footprint.push_back(pt);
596 footprint.push_back(pt);
600 footprint.push_back(pt);
604 footprint2.push_back(pt);
608 footprint2.push_back(pt);
612 footprint2.push_back(pt);
616 footprint2.push_back(pt);
620 footprint3.push_back(pt);
624 footprint3.push_back(pt);
628 footprint3.push_back(pt);
632 footprint3.push_back(pt);
636 footprint3.push_back(pt);
646 struct timeval start, end;
647 double start_t, end_t, t_diff;
651 gettimeofday(&start, NULL);
652 for(
unsigned int i = 0; i < 2000; ++i){
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);
661 vector<Observation> obs;
662 vector<PlanarLaserScan> scan;
664 gettimeofday(&start, NULL);
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;
674 printf(
"%%Footprint calc: %.9f \n", t_diff);
677 printf(
"%%Legal footprint %.4f, %.4f\n", legal, legal2);
679 printf(
"%%Illegal footprint\n");
geometry_msgs::Point origin_
void printPoint(pcl::PointXYZ pt)
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.
double resolution_
The resolution of the grid in meters/cell.
pcl::PointCloud< pcl::PointXYZ > * cloud_
unsigned int width_
The width of the grid in cells.
double sq_min_separation_
The minimum square distance required between points in the grid.
A class that implements the WorldModel interface to provide free-space collision checks for the traje...
bool gridCoords(geometry_msgs::Point pt, unsigned int &gx, unsigned int &gy) const
Convert from world coordinates to grid coordinates.
int main(int argc, char **argv)
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
TFSIMD_FORCE_INLINE const tfScalar & y() const
void insert(pcl::PointXYZ pt)
Insert a point into the point grid.
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan)
Removes points from the grid that lie within a laser scan.
geometry_msgs::Point32 origin
bool ptInPolygon(const pcl::PointXYZ &pt, const std::vector< geometry_msgs::Point > &poly)
Check if a point is in a polygon.
sensor_msgs::PointCloud cloud
bool ptInScan(const pcl::PointXYZ &pt, const PlanarLaserScan &laser_scan)
Checks to see if a point is within a laser scan specification.
double nearestNeighborDistance(pcl::PointXYZ &pt)
Find the distance between a point and its nearest neighbor in the grid.
std::vector< std::list< pcl::PointXYZ > * > points_
The lists of points returned by a range search, made a member to save on memory allocation.
void getPoints(pcl::PointCloud< pcl::PointXYZ > &cloud)
Get the points in the point grid.
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...
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
unsigned int height_
The height of the grid in cells.
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::vector< std::list< pcl::PointXYZ > > cells_
Storage for the cells in the grid.
void removePointsInPolygon(const std::vector< geometry_msgs::Point > poly)
Removes points from the grid that lie within the polygon.
double sq_distance(pcl::PointXYZ &pt1, pcl::PointXYZ &pt2)
Compute the squared distance between two points.
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...
void printPolygonPS(const std::vector< geometry_msgs::Point > &poly, double line_width)
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.
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.
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.
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...
double max_z_
The height cutoff for adding points as obstacles.
double getNearestInCell(pcl::PointXYZ &pt, unsigned int gx, unsigned int gy)
Find the distance between a point and its nearest neighbor in a cell.