37 #ifndef TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_ 38 #define TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_ 42 #include <geometry_msgs/Point.h> 46 #include <pcl/point_types.h> 47 #include <pcl/point_cloud.h> 73 VoxelGridModel(
double size_x,
double size_y,
double size_z,
double xy_resolution,
double z_resolution,
74 double origin_x,
double origin_y,
double origin_z,
double max_z,
double obstacle_range);
89 virtual double footprintCost(
const geometry_msgs::Point& position,
const std::vector<geometry_msgs::Point>& footprint,
90 double inscribed_radius,
double circumscribed_radius);
100 void updateWorld(
const std::vector<geometry_msgs::Point>& footprint,
101 const std::vector<costmap_2d::Observation>& observations,
const std::vector<PlanarLaserScan>& laser_scans);
103 void getPoints(pcl::PointCloud<pcl::PointXYZ>& cloud);
114 double lineCost(
int x0,
int x1,
int y0,
int y1);
126 inline bool worldToMap3D(
double wx,
double wy,
double wz,
unsigned int& mx,
unsigned int& my,
unsigned int& mz){
135 inline bool worldToMap2D(
double wx,
double wy,
unsigned int& mx,
unsigned int& my){
143 inline void mapToWorld3D(
unsigned int mx,
unsigned int my,
unsigned int mz,
double& wx,
double& wy,
double& wz){
150 inline void mapToWorld2D(
unsigned int mx,
unsigned int my,
double& wx,
double& wy){
156 inline double dist(
double x0,
double y0,
double z0,
double x1,
double y1,
double z1){
157 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
161 unsigned int cell_x, cell_y, cell_z;
162 if(!
worldToMap3D(pt.x, pt.y, pt.z, cell_x, cell_y, cell_z))
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
double pointCost(int x, int y)
Checks the cost of a point in the costmap.
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...
void mapToWorld2D(unsigned int mx, unsigned int my, double &wx, double &wy)
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.
A class that implements the WorldModel interface to provide grid based collision checks for the traje...
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
TFSIMD_FORCE_INLINE const tfScalar & y() const
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...
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
double lineCost(int x0, int x1, int y0, int y1)
Rasterizes a line in the costmap grid and checks for collisions.
double max_z_
The height cutoff for adding points as obstacles.
void insert(pcl::PointXYZ pt)
bool worldToMap2D(double wx, double wy, unsigned int &mx, unsigned int &my)
TFSIMD_FORCE_INLINE const tfScalar & x() const
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...
virtual ~VoxelGridModel()
Destructor for the world model.
void markVoxel(unsigned int x, unsigned int y, unsigned int z)
void getPoints(pcl::PointCloud< pcl::PointXYZ > &cloud)
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
voxel_grid::VoxelGrid obstacle_grid_
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan, double raytrace_range)
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Stores a scan from a planar laser that can be used to clear freespace.