Go to the documentation of this file.
   38 #ifndef COSTMAP_2D_OBSTACLE_LAYER_H_ 
   39 #define COSTMAP_2D_OBSTACLE_LAYER_H_ 
   46 #include <nav_msgs/OccupancyGrid.h> 
   48 #include <sensor_msgs/LaserScan.h> 
   49 #include <laser_geometry/laser_geometry.h> 
   50 #include <sensor_msgs/PointCloud.h> 
   51 #include <sensor_msgs/PointCloud2.h> 
   52 #include <sensor_msgs/point_cloud_conversion.h> 
   53 #include <tf2_ros/message_filter.h> 
   54 #include <message_filters/subscriber.h> 
   55 #include <dynamic_reconfigure/server.h> 
   56 #include <costmap_2d/ObstaclePluginConfig.h> 
   62 class ObstacleLayer : 
public CostmapLayer
 
   72   virtual void updateBounds(
double robot_x, 
double robot_y, 
double robot_yaw, 
double* min_x, 
double* min_y,
 
   73                             double* max_x, 
double* max_y);
 
   86                          const boost::shared_ptr<costmap_2d::ObservationBuffer>& buffer);
 
   94                                  const boost::shared_ptr<ObservationBuffer>& buffer);
 
  102                           const boost::shared_ptr<costmap_2d::ObservationBuffer>& buffer);
 
  110                            const boost::shared_ptr<costmap_2d::ObservationBuffer>& buffer);
 
  118   void checkTimeStamps(
double* min_x, 
double* min_y, 
double* max_x, 
double* max_y);
 
  147                                  double* max_x, 
double* max_y);
 
  149   void updateRaytraceBounds(
double ox, 
double oy, 
double wx, 
double wy, 
double range, 
double* min_x, 
double* min_y,
 
  150                             double* max_x, 
double* max_y);
 
  154   void updateFootprint(
double robot_x, 
double robot_y, 
double robot_yaw, 
double* min_x, 
double* min_y, 
 
  155                        double* max_x, 
double* max_y);
 
  172   dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig> *
dsrv_;
 
  177   void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level);
 
  182 #endif  // COSTMAP_2D_OBSTACLE_LAYER_H_ 
  
virtual void deactivate()
Stop publishers.
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
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.
std::string global_frame_
The global frame for the costmap.
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
std::vector< costmap_2d::Observation > static_clearing_observations_
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
double occupied_to_default_time_
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...
std::vector< costmap_2d::Observation > static_marking_observations_
void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
std::vector< boost::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
A 2D costmap provides a mapping between points in the world and their associated "costs".
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
double free_to_default_time_
double max_obstacle_height_
Max Obstacle Height.
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
Used for the observation message filters.
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
virtual void activate()
Restart publishers if they've been stopped.
std::vector< geometry_msgs::Point > transformed_footprint_
void checkTimeStamps(double *min_x, double *min_y, double *max_x, double *max_y)
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Stores an observation in terms of a point cloud and the origin of the source.
void laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
void pointCloudCallback(const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud messages.
void clearStaticObservations(bool marking, bool clearing)
bool footprint_clearing_enabled_
void laserScanCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.