voxel_costmap_2d.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #include <costmap_2d/voxel_costmap_2d.h>
00038 
00039 #define VOXEL_BITS 16
00040 
00041 using namespace std;
00042 
00043 namespace costmap_2d{
00044   VoxelCostmap2D::VoxelCostmap2D(unsigned int cells_size_x, unsigned int cells_size_y, unsigned int cells_size_z,
00045       double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z, double inscribed_radius,
00046       double circumscribed_radius, double inflation_radius, double obstacle_range,
00047       double raytrace_range, double weight,
00048       const std::vector<unsigned char>& static_data, unsigned char lethal_threshold, unsigned int unknown_threshold, unsigned int mark_threshold, unsigned char unknown_cost_value)
00049     : Costmap2D(cells_size_x, cells_size_y, xy_resolution, origin_x, origin_y, inscribed_radius, circumscribed_radius,
00050         inflation_radius, obstacle_range, cells_size_z * z_resolution + origin_z, raytrace_range, weight, static_data, lethal_threshold, unknown_threshold < cells_size_z, unknown_cost_value),
00051     voxel_grid_(cells_size_x, cells_size_y, cells_size_z), xy_resolution_(xy_resolution), z_resolution_(z_resolution),
00052     origin_z_(origin_z), unknown_threshold_(unknown_threshold + (VOXEL_BITS - cells_size_z)), mark_threshold_(mark_threshold), size_z_(cells_size_z)
00053   {
00054   }
00055 
00056   VoxelCostmap2D::VoxelCostmap2D(costmap_2d::Costmap2D& costmap, 
00057       double z_resolution, unsigned int cells_size_z, double origin_z, 
00058       unsigned int mark_threshold, unsigned int unknown_threshold)
00059     : Costmap2D(costmap), voxel_grid_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY(), cells_size_z), 
00060         xy_resolution_(costmap.getResolution()), z_resolution_(z_resolution), origin_z_(origin_z), 
00061         unknown_threshold_(unknown_threshold + (VOXEL_BITS - cells_size_z)), mark_threshold_(mark_threshold), size_z_(cells_size_z)
00062   {
00063   }
00064 
00065   VoxelCostmap2D::~VoxelCostmap2D(){}
00066 
00067   void VoxelCostmap2D::initMaps(unsigned int size_x, unsigned int size_y){
00068     Costmap2D::initMaps(size_x, size_y);
00069     voxel_grid_.resize(size_x, size_y, size_z_);
00070     ROS_ASSERT(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
00071   }
00072 
00073   void VoxelCostmap2D::resetMaps(){
00074     Costmap2D::resetMaps();
00075     voxel_grid_.reset();
00076   }
00077 
00078   void VoxelCostmap2D::resetMapOutsideWindow(double wx, double wy, double w_size_x, double w_size_y){
00079     ROS_ASSERT_MSG(w_size_x >= 0 && w_size_y >= 0, "You cannot specify a negative size window");
00080 
00081     double start_point_x = wx - w_size_x / 2;
00082     double start_point_y = wy - w_size_y / 2;
00083     double end_point_x = start_point_x + w_size_x;
00084     double end_point_y = start_point_y + w_size_y;
00085 
00086     //check start bounds
00087     start_point_x = max(origin_x_, start_point_x);
00088     start_point_y = max(origin_y_, start_point_y);
00089 
00090     //check end bounds
00091     end_point_x = min(origin_x_ + getSizeInMetersX(), end_point_x);
00092     end_point_y = min(origin_y_ + getSizeInMetersY(), end_point_y);
00093 
00094     unsigned int start_x, start_y, end_x, end_y;
00095 
00096     //check for legality just in case
00097     if(!worldToMap(start_point_x, start_point_y, start_x, start_y) || !worldToMap(end_point_x, end_point_y, end_x, end_y))
00098       return;
00099 
00100     ROS_ASSERT(end_x > start_x && end_y > start_y);
00101     unsigned int cell_size_x = end_x - start_x;
00102     unsigned int cell_size_y = end_y - start_y;
00103 
00104     //we need a map to store the obstacles in the window temporarily
00105     unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00106     unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
00107     unsigned int* voxel_map = voxel_grid_.getData();
00108 
00109     //copy the local window in the costmap to the local map
00110     copyMapRegion(costmap_, start_x, start_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00111     copyMapRegion(voxel_map, start_x, start_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00112 
00113     //now we'll reset the costmap to the static map
00114     memcpy(costmap_, static_map_, size_x_ * size_y_ * sizeof(unsigned char));
00115 
00116     //the voxel grid will just go back to being unknown
00117     voxel_grid_.reset();
00118 
00119     //now we want to copy the local map back into the costmap
00120     copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00121     copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00122 
00123     //clean up
00124     delete[] local_map;
00125     delete[] local_voxel_map;
00126   }
00127 
00128   void VoxelCostmap2D::updateObstacles(const vector<Observation>& observations, priority_queue<CellData>& inflation_queue){
00129     //place the new obstacles into a priority queue... each with a priority of zero to begin with
00130     for(vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it){
00131       const Observation& obs = *it;
00132 
00133       const pcl::PointCloud<pcl::PointXYZ>& cloud =obs.cloud_;
00134 
00135       double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
00136 
00137       for(unsigned int i = 0; i < cloud.points.size(); ++i){
00138         //if the obstacle is too high or too far away from the robot we won't add it
00139         if(cloud.points[i].z > max_obstacle_height_)
00140           continue;
00141 
00142         //compute the squared distance from the hitpoint to the pointcloud's origin
00143         double sq_dist = (cloud.points[i].x - obs.origin_.x) * (cloud.points[i].x - obs.origin_.x)
00144           + (cloud.points[i].y - obs.origin_.y) * (cloud.points[i].y - obs.origin_.y)
00145           + (cloud.points[i].z - obs.origin_.z) * (cloud.points[i].z - obs.origin_.z);
00146 
00147         //if the point is far enough away... we won't consider it
00148         if(sq_dist >= sq_obstacle_range)
00149           continue;
00150 
00151         //now we need to compute the map coordinates for the observation
00152         unsigned int mx, my, mz;
00153         if(cloud.points[i].z < origin_z_){
00154           if(!worldToMap3D(cloud.points[i].x, cloud.points[i].y, origin_z_, mx, my, mz))
00155             continue;
00156         }
00157         else if(!worldToMap3D(cloud.points[i].x, cloud.points[i].y, cloud.points[i].z, mx, my, mz)){
00158           continue;
00159         }
00160 
00161         //mark the cell in the voxel grid and check if we should also mark it in the costmap
00162         if(voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)){
00163           unsigned int index = getIndex(mx, my);
00164 
00165           //push the relevant cell index back onto the inflation queue
00166           enqueue(index, mx, my, mx, my, inflation_queue);
00167         }
00168       }
00169     }
00170   }
00171 
00172   void VoxelCostmap2D::raytraceFreespace(const Observation& clearing_observation){
00173     if(clearing_observation.cloud_.points.size() == 0)
00174       return;
00175 
00176 
00177     double sensor_x, sensor_y, sensor_z;
00178     double ox = clearing_observation.origin_.x;
00179     double oy = clearing_observation.origin_.y;
00180     double oz = clearing_observation.origin_.z;
00181 
00182     if(!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)){
00183       ROS_WARN_THROTTLE(1.0, "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.", ox, oy, oz);
00184       return;
00185     }
00186 
00187     //we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
00188     double map_end_x = origin_x_ + getSizeInMetersX();
00189     double map_end_y = origin_y_ + getSizeInMetersY();
00190 
00191     for(unsigned int i = 0; i < clearing_observation.cloud_.points.size(); ++i){
00192       double wpx = clearing_observation.cloud_.points[i].x;
00193       double wpy = clearing_observation.cloud_.points[i].y;
00194       double wpz = clearing_observation.cloud_.points[i].z;
00195 
00196       double distance = dist(ox, oy, oz, wpx, wpy, wpz);
00197       double scaling_fact = 1.0;
00198       scaling_fact = std::max(std::min(scaling_fact, (distance -  2 * xy_resolution_) / distance), 0.0);
00199       wpx = scaling_fact * (wpx - ox) + ox;
00200       wpy = scaling_fact * (wpy - oy) + oy;
00201       wpz = scaling_fact * (wpz - oz) + oz;
00202 
00203       double a = wpx - ox;
00204       double b = wpy - oy;
00205       double c = wpz - oz;
00206       double t = 1.0;
00207 
00208       //we can only raytrace to a maximum z height
00209       if(wpz > max_obstacle_height_){
00210         //we know we want the vector's z value to be max_z
00211         t = std::min(t, (max_obstacle_height_ - 0.01 - oz) / c);
00212       }
00213       //and we can only raytrace down to the floor
00214       else if(wpz < origin_z_){
00215         //we know we want the vector's z value to be 0.0
00216         t = std::min(t, (origin_z_ - oz) / c);
00217       }
00218 
00219       //the minimum value to raytrace from is the origin
00220       if(wpx < origin_x_){
00221         t = std::min(t, (origin_x_ - ox) / a);
00222       }
00223       if(wpy < origin_y_){
00224         t = std::min(t, (origin_y_ - oy) / b);
00225       }
00226 
00227       //the maximum value to raytrace to is the end of the map
00228       if(wpx > map_end_x){
00229         t = std::min(t, (map_end_x - ox) / a);
00230       }
00231       if(wpy > map_end_y){
00232         t = std::min(t, (map_end_y - oy) / b);
00233       }
00234 
00235       wpx = ox + a * t;
00236       wpy = oy + b * t;
00237       wpz = oz + c * t;
00238 
00239       double point_x, point_y, point_z;
00240       if(worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z)){
00241         unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
00242         
00243         //voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
00244         voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_, 
00245             unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION, cell_raytrace_range);
00246       }
00247     }
00248   }
00249 
00250 
00251   void VoxelCostmap2D::updateOrigin(double new_origin_x, double new_origin_y){
00252     //project the new origin into the grid
00253     int cell_ox, cell_oy;
00254     cell_ox = int((new_origin_x - origin_x_) / resolution_);
00255     cell_oy = int((new_origin_y - origin_y_) / resolution_);
00256 
00257     //compute the associated world coordinates for the origin cell
00258     //beacuase we want to keep things grid-aligned
00259     double new_grid_ox, new_grid_oy;
00260     new_grid_ox = origin_x_ + cell_ox * resolution_;
00261     new_grid_oy = origin_y_ + cell_oy * resolution_;
00262 
00263     //To save casting from unsigned int to int a bunch of times
00264     int size_x = size_x_;
00265     int size_y = size_y_;
00266 
00267     //we need to compute the overlap of the new and existing windows
00268     int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00269     lower_left_x = min(max(cell_ox, 0), size_x);
00270     lower_left_y = min(max(cell_oy, 0), size_y);
00271     upper_right_x = min(max(cell_ox + size_x, 0), size_x);
00272     upper_right_y = min(max(cell_oy + size_y, 0), size_y);
00273 
00274     unsigned int cell_size_x = upper_right_x - lower_left_x;
00275     unsigned int cell_size_y = upper_right_y - lower_left_y;
00276 
00277     //we need a map to store the obstacles in the window temporarily
00278     unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00279     unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
00280     unsigned int* voxel_map = voxel_grid_.getData(); 
00281 
00282     //copy the local window in the costmap to the local map
00283     copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00284     copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00285 
00286     //we'll reset our maps to unknown space if appropriate
00287     resetMaps();
00288 
00289     //update the origin with the appropriate world coordinates
00290     origin_x_ = new_grid_ox;
00291     origin_y_ = new_grid_oy;
00292 
00293     //compute the starting cell location for copying data back in
00294     int start_x = lower_left_x - cell_ox;
00295     int start_y = lower_left_y - cell_oy;
00296 
00297     //now we want to copy the overlapping information back into the map, but in its new location
00298     copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00299     copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00300 
00301     //make sure to clean up
00302     delete[] local_map;
00303     delete[] local_voxel_map;
00304 
00305   }
00306 
00307   void VoxelCostmap2D::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info){
00308     //get the cell coordinates of the center point of the window
00309     unsigned int mx, my;
00310     if(!worldToMap(wx, wy, mx, my))
00311       return;
00312 
00313     //compute the bounds of the window
00314     double start_x = wx - w_size_x / 2;
00315     double start_y = wy - w_size_y / 2;
00316     double end_x = start_x + w_size_x;
00317     double end_y = start_y + w_size_y;
00318 
00319     //scale the window based on the bounds of the costmap
00320     start_x = max(origin_x_, start_x);
00321     start_y = max(origin_y_, start_y);
00322 
00323     end_x = min(origin_x_ + getSizeInMetersX(), end_x);
00324     end_y = min(origin_y_ + getSizeInMetersY(), end_y);
00325 
00326     //get the map coordinates of the bounds of the window
00327     unsigned int map_sx, map_sy, map_ex, map_ey;
00328 
00329     //check for legality just in case
00330     if(!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
00331       return;
00332 
00333     //we know that we want to clear all non-lethal obstacles in this window to get it ready for inflation
00334     unsigned int index = getIndex(map_sx, map_sy);
00335     unsigned char* current = &costmap_[index];
00336     for(unsigned int j = map_sy; j <= map_ey; ++j){
00337       for(unsigned int i = map_sx; i <= map_ex; ++i){
00338         //if the cell is a lethal obstacle... we'll keep it and queue it, otherwise... we'll clear it
00339         if(*current != LETHAL_OBSTACLE){
00340           if(clear_no_info || *current != NO_INFORMATION){
00341             *current = FREE_SPACE;
00342             voxel_grid_.clearVoxelColumn(index);
00343           }
00344         }
00345         current++;
00346         index++;
00347       }
00348       current += size_x_ - (map_ex - map_sx) - 1;
00349       index += size_x_ - (map_ex - map_sx) - 1;
00350     }
00351   }
00352 
00353   void VoxelCostmap2D::getVoxelGridMessage(VoxelGrid& grid){
00354     unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
00355     grid.size_x = voxel_grid_.sizeX();
00356     grid.size_y = voxel_grid_.sizeY();
00357     grid.size_z = voxel_grid_.sizeZ();
00358     grid.data.resize(size);
00359     memcpy(&grid.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
00360 
00361     grid.origin.x = origin_x_;
00362     grid.origin.y = origin_y_;
00363     grid.origin.z = origin_z_;
00364 
00365     grid.resolutions.x = xy_resolution_;
00366     grid.resolutions.y = xy_resolution_;
00367     grid.resolutions.z = z_resolution_;
00368   }
00369 
00370   void VoxelCostmap2D::getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud){
00371     for(unsigned int i = 0; i < voxel_grid_.sizeX(); ++i){
00372       for(unsigned int j = 0; j < voxel_grid_.sizeY(); ++j){
00373         for(unsigned int k = 0; k < voxel_grid_.sizeZ(); ++k){
00374           if(voxel_grid_.getVoxel(i, j, k) == voxel_grid::MARKED){
00375             double wx, wy, wz;
00376             mapToWorld3D(i, j, k, wx, wy, wz);
00377             pcl::PointXYZ pt;
00378             pt.x = wx;
00379             pt.y = wy;
00380             pt.z = wz;
00381             cloud.points.push_back(pt);
00382           }
00383         }
00384       }
00385     }
00386   }
00387 
00388   void VoxelCostmap2D::finishConfiguration(costmap_2d::Costmap2DConfig &config) {
00389     unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
00390     mark_threshold_ = config.mark_threshold;
00391   }
00392 
00393 };


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40