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
00040 #ifndef PCL_SURFACE_TEXTURE_MAPPING_H_
00041 #define PCL_SURFACE_TEXTURE_MAPPING_H_
00042
00043 #include <pcl/surface/reconstruction.h>
00044 #include <pcl/common/transforms.h>
00045 #include <pcl/TextureMesh.h>
00046 #include <rtabmap/core/ProgressState.h>
00047 #include <rtabmap/utilite/ULogger.h>
00048 #include <rtabmap/utilite/UStl.h>
00049 #include <rtabmap/utilite/UConversion.h>
00050
00051
00052 namespace pcl
00053 {
00054 namespace texture_mapping
00055 {
00056
00067 struct Camera
00068 {
00069 Camera () : pose (), focal_length (), focal_length_w (-1), focal_length_h (-1),
00070 center_w (-1), center_h (-1), height (), width (), texture_file () {}
00071 Eigen::Affine3f pose;
00072 double focal_length;
00073 double focal_length_w;
00074 double focal_length_h;
00075 double center_w;
00076 double center_h;
00077 double height;
00078 double width;
00079 std::string texture_file;
00080 std::vector<double> roi;
00081 cv::Mat depth;
00082
00083 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00084 };
00085
00088 struct UvIndex
00089 {
00090 UvIndex () : idx_cloud (), idx_face () {}
00091 int idx_cloud;
00092 int idx_face;
00093 };
00094
00095 typedef std::vector<Camera, Eigen::aligned_allocator<Camera> > CameraVector;
00096
00097 }
00098
00103 template<typename PointInT>
00104 class TextureMapping
00105 {
00106 public:
00107
00108 typedef boost::shared_ptr< TextureMapping < PointInT > > Ptr;
00109 typedef boost::shared_ptr< const TextureMapping < PointInT > > ConstPtr;
00110
00111 typedef pcl::PointCloud<PointInT> PointCloud;
00112 typedef typename PointCloud::Ptr PointCloudPtr;
00113 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00114
00115 typedef pcl::octree::OctreePointCloudSearch<PointInT> Octree;
00116 typedef typename Octree::Ptr OctreePtr;
00117 typedef typename Octree::ConstPtr OctreeConstPtr;
00118
00119 typedef pcl::texture_mapping::Camera Camera;
00120 typedef pcl::texture_mapping::UvIndex UvIndex;
00121
00123 TextureMapping () :
00124 f_ (), vector_field_ (), tex_files_ (), tex_material_ (), max_distance_(0.0f), max_depth_error_(0.0f), max_angle_(0.0f), min_cluster_size_(50)
00125 {
00126 }
00127
00129 ~TextureMapping ()
00130 {
00131 }
00132
00136 inline void
00137 setF (float f)
00138 {
00139 f_ = f;
00140 }
00141
00147 inline void
00148 setVectorField (float x, float y, float z)
00149 {
00150 vector_field_ = Eigen::Vector3f (x, y, z);
00151
00152 vector_field_ = vector_field_ / std::sqrt (vector_field_.dot (vector_field_));
00153 }
00154
00158 inline void
00159 setTextureFiles (std::vector<std::string> tex_files)
00160 {
00161 tex_files_ = tex_files;
00162 }
00163
00167 inline void
00168 setTextureMaterials (TexMaterial tex_material)
00169 {
00170 tex_material_ = tex_material;
00171 }
00172
00173 inline void
00174 setMaxDistance(float maxDistance)
00175 {
00176 max_distance_ = maxDistance;
00177 }
00178
00179 inline void
00180 setMaxDepthError(float maxDepthError)
00181 {
00182 max_depth_error_ = maxDepthError;
00183 }
00184
00185 inline void
00186 setMaxAngle(float maxAngle)
00187 {
00188 max_angle_ = maxAngle;
00189 }
00190
00191 inline void
00192 setMinClusterSize(int size)
00193 {
00194 min_cluster_size_ = size;
00195 }
00196
00200 void
00201 mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
00202
00206 void
00207 mapTexture2MeshUV (pcl::TextureMesh &tex_mesh);
00208
00215 void
00216 mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh,
00217 pcl::texture_mapping::CameraVector &cams);
00218
00225 inline bool
00226 getPointUVCoordinates (const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
00227 {
00228
00229 if (pt.z > 0 && (max_distance_ <= 0.0f || pt.z < max_distance_))
00230 {
00231
00232 double sizeX = cam.width;
00233 double sizeY = cam.height;
00234 double cx, cy;
00235 if (cam.center_w > 0)
00236 cx = cam.center_w;
00237 else
00238 cx = (sizeX) / 2.0;
00239 if (cam.center_h > 0)
00240 cy = cam.center_h;
00241 else
00242 cy = (sizeY) / 2.0;
00243
00244 double focal_x, focal_y;
00245 if (cam.focal_length_w > 0)
00246 focal_x = cam.focal_length_w;
00247 else
00248 focal_x = cam.focal_length;
00249 if (cam.focal_length_h>0)
00250 focal_y = cam.focal_length_h;
00251 else
00252 focal_y = cam.focal_length;
00253
00254
00255 UV_coordinates[0] = static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX);
00256 UV_coordinates[1] = 1.0f - static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY));
00257
00258
00259 if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
00260 <= 1.0)
00261 return (true);
00262 }
00263
00264
00265 UV_coordinates[0] = -1.0;
00266 UV_coordinates[1] = -1.0;
00267 return (false);
00268 }
00269
00275 inline bool
00276 isPointOccluded (const PointInT &pt, const OctreePtr octree);
00277
00285 void
00286 removeOccludedPoints (const PointCloudPtr &input_cloud,
00287 PointCloudPtr &filtered_cloud, const double octree_voxel_size,
00288 std::vector<int> &visible_indices, std::vector<int> &occluded_indices);
00289
00295 void
00296 removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size);
00297
00298
00304 void
00305 removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size);
00306
00307
00316 int
00317 sortFacesByCamera (pcl::TextureMesh &tex_mesh,
00318 pcl::TextureMesh &sorted_mesh,
00319 const pcl::texture_mapping::CameraVector &cameras,
00320 const double octree_voxel_size, PointCloud &visible_pts);
00321
00332 void
00333 showOcclusions (const PointCloudPtr &input_cloud,
00334 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00335 const double octree_voxel_size,
00336 const bool show_nb_occlusions = true,
00337 const int max_occlusions = 4);
00338
00349 void
00350 showOcclusions (pcl::TextureMesh &tex_mesh,
00351 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00352 double octree_voxel_size,
00353 bool show_nb_occlusions = true,
00354 int max_occlusions = 4);
00355
00362 void
00363 textureMeshwithMultipleCameras (pcl::TextureMesh &mesh,
00364 const pcl::texture_mapping::CameraVector &cameras);
00365 bool
00366 textureMeshwithMultipleCameras2 (pcl::TextureMesh &mesh,
00367 const pcl::texture_mapping::CameraVector &cameras,
00368 const rtabmap::ProgressState * callback = 0,
00369 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
00370
00371 protected:
00373 float f_;
00374
00376 Eigen::Vector3f vector_field_;
00377
00379 std::vector<std::string> tex_files_;
00380
00382 TexMaterial tex_material_;
00383
00385 float max_distance_;
00386
00388 float max_depth_error_;
00389
00391 float max_angle_;
00392
00394 int min_cluster_size_;
00395
00401 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >
00402 mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3);
00403
00412 inline void
00413 getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
00414
00415
00424 inline void
00425 getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
00426
00427
00434 inline bool
00435 getPointUVCoordinates (const PointInT &pt, const Camera &cam, pcl::PointXY &UV_coordinates);
00436
00446 inline bool
00447 isFaceProjected (const Camera &camera,
00448 const PointInT &p1, const PointInT &p2, const PointInT &p3,
00449 pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
00450
00458 inline bool
00459 checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt);
00460
00462 std::string
00463 getClassName () const
00464 {
00465 return ("TextureMapping");
00466 }
00467
00468 public:
00469 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00470 };
00471 }
00472
00473 #include <pcl18/surface/impl/texture_mapping.hpp>
00474
00475 #endif
00476