40 #ifndef PCL_SURFACE_TEXTURE_MAPPING_H_ 41 #define PCL_SURFACE_TEXTURE_MAPPING_H_ 43 #include <pcl/surface/reconstruction.h> 44 #include <pcl/common/transforms.h> 45 #include <pcl/TextureMesh.h> 46 #include <pcl/octree/octree.h> 55 namespace texture_mapping
81 std::vector<double>
roi;
84 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
96 typedef std::vector<Camera, Eigen::aligned_allocator<Camera> >
CameraVector;
104 template<
typename Po
intInT>
116 typedef pcl::octree::OctreePointCloudSearch<PointInT>
Octree;
125 f_ (), vector_field_ (), tex_files_ (), tex_material_ (), max_distance_(0.0
f), max_depth_error_(0.0
f), max_angle_(0.0
f), min_cluster_size_(50)
151 vector_field_ = Eigen::Vector3f (x, y, z);
153 vector_field_ = vector_field_ /
std::sqrt (vector_field_.dot (vector_field_));
162 tex_files_ = tex_files;
171 tex_material_ = tex_material;
177 max_distance_ = maxDistance;
189 max_angle_ = maxAngle;
195 min_cluster_size_ = size;
202 mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
208 mapTexture2MeshUV (pcl::TextureMesh &tex_mesh);
217 mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh,
230 if (pt.z > 0 && (max_distance_ <= 0.0f || pt.z < max_distance_))
233 double sizeX = cam.
width;
234 double sizeY = cam.
height;
245 double focal_x, focal_y;
256 UV_coordinates[0] =
static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX);
257 UV_coordinates[1] = 1.0f -
static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY));
260 if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
266 UV_coordinates[0] = -1.0;
267 UV_coordinates[1] = -1.0;
277 isPointOccluded (
const PointInT &pt,
const OctreePtr
octree);
287 removeOccludedPoints (
const PointCloudPtr &input_cloud,
288 PointCloudPtr &filtered_cloud,
const double octree_voxel_size,
289 std::vector<int> &visible_indices, std::vector<int> &occluded_indices);
297 removeOccludedPoints (
const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh,
const double octree_voxel_size);
306 removeOccludedPoints (
const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud,
const double octree_voxel_size);
318 sortFacesByCamera (pcl::TextureMesh &tex_mesh,
319 pcl::TextureMesh &sorted_mesh,
321 const double octree_voxel_size, PointCloud &visible_pts);
334 showOcclusions (
const PointCloudPtr &input_cloud,
335 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
336 const double octree_voxel_size,
337 const bool show_nb_occlusions =
true,
338 const int max_occlusions = 4);
351 showOcclusions (pcl::TextureMesh &tex_mesh,
352 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
353 double octree_voxel_size,
354 bool show_nb_occlusions =
true,
355 int max_occlusions = 4);
364 textureMeshwithMultipleCameras (pcl::TextureMesh &mesh,
367 textureMeshwithMultipleCameras2 (pcl::TextureMesh &mesh,
370 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0,
371 bool distanceToCamPolicy =
false);
403 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >
404 mapTexture2Face (
const Eigen::Vector3f &p1,
const Eigen::Vector3f &p2,
const Eigen::Vector3f &p3);
415 getTriangleCircumcenterAndSize (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3, pcl::PointXY &circumcenter,
double &radius);
427 getTriangleCircumcscribedCircleCentroid (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3, pcl::PointXY &circumcenter,
double &radius);
437 getPointUVCoordinates (
const PointInT &pt,
const Camera &
cam, pcl::PointXY &UV_coordinates);
449 isFaceProjected (
const Camera &camera,
450 const PointInT &p1,
const PointInT &p2,
const PointInT &p3,
451 pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
461 checkPointInsideTriangle (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3,
const pcl::PointXY &pt);
467 return (
"TextureMapping");
471 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
boost::shared_ptr< const TextureMapping< PointInT > > ConstPtr
float max_distance_
maximum distance between camera and polygon to apply a texture
void setVectorField(float x, float y, float z)
Set vector field.
rtabmap::CameraThread * cam
void setTextureMaterials(TexMaterial tex_material)
Set texture materials.
std::vector< Camera, Eigen::aligned_allocator< Camera > > CameraVector
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
TextureMapping()
Constructor.
const float maxDepthError
The texture mapping algorithm.
float max_depth_error_
maximum depth error between projected point and corresponding depth of the camera to apply a texture ...
void setMinClusterSize(int size)
Some conversion functions.
pcl::octree::OctreePointCloudSearch< PointInT > Octree
std::vector< double > roi
void setTextureFiles(std::vector< std::string > tex_files)
Set texture files.
int min_cluster_size_
Remove texture from small polygon clusters.
Wrappers of STL for convenient functions.
Structure that links a uv coordinate to its 3D point and face.
Structure to store camera pose and focal length.
~TextureMapping()
Destructor.
Octree::ConstPtr OctreeConstPtr
pcl::PointCloud< PointInT > PointCloud
PointCloud::Ptr PointCloudPtr
void setMaxDepthError(float maxDepthError)
std::string getClassName() const
Class get name method.
float max_angle_
maximum angle (rad) between camera and polygon to apply a texture
float f_
mesh scale control.
TexMaterial tex_material_
list of texture materials
std::vector< std::string > tex_files_
list of texture files
ULogger class and convenient macros.
pcl::texture_mapping::Camera Camera
void setMaxAngle(float maxAngle)
Eigen::Vector3f vector_field_
vector field
bool getPointUVCoordinates(const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
computes UV coordinates of point, observed by one particular camera
void setMaxDistance(float maxDistance)
void setF(float f)
Set mesh scale control.
PointCloud::ConstPtr PointCloudConstPtr
pcl::texture_mapping::UvIndex UvIndex
boost::shared_ptr< TextureMapping< PointInT > > Ptr