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) {}
51 double inscribed_radius,
double circumscribed_radius){
52 if(footprint.size() < 3)
56 unsigned int x0, x1, y0, y1;
57 double line_cost = 0.0;
60 for(
unsigned int i = 0; i < footprint.size() - 1; ++i){
62 if(!
worldToMap2D(footprint[i].x, footprint[i].y, x0, y0))
66 if(!
worldToMap2D(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
69 line_cost =
lineCost(x0, x1, y0, y1);
78 if(!
worldToMap2D(footprint.back().x, footprint.back().y, x0, y0))
82 if(!
worldToMap2D(footprint.front().x, footprint.front().y, x1, y1))
85 line_cost =
lineCost(x0, x1, y0, y1);
98 int deltax = abs(x1 - x0);
99 int deltay = abs(y1 - y0);
103 int xinc1, xinc2, yinc1, yinc2;
104 int den, num, numadd, numpixels;
106 double line_cost = 0.0;
107 double point_cost = -1.0;
131 if (deltax >= deltay)
150 for (
int curpixel = 0; curpixel <= numpixels; curpixel++)
157 if(line_cost < point_cost)
158 line_cost = point_cost;
184 const vector<Observation>& observations,
const vector<PlanarLaserScan>& laser_scans){
187 for(
unsigned int i = 0; i < laser_scans.size(); ++i)
191 for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
193 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
199 geometry_msgs::Point32 pt;
201 for(; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z){
207 double sq_dist = (*iter_x - obs.
origin_.x) * (*iter_x - obs.
origin_.x)
227 if(laser_scan.
cloud.points.size() == 0)
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;
235 if(!
worldToMap3D(ox, oy, oz, sensor_x, sensor_y, sensor_z))
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;
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;
256 double t = (
max_z_ - .01 - oz) / c;
267 double t = (0.0 - oz) / c;
273 unsigned int point_x, point_y, point_z;
274 if(
worldToMap3D(wpx, wpy, wpz, point_x, point_y, point_z)){