6#include "reusex/types.hpp"
7#include "reusex/core/SensorIntrinsics.hpp"
9#include <pcl/PolygonMesh.h>
10#include <pcl/TextureMesh.h>
11#include <rtabmap/core/DBDriver.h>
12#include <opencv2/core/mat.hpp>
31 std::map<int, rtabmap::Transform>
const &poses,
32 std::map<int, rtabmap::Signature>
const &nodes);
37 std::map<int, CameraData>
const &cameras);
pcl::PolygonMeshPtr mesh(CloudConstPtr cloud, CloudNConstPtr normals, EigenVectorContainer< double, 4 > &planes, EigenVectorContainer< double, 3 > ¢roids, std::vector< IndicesPtr > &inliers, CloudLConstPtr rooms, MeshOptions const opt=MeshOptions{})
Generate a mesh from point cloud and geometric primitives.
pcl::TextureMesh::Ptr texture_mesh_with_cloud(pcl::PolygonMesh::Ptr mesh, CloudConstPtr cloud)
pcl::TextureMesh::Ptr texture_mesh(pcl::PolygonMesh::Ptr mesh, std::map< int, rtabmap::Transform > const &poses, std::map< int, rtabmap::Signature > const &nodes)
Texture mesh using RTABMap signatures (legacy API).
typename Cloud::ConstPtr CloudConstPtr
Lightweight camera intrinsics replacing rtabmap::CameraModel in downstream code.
Camera data for texture mapping.
core::SensorIntrinsics intrinsics
Camera intrinsics.
Eigen::Matrix4d pose
World pose (SE(3)).
cv::Mat image
Color image.