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
00033
00034
00035
00036
00037
00038 #ifndef PCL_RANGE_IMAGE_PLANAR_H_
00039 #define PCL_RANGE_IMAGE_PLANAR_H_
00040
00041 #include <pcl/range_image/range_image.h>
00042
00043 namespace pcl
00044 {
00052 class RangeImagePlanar : public RangeImage
00053 {
00054 public:
00055
00056 typedef RangeImage BaseClass;
00057 typedef boost::shared_ptr<RangeImagePlanar> Ptr;
00058 typedef boost::shared_ptr<const RangeImagePlanar> ConstPtr;
00059
00060
00062 PCL_EXPORTS RangeImagePlanar ();
00064 PCL_EXPORTS virtual ~RangeImagePlanar ();
00065
00068 virtual RangeImage*
00069 getNew () const { return new RangeImagePlanar; }
00070
00072 PCL_EXPORTS virtual void
00073 copyTo (RangeImage& other) const;
00074
00075
00077 inline Ptr
00078 makeShared () { return Ptr (new RangeImagePlanar (*this)); }
00079
00090 PCL_EXPORTS void
00091 setDisparityImage (const float* disparity_image, int di_width, int di_height,
00092 float focal_length, float base_line, float desired_angular_resolution=-1);
00093
00106 PCL_EXPORTS void
00107 setDepthImage (const float* depth_image, int di_width, int di_height, float di_center_x, float di_center_y,
00108 float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1);
00109
00122 PCL_EXPORTS void
00123 setDepthImage (const unsigned short* depth_image, int di_width, int di_height, float di_center_x, float di_center_y,
00124 float di_focal_length_x, float di_focal_length_y, float desired_angular_resolution=-1);
00125
00139 template <typename PointCloudType> void
00140 createFromPointCloudWithFixedSize (const PointCloudType& point_cloud,
00141 int di_width, int di_height, float di_center_x, float di_center_y,
00142 float di_focal_length_x, float di_focal_length_y,
00143 const Eigen::Affine3f& sensor_pose,
00144 CoordinateFrame coordinate_frame=CAMERA_FRAME, float noise_level=0.0f,
00145 float min_range=0.0f);
00146
00147
00148 using RangeImage::calculate3DPoint;
00149 using RangeImage::getImagePoint;
00150
00158 virtual inline void
00159 calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const;
00160
00168 virtual inline void
00169 getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const;
00170
00184 PCL_EXPORTS virtual void
00185 getSubImage (int sub_image_image_offset_x, int sub_image_image_offset_y, int sub_image_width,
00186 int sub_image_height, int combine_pixels, RangeImage& sub_image) const;
00187
00189 PCL_EXPORTS virtual void
00190 getHalfImage (RangeImage& half_image) const;
00191
00193 inline float
00194 getFocalLengthX () const { return focal_length_x_; }
00195
00197 inline float
00198 getFocalLengthY () const { return focal_length_y_; }
00199
00201 inline float
00202 getCenterX () const { return center_x_; }
00203
00205 inline float
00206 getCenterY () const { return center_y_; }
00207
00208
00209 protected:
00210 float focal_length_x_, focal_length_y_;
00211 float focal_length_x_reciprocal_, focal_length_y_reciprocal_;
00212 float center_x_, center_y_;
00213 };
00214 }
00215
00216
00217 #include <pcl/range_image/impl/range_image_planar.hpp>
00218
00219 #endif //#ifndef PCL_RANGE_IMAGE_H_