32 #ifndef COSTMAP_2D_OBSERVATION_H_ 33 #define COSTMAP_2D_OBSERVATION_H_ 35 #include <geometry_msgs/Point.h> 36 #include <pcl/point_types.h> 37 #include <pcl/point_cloud.h> 70 Observation(geometry_msgs::Point& origin, pcl::PointCloud<pcl::PointXYZ> cloud,
71 double obstacle_range,
double raytrace_range) :
92 Observation(pcl::PointCloud<pcl::PointXYZ> cloud,
double obstacle_range) :
98 pcl::PointCloud<pcl::PointXYZ>*
cloud_;
103 #endif // COSTMAP_2D_OBSERVATION_H_ geometry_msgs::Point origin_
Observation()
Creates an empty observation.
pcl::PointCloud< pcl::PointXYZ > * cloud_
Stores an observation in terms of a point cloud and the origin of the source.
sensor_msgs::PointCloud2 PointCloud
Observation(const Observation &obs)
Copy constructor.
Observation(geometry_msgs::Point &origin, pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range, double raytrace_range)
Creates an observation from an origin point and a point cloud.
Observation(pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range)
Creates an observation from a point cloud.