39 #ifndef COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_ 40 #define COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_ 46 #include <costmap_2d/VoxelGrid.h> 47 #include <nav_msgs/OccupancyGrid.h> 48 #include <sensor_msgs/LaserScan.h> 50 #include <sensor_msgs/PointCloud.h> 51 #include <sensor_msgs/PointCloud2.h> 55 #include <dynamic_reconfigure/server.h> 56 #include <nonpersistent_voxel_layer/NonPersistentVoxelPluginConfig.h> 75 virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
76 double* max_x,
double* max_y);
78 void updateOrigin(
double new_origin_x,
double new_origin_y);
90 void updateFootprint(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
91 double* max_x,
double* max_y);
94 void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level);
96 dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig> *
voxel_dsrv_;
104 inline bool worldToMap3DFloat(
double wx,
double wy,
double wz,
double& mx,
double& my,
double& mz)
117 inline bool worldToMap3D(
double wx,
double wy,
double wz,
unsigned int& mx,
unsigned int& my,
unsigned int& mz)
132 inline void mapToWorld3D(
unsigned int mx,
unsigned int my,
unsigned int mz,
double& wx,
double& wy,
double& wz)
140 inline double dist(
double x0,
double y0,
double z0,
double x1,
double y1,
double z1)
142 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
148 #endif // COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_
unsigned int mark_threshold_
dynamic_reconfigure::Server< costmap_2d::NonPersistentVoxelPluginConfig > * voxel_dsrv_
ros::Publisher voxel_pub_
voxel_grid::VoxelGrid voxel_grid_
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
virtual ~NonPersistentVoxelLayer()
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
unsigned int unknown_threshold_
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
void updateOrigin(double new_origin_x, double new_origin_y)
NonPersistentVoxelLayer()
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
virtual void onInitialize()
void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level)