32 #ifndef COSTMAP_2D_OBSERVATION_H_ 
   33 #define COSTMAP_2D_OBSERVATION_H_ 
   35 #include <geometry_msgs/Point.h> 
   36 #include <sensor_msgs/PointCloud2.h> 
   69   Observation(geometry_msgs::Point& origin, 
const sensor_msgs::PointCloud2 &cloud,
 
   70               double obstacle_range, 
double raytrace_range) :
 
   91   Observation(
const sensor_msgs::PointCloud2 &cloud, 
double obstacle_range) :
 
  102 #endif  // COSTMAP_2D_OBSERVATION_H_