obstacle_layer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef COSTMAP_2D_OBSTACLE_LAYER_H_
39 #define COSTMAP_2D_OBSTACLE_LAYER_H_
40 
41 #include <ros/ros.h>
45 
46 #include <nav_msgs/OccupancyGrid.h>
47 
48 #include <sensor_msgs/LaserScan.h>
50 #include <sensor_msgs/PointCloud.h>
51 #include <sensor_msgs/PointCloud2.h>
53 #include <tf/message_filter.h>
55 #include <dynamic_reconfigure/server.h>
56 #include <costmap_2d/ObstaclePluginConfig.h>
57 #include <costmap_2d/footprint.h>
58 
59 namespace costmap_2d
60 {
61 
63 {
64 public:
66  {
67  costmap_ = NULL; // this is the unsigned char* member of parent class Costmap2D.
68  }
69 
70  virtual ~ObstacleLayer();
71  virtual void onInitialize();
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);
74  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
75 
76  virtual void activate();
77  virtual void deactivate();
78  virtual void reset();
79 
85  void laserScanCallback(const sensor_msgs::LaserScanConstPtr& message,
87 
93  void laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr& message,
95 
101  void pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message,
103 
109  void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message,
111 
112  // for testing purposes
113  void addStaticObservation(costmap_2d::Observation& obs, bool marking, bool clearing);
114  void clearStaticObservations(bool marking, bool clearing);
115 
116 protected:
117  virtual void setupDynamicReconfigure(ros::NodeHandle& nh);
118 
124  bool getMarkingObservations(std::vector<costmap_2d::Observation>& marking_observations) const;
125 
131  bool getClearingObservations(std::vector<costmap_2d::Observation>& clearing_observations) const;
132 
141  virtual void raytraceFreespace(const costmap_2d::Observation& clearing_observation, double* min_x, double* min_y,
142  double* max_x, double* max_y);
143 
144  void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double* min_x, double* min_y,
145  double* max_x, double* max_y);
146 
147  std::vector<geometry_msgs::Point> transformed_footprint_;
149  void updateFootprint(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
150  double* max_x, double* max_y);
151 
152  std::string global_frame_;
154 
156 
157  std::vector<boost::shared_ptr<message_filters::SubscriberBase> > observation_subscribers_;
158  std::vector<boost::shared_ptr<tf::MessageFilterBase> > observation_notifiers_;
159  std::vector<boost::shared_ptr<costmap_2d::ObservationBuffer> > observation_buffers_;
160  std::vector<boost::shared_ptr<costmap_2d::ObservationBuffer> > marking_buffers_;
161  std::vector<boost::shared_ptr<costmap_2d::ObservationBuffer> > clearing_buffers_;
162 
163  // Used only for testing purposes
164  std::vector<costmap_2d::Observation> static_clearing_observations_, static_marking_observations_;
165 
167  dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig> *dsrv_;
168 
170 
171 private:
172  void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level);
173 };
174 
175 } // namespace costmap_2d
176 
177 #endif // COSTMAP_2D_OBSTACLE_LAYER_H_
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_...
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
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().
virtual void deactivate()
Stop publishers.
std::vector< costmap_2d::Observation > static_clearing_observations_
void clearStaticObservations(bool marking, bool clearing)
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
std::vector< geometry_msgs::Point > transformed_footprint_
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_marking_observations_
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:47
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...
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
double max_obstacle_height_
Max Obstacle Height.
virtual void activate()
Restart publishers if they&#39;ve been stopped.
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
Used for the observation message filters.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
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::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:60
unsigned char * costmap_
Definition: costmap_2d.h:426
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.
std::string global_frame_
The global frame for the costmap.
void pointCloudCallback(const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud messages.
std::vector< boost::shared_ptr< tf::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:17