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
00039 #ifndef PCL_RANGE_IMAGE_PLANAR_IMPL_HPP_
00040 #define PCL_RANGE_IMAGE_PLANAR_IMPL_HPP_
00041
00042 #include <pcl/pcl_macros.h>
00043 #include <pcl/common/eigen.h>
00044
00045 namespace pcl
00046 {
00047
00049 template <typename PointCloudType> void
00050 RangeImagePlanar::createFromPointCloudWithFixedSize (const PointCloudType& point_cloud,
00051 int di_width, int di_height,
00052 float di_center_x, float di_center_y,
00053 float di_focal_length_x, float di_focal_length_y,
00054 const Eigen::Affine3f& sensor_pose,
00055 CoordinateFrame coordinate_frame, float noise_level,
00056 float min_range)
00057 {
00058
00059
00060 width = di_width;
00061 height = di_height;
00062 center_x_ = di_center_x;
00063 center_y_ = di_center_y;
00064 focal_length_x_ = di_focal_length_x;
00065 focal_length_y_ = di_focal_length_y;
00066 focal_length_x_reciprocal_ = 1 / focal_length_x_;
00067 focal_length_y_reciprocal_ = 1 / focal_length_y_;
00068
00069 is_dense = false;
00070
00071 getCoordinateFrameTransformation (coordinate_frame, to_world_system_);
00072 to_world_system_ = sensor_pose * to_world_system_;
00073
00074 to_range_image_system_ = to_world_system_.inverse (Eigen::Isometry);
00075
00076 unsigned int size = width*height;
00077 points.clear ();
00078 points.resize (size, unobserved_point);
00079
00080 int top=height, right=-1, bottom=-1, left=width;
00081 doZBuffer (point_cloud, noise_level, min_range, top, right, bottom, left);
00082
00083
00084
00085
00086 recalculate3DPointPositions ();
00087 }
00088
00089
00091 void
00092 RangeImagePlanar::calculate3DPoint (float image_x, float image_y, float range, Eigen::Vector3f& point) const
00093 {
00094
00095 float delta_x = (image_x+static_cast<float> (image_offset_x_)-center_x_)*focal_length_x_reciprocal_,
00096 delta_y = (image_y+static_cast<float> (image_offset_y_)-center_y_)*focal_length_y_reciprocal_;
00097 point[2] = range / (sqrtf (delta_x*delta_x + delta_y*delta_y + 1));
00098 point[0] = delta_x*point[2];
00099 point[1] = delta_y*point[2];
00100 point = to_world_system_ * point;
00101 }
00102
00104 inline void
00105 RangeImagePlanar::getImagePoint (const Eigen::Vector3f& point, float& image_x, float& image_y, float& range) const
00106 {
00107 Eigen::Vector3f transformedPoint = to_range_image_system_ * point;
00108 if (transformedPoint[2]<=0)
00109 {
00110 image_x = image_y = range = -1.0f;
00111 return;
00112 }
00113 range = transformedPoint.norm ();
00114
00115 image_x = center_x_ + focal_length_x_*transformedPoint[0]/transformedPoint[2] - static_cast<float> (image_offset_x_);
00116 image_y = center_y_ + focal_length_y_*transformedPoint[1]/transformedPoint[2] - static_cast<float> (image_offset_y_);
00117 }
00118
00119 }
00120
00121 #endif
00122