voxel_grid_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 
40 using namespace std;
41 using namespace costmap_2d;
42 
43 namespace base_local_planner {
44  VoxelGridModel::VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution,
45  double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range) :
46  obstacle_grid_(size_x, size_y, size_z), xy_resolution_(xy_resolution), z_resolution_(z_resolution),
47  origin_x_(origin_x), origin_y_(origin_y), origin_z_(origin_z),
48  max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range) {}
49 
50  double VoxelGridModel::footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
51  double inscribed_radius, double circumscribed_radius){
52  if(footprint.size() < 3)
53  return -1.0;
54 
55  //now we really have to lay down the footprint in the costmap grid
56  unsigned int x0, x1, y0, y1;
57  double line_cost = 0.0;
58 
59  //we need to rasterize each line in the footprint
60  for(unsigned int i = 0; i < footprint.size() - 1; ++i){
61  //get the cell coord of the first point
62  if(!worldToMap2D(footprint[i].x, footprint[i].y, x0, y0))
63  return -1.0;
64 
65  //get the cell coord of the second point
66  if(!worldToMap2D(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
67  return -1.0;
68 
69  line_cost = lineCost(x0, x1, y0, y1);
70 
71  //if there is an obstacle that hits the line... we know that we can return false right away
72  if(line_cost < 0)
73  return -1.0;
74  }
75 
76  //we also need to connect the first point in the footprint to the last point
77  //get the cell coord of the last point
78  if(!worldToMap2D(footprint.back().x, footprint.back().y, x0, y0))
79  return -1.0;
80 
81  //get the cell coord of the first point
82  if(!worldToMap2D(footprint.front().x, footprint.front().y, x1, y1))
83  return -1.0;
84 
85  line_cost = lineCost(x0, x1, y0, y1);
86 
87  if(line_cost < 0)
88  return -1.0;
89 
90  //if all line costs are legal... then we can return that the footprint is legal
91  return 0.0;
92  }
93 
94  //calculate the cost of a ray-traced line
95  double VoxelGridModel::lineCost(int x0, int x1,
96  int y0, int y1){
97  //Bresenham Ray-Tracing
98  int deltax = abs(x1 - x0); // The difference between the x's
99  int deltay = abs(y1 - y0); // The difference between the y's
100  int x = x0; // Start x off at the first pixel
101  int y = y0; // Start y off at the first pixel
102 
103  int xinc1, xinc2, yinc1, yinc2;
104  int den, num, numadd, numpixels;
105 
106  double line_cost = 0.0;
107  double point_cost = -1.0;
108 
109  if (x1 >= x0) // The x-values are increasing
110  {
111  xinc1 = 1;
112  xinc2 = 1;
113  }
114  else // The x-values are decreasing
115  {
116  xinc1 = -1;
117  xinc2 = -1;
118  }
119 
120  if (y1 >= y0) // The y-values are increasing
121  {
122  yinc1 = 1;
123  yinc2 = 1;
124  }
125  else // The y-values are decreasing
126  {
127  yinc1 = -1;
128  yinc2 = -1;
129  }
130 
131  if (deltax >= deltay) // There is at least one x-value for every y-value
132  {
133  xinc1 = 0; // Don't change the x when numerator >= denominator
134  yinc2 = 0; // Don't change the y for every iteration
135  den = deltax;
136  num = deltax / 2;
137  numadd = deltay;
138  numpixels = deltax; // There are more x-values than y-values
139  }
140  else // There is at least one y-value for every x-value
141  {
142  xinc2 = 0; // Don't change the x for every iteration
143  yinc1 = 0; // Don't change the y when numerator >= denominator
144  den = deltay;
145  num = deltay / 2;
146  numadd = deltax;
147  numpixels = deltay; // There are more y-values than x-values
148  }
149 
150  for (int curpixel = 0; curpixel <= numpixels; curpixel++)
151  {
152  point_cost = pointCost(x, y); //Score the current point
153 
154  if(point_cost < 0)
155  return -1;
156 
157  if(line_cost < point_cost)
158  line_cost = point_cost;
159 
160  num += numadd; // Increase the numerator by the top of the fraction
161  if (num >= den) // Check if numerator >= denominator
162  {
163  num -= den; // Calculate the new numerator value
164  x += xinc1; // Change the x as appropriate
165  y += yinc1; // Change the y as appropriate
166  }
167  x += xinc2; // Change the x as appropriate
168  y += yinc2; // Change the y as appropriate
169  }
170 
171  return line_cost;
172  }
173 
174  double VoxelGridModel::pointCost(int x, int y){
175  //if the cell is in an obstacle the path is invalid
176  if(obstacle_grid_.getVoxelColumn(x, y)){
177  return -1;
178  }
179 
180  return 1;
181  }
182 
183  void VoxelGridModel::updateWorld(const std::vector<geometry_msgs::Point>& footprint,
184  const vector<Observation>& observations, const vector<PlanarLaserScan>& laser_scans){
185 
186  //remove points in the laser scan boundry
187  for(unsigned int i = 0; i < laser_scans.size(); ++i)
188  removePointsInScanBoundry(laser_scans[i], 10.0);
189 
190  //iterate through all observations and update the grid
191  for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
192  const Observation& obs = *it;
193  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
194 
198 
199  geometry_msgs::Point32 pt;
200 
201  for(; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z){
202  //filter out points that are too high
203  if(*iter_z > max_z_)
204  continue;
205 
206  //compute the squared distance from the hitpoint to the pointcloud's origin
207  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x)
208  + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y)
209  + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
210 
211  if(sq_dist >= sq_obstacle_range_)
212  continue;
213 
214  //insert the point
215  pt.x = *iter_x;
216  pt.y = *iter_y;
217  pt.z = *iter_z;
218  insert(pt);
219  }
220  }
221 
222  //remove the points that are in the footprint of the robot
223  //removePointsInPolygon(footprint);
224  }
225 
226  void VoxelGridModel::removePointsInScanBoundry(const PlanarLaserScan& laser_scan, double raytrace_range){
227  if(laser_scan.cloud.points.size() == 0)
228  return;
229 
230  unsigned int sensor_x, sensor_y, sensor_z;
231  double ox = laser_scan.origin.x;
232  double oy = laser_scan.origin.y;
233  double oz = laser_scan.origin.z;
234 
235  if(!worldToMap3D(ox, oy, oz, sensor_x, sensor_y, sensor_z))
236  return;
237 
238  for(unsigned int i = 0; i < laser_scan.cloud.points.size(); ++i){
239  double wpx = laser_scan.cloud.points[i].x;
240  double wpy = laser_scan.cloud.points[i].y;
241  double wpz = laser_scan.cloud.points[i].z;
242 
243  double distance = dist(ox, oy, oz, wpx, wpy, wpz);
244  double scaling_fact = raytrace_range / distance;
245  scaling_fact = scaling_fact > 1.0 ? 1.0 : scaling_fact;
246  wpx = scaling_fact * (wpx - ox) + ox;
247  wpy = scaling_fact * (wpy - oy) + oy;
248  wpz = scaling_fact * (wpz - oz) + oz;
249 
250  //we can only raytrace to a maximum z height
251  if(wpz >= max_z_){
252  //we know we want the vector's z value to be max_z
253  double a = wpx - ox;
254  double b = wpy - oy;
255  double c = wpz - oz;
256  double t = (max_z_ - .01 - oz) / c;
257  wpx = ox + a * t;
258  wpy = oy + b * t;
259  wpz = oz + c * t;
260  }
261  //and we can only raytrace down to the floor
262  else if(wpz < 0.0){
263  //we know we want the vector's z value to be 0.0
264  double a = wpx - ox;
265  double b = wpy - oy;
266  double c = wpz - oz;
267  double t = (0.0 - oz) / c;
268  wpx = ox + a * t;
269  wpy = oy + b * t;
270  wpz = oz + c * t;
271  }
272 
273  unsigned int point_x, point_y, point_z;
274  if(worldToMap3D(wpx, wpy, wpz, point_x, point_y, point_z)){
275  obstacle_grid_.clearVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
276  }
277  }
278  }
279 
280  void VoxelGridModel::getPoints(sensor_msgs::PointCloud2& cloud){
281  size_t n = 0;
282 
283  for(unsigned int i = 0; i < obstacle_grid_.sizeX(); ++i)
284  for(unsigned int j = 0; j < obstacle_grid_.sizeY(); ++j)
285  for(unsigned int k = 0; k < obstacle_grid_.sizeZ(); ++k)
286  if(obstacle_grid_.getVoxel(i, j, k))
287  ++n;
288 
289  sensor_msgs::PointCloud2Modifier modifier(cloud);
290  modifier.setPointCloud2FieldsByString(1, "xyz");
291  modifier.resize(n);
292 
293  sensor_msgs::PointCloud2Iterator<float> iter_x(cloud, "x");
294  sensor_msgs::PointCloud2Iterator<float> iter_y(cloud, "y");
295  sensor_msgs::PointCloud2Iterator<float> iter_z(cloud, "z");
296 
297  for(unsigned int i = 0; i < obstacle_grid_.sizeX(); ++i){
298  for(unsigned int j = 0; j < obstacle_grid_.sizeY(); ++j){
299  for(unsigned int k = 0; k < obstacle_grid_.sizeZ(); ++k){
300  if(obstacle_grid_.getVoxel(i, j, k)){
301  double wx, wy, wz;
302  mapToWorld3D(i, j, k, wx, wy, wz);
303  *iter_x = wx;
304  *iter_y = wy;
305  *iter_z = wz;
306  ++iter_x;
307  ++iter_y;
308  ++iter_z;
309  }
310  }
311  }
312  }
313  }
314 };
base_local_planner::VoxelGridModel::pointCost
double pointCost(int x, int y)
Checks the cost of a point in the costmap.
Definition: voxel_grid_model.cpp:174
point_cloud2_iterator.h
base_local_planner::VoxelGridModel::mapToWorld3D
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
Definition: voxel_grid_model.h:179
voxel_grid::VoxelGrid::clearVoxelLine
void clearVoxelLine(double x0, double y0, double z0, double x1, double y1, double z1, unsigned int max_length=UINT_MAX)
PointCloud2IteratorBase< T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator >::end
PointCloud2ConstIterator< T > end() const
base_local_planner::VoxelGridModel::insert
void insert(const geometry_msgs::Point32 &pt)
Definition: voxel_grid_model.h:196
voxel_grid::VoxelGrid::sizeZ
unsigned int sizeZ()
base_local_planner::PlanarLaserScan
Stores a scan from a planar laser that can be used to clear freespace.
Definition: planar_laser_scan.h:83
voxel_grid::VoxelGrid::sizeX
unsigned int sizeX()
sensor_msgs::PointCloud2ConstIterator
base_local_planner::VoxelGridModel::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 obstacles in the voxel grid lie inside a convex footprint that is rasterized into the g...
Definition: voxel_grid_model.cpp:50
costmap_2d::Observation::cloud_
sensor_msgs::PointCloud2 * cloud_
base_local_planner::VoxelGridModel::getPoints
void getPoints(sensor_msgs::PointCloud2 &cloud)
Function copying the Voxel points into a point cloud.
Definition: voxel_grid_model.cpp:280
voxel_grid::VoxelGrid::sizeY
unsigned int sizeY()
base_local_planner::VoxelGridModel::removePointsInScanBoundry
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan, double raytrace_range)
Definition: voxel_grid_model.cpp:226
voxel_grid::VoxelGrid::getVoxel
VoxelStatus getVoxel(unsigned int x, unsigned int y, unsigned int z)
sensor_msgs::PointCloud2Iterator
base_local_planner::VoxelGridModel::lineCost
double lineCost(int x0, int x1, int y0, int y1)
Rasterizes a line in the costmap grid and checks for collisions.
Definition: voxel_grid_model.cpp:95
distance
double distance(double x0, double y0, double x1, double y1)
base_local_planner::PlanarLaserScan::cloud
sensor_msgs::PointCloud cloud
Definition: planar_laser_scan.h:87
voxel_grid_model.h
base_local_planner::VoxelGridModel::max_z_
double max_z_
The height cutoff for adding points as obstacles.
Definition: voxel_grid_model.h:209
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
voxel_grid::VoxelGrid::getVoxelColumn
VoxelStatus getVoxelColumn(unsigned int x, unsigned int y, unsigned int unknown_threshold=0, unsigned int marked_threshold=0)
base_local_planner::VoxelGridModel::obstacle_grid_
voxel_grid::VoxelGrid obstacle_grid_
Definition: voxel_grid_model.h:203
costmap_2d::Observation
std
sensor_msgs::PointCloud2Modifier
costmap_2d::Observation::origin_
geometry_msgs::Point origin_
base_local_planner::VoxelGridModel::sq_obstacle_range_
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
Definition: voxel_grid_model.h:210
base_local_planner
Definition: costmap_model.h:44
costmap_2d
base_local_planner::VoxelGridModel::updateWorld
void updateWorld(const std::vector< geometry_msgs::Point > &footprint, const std::vector< costmap_2d::Observation > &observations, const std::vector< PlanarLaserScan > &laser_scans)
The costmap already keeps track of world observations, so for this world model this method does nothi...
Definition: voxel_grid_model.cpp:183
base_local_planner::VoxelGridModel::dist
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Definition: voxel_grid_model.h:192
t
geometry_msgs::TransformStamped t
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
base_local_planner::PlanarLaserScan::origin
geometry_msgs::Point32 origin
Definition: planar_laser_scan.h:86
base_local_planner::VoxelGridModel::worldToMap2D
bool worldToMap2D(double wx, double wy, unsigned int &mx, unsigned int &my)
Definition: voxel_grid_model.h:171
base_local_planner::VoxelGridModel::worldToMap3D
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Definition: voxel_grid_model.h:162


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