Go to the documentation of this file.
37 #ifndef TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
38 #define TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_
42 #include <geometry_msgs/Point.h>
55 class VoxelGridModel :
public WorldModel {
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);
86 virtual double footprintCost(
const geometry_msgs::Point& position,
const std::vector<geometry_msgs::Point>& footprint,
87 double inscribed_radius,
double circumscribed_radius);
97 void updateWorld(
const std::vector<geometry_msgs::Point>& footprint,
98 const std::vector<costmap_2d::Observation>& observations,
const std::vector<PlanarLaserScan>& laser_scans);
104 void getPoints(sensor_msgs::PointCloud2& cloud);
115 double lineCost(
int x0,
int x1,
int y0,
int y1);
127 inline bool worldToMap3D(
double wx,
double wy,
double wz,
unsigned int& mx,
unsigned int& my,
unsigned int& mz){
136 inline bool worldToMap2D(
double wx,
double wy,
unsigned int& mx,
unsigned int& my){
144 inline void mapToWorld3D(
unsigned int mx,
unsigned int my,
unsigned int mz,
double& wx,
double& wy,
double& wz){
151 inline void mapToWorld2D(
unsigned int mx,
unsigned int my,
double& wx,
double& wy){
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));
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))
void mapToWorld2D(unsigned int mx, unsigned int my, double &wx, double &wy)
double pointCost(int x, int y)
Checks the cost of a point in the costmap.
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
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 insert(const geometry_msgs::Point32 &pt)
Stores a scan from a planar laser that can be used to clear freespace.
virtual ~VoxelGridModel()
Destructor for the world model.
void markVoxel(unsigned int x, unsigned int y, unsigned int z)
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...
void getPoints(sensor_msgs::PointCloud2 &cloud)
Function copying the Voxel points into a point cloud.
void removePointsInScanBoundry(const PlanarLaserScan &laser_scan, double raytrace_range)
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.
voxel_grid::VoxelGrid obstacle_grid_
double sq_obstacle_range_
The square distance at which we no longer add obstacles to the grid.
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...
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
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.
bool worldToMap2D(double wx, double wy, unsigned int &mx, unsigned int &my)
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24