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> 54 namespace texture_mapping
80 std::vector<double>
roi;
83 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
95 typedef std::vector<Camera, Eigen::aligned_allocator<Camera> >
CameraVector;
103 template<
typename Po
intInT>
115 typedef pcl::octree::OctreePointCloudSearch<PointInT>
Octree;
124 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)
150 vector_field_ = Eigen::Vector3f (x, y, z);
152 vector_field_ = vector_field_ /
std::sqrt (vector_field_.dot (vector_field_));
161 tex_files_ = tex_files;
170 tex_material_ = tex_material;
176 max_distance_ = maxDistance;
188 max_angle_ = maxAngle;
194 min_cluster_size_ = size;
201 mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
207 mapTexture2MeshUV (pcl::TextureMesh &tex_mesh);
216 mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh,
229 if (pt.z > 0 && (max_distance_ <= 0.0f || pt.z < max_distance_))
232 double sizeX = cam.
width;
233 double sizeY = cam.
height;
244 double focal_x, focal_y;
255 UV_coordinates[0] =
static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX);
256 UV_coordinates[1] = 1.0f -
static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY));
259 if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
265 UV_coordinates[0] = -1.0;
266 UV_coordinates[1] = -1.0;
276 isPointOccluded (
const PointInT &pt,
const OctreePtr octree);
286 removeOccludedPoints (
const PointCloudPtr &input_cloud,
287 PointCloudPtr &filtered_cloud,
const double octree_voxel_size,
288 std::vector<int> &visible_indices, std::vector<int> &occluded_indices);
296 removeOccludedPoints (
const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh,
const double octree_voxel_size);
305 removeOccludedPoints (
const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud,
const double octree_voxel_size);
317 sortFacesByCamera (pcl::TextureMesh &tex_mesh,
318 pcl::TextureMesh &sorted_mesh,
320 const double octree_voxel_size, PointCloud &visible_pts);
333 showOcclusions (
const PointCloudPtr &input_cloud,
334 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
335 const double octree_voxel_size,
336 const bool show_nb_occlusions =
true,
337 const int max_occlusions = 4);
350 showOcclusions (pcl::TextureMesh &tex_mesh,
351 pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
352 double octree_voxel_size,
353 bool show_nb_occlusions =
true,
354 int max_occlusions = 4);
363 textureMeshwithMultipleCameras (pcl::TextureMesh &mesh,
366 textureMeshwithMultipleCameras2 (pcl::TextureMesh &mesh,
369 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
401 std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >
402 mapTexture2Face (
const Eigen::Vector3f &p1,
const Eigen::Vector3f &p2,
const Eigen::Vector3f &p3);
413 getTriangleCircumcenterAndSize (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3, pcl::PointXY &circumcenter,
double &radius);
425 getTriangleCircumcscribedCircleCentroid (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3, pcl::PointXY &circumcenter,
double &radius);
435 getPointUVCoordinates (
const PointInT &pt,
const Camera &
cam, pcl::PointXY &UV_coordinates);
447 isFaceProjected (
const Camera &camera,
448 const PointInT &p1,
const PointInT &p2,
const PointInT &p3,
449 pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
459 checkPointInsideTriangle (
const pcl::PointXY &p1,
const pcl::PointXY &p2,
const pcl::PointXY &p3,
const pcl::PointXY &pt);
465 return (
"TextureMapping");
469 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)
float max_angle_
maximum angle (rad) between camera and polygon to apply a texture
std::string getClassName() const
Class get name method.
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