Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef COSTMAP_OBSERVATION_H_
00033 #define COSTMAP_OBSERVATION_H_
00034
00035 #include <geometry_msgs/Point.h>
00036 #include <pcl/point_types.h>
00037 #include <pcl/point_cloud.h>
00038
00039 namespace costmap_2d
00040 {
00041
00047 class Observation
00048 {
00049 public:
00053 Observation() :
00054 cloud_(new pcl::PointCloud<pcl::PointXYZ>()), obstacle_range_(0.0), raytrace_range_(0.0)
00055 {
00056 }
00057
00058 virtual ~Observation()
00059 {
00060 delete cloud_;
00061 }
00062
00070 Observation(geometry_msgs::Point& origin, pcl::PointCloud<pcl::PointXYZ> cloud, double obstacle_range,
00071 double raytrace_range) :
00072 origin_(origin), cloud_(new pcl::PointCloud<pcl::PointXYZ>(cloud)), obstacle_range_(obstacle_range), raytrace_range_(raytrace_range)
00073 {
00074 }
00075
00080 Observation(const Observation& obs) :
00081 origin_(obs.origin_), cloud_(new pcl::PointCloud<pcl::PointXYZ>(*(obs.cloud_))), obstacle_range_(obs.obstacle_range_), raytrace_range_(
00082 obs.raytrace_range_)
00083 {
00084 }
00085
00091 Observation(pcl::PointCloud<pcl::PointXYZ> cloud, double obstacle_range) :
00092 cloud_(new pcl::PointCloud<pcl::PointXYZ>(cloud)), obstacle_range_(obstacle_range), raytrace_range_(0.0)
00093 {
00094 }
00095
00096 geometry_msgs::Point origin_;
00097 pcl::PointCloud<pcl::PointXYZ>* cloud_;
00098 double obstacle_range_, raytrace_range_;
00099 };
00100
00101 }
00102 #endif
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55