Go to the documentation of this file.
   38 #ifndef COSTMAP_2D_VOXEL_LAYER_H_ 
   39 #define COSTMAP_2D_VOXEL_LAYER_H_ 
   45 #include <costmap_2d/VoxelGrid.h> 
   46 #include <nav_msgs/OccupancyGrid.h> 
   47 #include <sensor_msgs/LaserScan.h> 
   49 #include <sensor_msgs/PointCloud.h> 
   50 #include <sensor_msgs/PointCloud2.h> 
   53 #include <dynamic_reconfigure/server.h> 
   54 #include <costmap_2d/VoxelPluginConfig.h> 
   61 class VoxelLayer : 
public ObstacleLayer
 
   73   virtual void updateBounds(
double robot_x, 
double robot_y, 
double robot_yaw, 
double* min_x, 
double* min_y,
 
   74                             double* max_x, 
double* max_y);
 
   76   void updateOrigin(
double new_origin_x, 
double new_origin_y);
 
   91   void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level);
 
   92   void clearNonLethal(
double wx, 
double wy, 
double w_size_x, 
double w_size_y, 
bool clear_no_info);
 
   94                                  double* max_x, 
double* max_y);
 
   96   dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig> *
voxel_dsrv_;
 
  106   inline bool worldToMap3DFloat(
double wx, 
double wy, 
double wz, 
double& mx, 
double& my, 
double& mz)
 
  119   inline bool worldToMap3D(
double wx, 
double wy, 
double wz, 
unsigned int& mx, 
unsigned int& my, 
unsigned int& mz)
 
  134   inline void mapToWorld3D(
unsigned int mx, 
unsigned int my, 
unsigned int mz, 
double& wx, 
double& wy, 
double& wz)
 
  142   inline double dist(
double x0, 
double y0, 
double z0, 
double x1, 
double y1, 
double z1)
 
  144     return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
 
  150 #endif  // COSTMAP_2D_VOXEL_LAYER_H_ 
  
void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
 
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
 
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
 
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
 
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
 
voxel_grid::VoxelGrid voxel_grid_
 
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
 
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
 
ros::Publisher voxel_pub_
 
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
 
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
 
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * voxel_dsrv_
 
unsigned int unknown_threshold_
 
ros::Publisher clearing_endpoints_pub_
 
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
 
Stores an observation in terms of a point cloud and the origin of the source.
 
sensor_msgs::PointCloud clearing_endpoints_
 
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
 
void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
 
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
 
unsigned int mark_threshold_
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17