3 #ifndef __YARP_CLOUD_UTILS_HPP__
4 #define __YARP_CLOUD_UTILS_HPP__
8 #include <yarp/os/Property.h>
9 #include <yarp/os/Searchable.h>
11 #include <yarp/sig/PointCloud.h>
12 #include <yarp/sig/Vector.h>
30 namespace YarpCloudUtils
45 bool savePLY(
const std::string & filename,
const yarp::sig::PointCloud<T> & cloud,
const yarp::sig::VectorOf<int> & indices,
bool isBinary =
true);
58 bool savePLY(
const std::string & filename,
const yarp::sig::PointCloud<T> & cloud,
bool isBinary =
true)
60 return savePLY(filename, cloud, {}, isBinary);
77 bool loadPLY(
const std::string & filename, yarp::sig::PointCloud<T> & cloud, yarp::sig::VectorOf<int> & indices);
92 bool loadPLY(
const std::string & filename, yarp::sig::PointCloud<T> & cloud)
94 yarp::sig::VectorOf<int> indices;
95 return loadPLY(filename, cloud, indices);
112 template <
typename T1,
typename T2 = T1>
114 yarp::sig::PointCloud<T2> & meshPoints,
115 yarp::sig::VectorOf<int> & meshIndices,
116 const yarp::sig::VectorOf<yarp::os::Property> & options);
133 template <
typename T1,
typename T2 = T1>
135 yarp::sig::PointCloud<T2> & meshPoints,
136 yarp::sig::VectorOf<int> & meshIndices,
137 const yarp::os::Searchable & config,
138 const std::string & collection =
"meshPipeline");
154 template <
typename T1,
typename T2 = T1>
156 yarp::sig::PointCloud<T2> & out,
157 const yarp::sig::VectorOf<yarp::os::Property> & options);
174 template <
typename T1,
typename T2 = T1>
176 yarp::sig::PointCloud<T2> & out,
177 const yarp::os::Searchable & config,
178 const std::string & collection =
"cloudPipeline");
bool meshFromCloud(const yarp::sig::PointCloud< T1 > &cloud, yarp::sig::PointCloud< T2 > &meshPoints, yarp::sig::VectorOf< int > &meshIndices, const yarp::sig::VectorOf< yarp::os::Property > &options)
Constructs a triangular polygon mesh from a point cloud.
Definition: YarpCloudUtils-pcl.cpp:286
bool loadPLY(const std::string &filename, yarp::sig::PointCloud< T > &cloud, yarp::sig::VectorOf< int > &indices)
Reads a triangular polygon mesh from file.
Definition: YarpCloudUtils-ply-import.cpp:523
bool processCloud(const yarp::sig::PointCloud< T1 > &in, yarp::sig::PointCloud< T2 > &out, const yarp::sig::VectorOf< yarp::os::Property > &options)
Processes a cloud of points.
Definition: YarpCloudUtils-pcl.cpp:363
bool savePLY(const std::string &filename, const yarp::sig::PointCloud< T > &cloud, const yarp::sig::VectorOf< int > &indices, bool isBinary)
Writes a triangular polygon mesh to file.
Definition: YarpCloudUtils-ply-export.cpp:368
The main, catch-all namespace for Robotics Lab UC3M.
Definition: groups.dox:5