voxel_grid_model.h
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 #ifndef TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
38 #define TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
39 #include <vector>
40 #include <list>
41 #include <cfloat>
42 #include <geometry_msgs/Point.h>
43 #include <costmap_2d/observation.h>
45 
46 //voxel grid stuff
47 #include <voxel_grid/voxel_grid.h>
48 
49 namespace base_local_planner {
55  class VoxelGridModel : public WorldModel {
56  public:
70  VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution,
71  double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range);
72 
76  virtual ~VoxelGridModel(){}
77 
86  virtual double footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
87  double inscribed_radius, double circumscribed_radius);
88 
90 
97  void updateWorld(const std::vector<geometry_msgs::Point>& footprint,
98  const std::vector<costmap_2d::Observation>& observations, const std::vector<PlanarLaserScan>& laser_scans);
99 
104  void getPoints(sensor_msgs::PointCloud2& cloud);
105 
106  private:
115  double lineCost(int x0, int x1, int y0, int y1);
116 
123  double pointCost(int x, int y);
124 
125  void removePointsInScanBoundry(const PlanarLaserScan& laser_scan, double raytrace_range);
126 
127  inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz){
128  if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
129  return false;
130  mx = (int) ((wx - origin_x_) / xy_resolution_);
131  my = (int) ((wy - origin_y_) / xy_resolution_);
132  mz = (int) ((wz - origin_z_) / z_resolution_);
133  return true;
134  }
135 
136  inline bool worldToMap2D(double wx, double wy, unsigned int& mx, unsigned int& my){
137  if(wx < origin_x_ || wy < origin_y_)
138  return false;
139  mx = (int) ((wx - origin_x_) / xy_resolution_);
140  my = (int) ((wy - origin_y_) / xy_resolution_);
141  return true;
142  }
143 
144  inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz){
145  //returns the center point of the cell
146  wx = origin_x_ + (mx + 0.5) * xy_resolution_;
147  wy = origin_y_ + (my + 0.5) * xy_resolution_;
148  wz = origin_z_ + (mz + 0.5) * z_resolution_;
149  }
150 
151  inline void mapToWorld2D(unsigned int mx, unsigned int my, double& wx, double& wy){
152  //returns the center point of the cell
153  wx = origin_x_ + (mx + 0.5) * xy_resolution_;
154  wy = origin_y_ + (my + 0.5) * xy_resolution_;
155  }
156 
157  inline double dist(double x0, double y0, double z0, double x1, double y1, double z1){
158  return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
159  }
160 
161  inline void insert(const geometry_msgs::Point32& pt){
162  unsigned int cell_x, cell_y, cell_z;
163  if(!worldToMap3D(pt.x, pt.y, pt.z, cell_x, cell_y, cell_z))
164  return;
165  obstacle_grid_.markVoxel(cell_x, cell_y, cell_z);
166  }
167 
169  double xy_resolution_;
170  double z_resolution_;
171  double origin_x_;
172  double origin_y_;
173  double origin_z_;
174  double max_z_;
175  double sq_obstacle_range_;
176 
177  };
178 };
179 #endif
base_local_planner::VoxelGridModel::mapToWorld2D
void mapToWorld2D(unsigned int mx, unsigned int my, double &wx, double &wy)
Definition: voxel_grid_model.h:186
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
base_local_planner::VoxelGridModel::xy_resolution_
double xy_resolution_
Definition: voxel_grid_model.h:204
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
base_local_planner::WorldModel::footprintCost
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
base_local_planner::VoxelGridModel::insert
void insert(const geometry_msgs::Point32 &pt)
Definition: voxel_grid_model.h:196
voxel_grid.h
observation.h
base_local_planner::PlanarLaserScan
Stores a scan from a planar laser that can be used to clear freespace.
Definition: planar_laser_scan.h:83
base_local_planner::VoxelGridModel::~VoxelGridModel
virtual ~VoxelGridModel()
Destructor for the world model.
Definition: voxel_grid_model.h:111
voxel_grid::VoxelGrid::markVoxel
void markVoxel(unsigned int x, unsigned int y, unsigned int z)
base_local_planner::VoxelGridModel::origin_z_
double origin_z_
Definition: voxel_grid_model.h:208
base_local_planner::VoxelGridModel::z_resolution_
double z_resolution_
Definition: voxel_grid_model.h:205
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
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
base_local_planner::VoxelGridModel::removePointsInScanBoundry
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan, double raytrace_range)
Definition: voxel_grid_model.cpp:226
base_local_planner::VoxelGridModel::origin_y_
double origin_y_
Definition: voxel_grid_model.h:207
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
base_local_planner::VoxelGridModel::max_z_
double max_z_
The height cutoff for adding points as obstacles.
Definition: voxel_grid_model.h:209
base_local_planner::VoxelGridModel::obstacle_grid_
voxel_grid::VoxelGrid obstacle_grid_
Definition: voxel_grid_model.h:203
base_local_planner::VoxelGridModel::origin_x_
double origin_x_
Definition: voxel_grid_model.h:206
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
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
voxel_grid::VoxelGrid
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
base_local_planner::VoxelGridModel::VoxelGridModel
VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution, double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range)
Constructor for the VoxelGridModel.
Definition: voxel_grid_model.cpp:44
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
world_model.h


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