19 #ifndef LOCALIZATION_MEASUREMENTS_DEPTH_IMAGE_H_ 
   20 #define LOCALIZATION_MEASUREMENTS_DEPTH_IMAGE_H_ 
   24 #include <boost/optional.hpp> 
   26 #include <opencv2/core.hpp> 
   28 #include <pcl/point_cloud.h> 
   29 #include <pcl/point_types.h> 
   34   DepthImage(
const cv::Mat& 
image, 
const pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud);
 
   37   boost::optional<const pcl::PointXYZI&> 
UnfilteredPoint3D(
const int col, 
const int row) 
const;
 
   38   boost::optional<const pcl::PointXYZI&> 
UnfilteredPoint3D(
const double col, 
const double row) 
const;
 
   39   boost::optional<pcl::PointXYZI> 
InterpolatePoint3D(
const double col, 
const double row) 
const;
 
   40   const cv::Mat& 
image()
 const { 
return image_; }
 
   44   static bool ValidPoint(
const boost::optional<const pcl::PointXYZI&> point);
 
   47   pcl::PointCloud<pcl::PointXYZI>::Ptr unfiltered_point_cloud_;
 
   51 #endif  // LOCALIZATION_MEASUREMENTS_DEPTH_IMAGE_H_