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