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