vision
|
Collection of cloud-related utilities for YARP. More...
Functions | |
template<typename T > | |
bool | roboticslab::YarpCloudUtils::savePLY (const std::string &filename, const yarp::sig::PointCloud< T > &cloud, const yarp::sig::VectorOf< int > &indices, bool isBinary=true) |
Writes a triangular polygon mesh to file. More... | |
template<typename T > | |
bool | roboticslab::YarpCloudUtils::savePLY (const std::string &filename, const yarp::sig::PointCloud< T > &cloud, bool isBinary=true) |
Writes a point cloud to file. More... | |
template<typename T > | |
bool | roboticslab::YarpCloudUtils::loadPLY (const std::string &filename, yarp::sig::PointCloud< T > &cloud, yarp::sig::VectorOf< int > &indices) |
Reads a triangular polygon mesh from file. More... | |
template<typename T > | |
bool | roboticslab::YarpCloudUtils::loadPLY (const std::string &filename, yarp::sig::PointCloud< T > &cloud) |
Reads a point cloud from file. More... | |
template<typename T1 , typename T2 > | |
bool | roboticslab::YarpCloudUtils::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. More... | |
template<typename T1 , typename T2 > | |
bool | roboticslab::YarpCloudUtils::meshFromCloud (const yarp::sig::PointCloud< T1 > &cloud, yarp::sig::PointCloud< T2 > &meshPoints, yarp::sig::VectorOf< int > &meshIndices, const yarp::os::Searchable &config, const std::string &collection="meshPipeline") |
Constructs a triangular polygon mesh from a point cloud. More... | |
template<typename T1 , typename T2 > | |
bool | roboticslab::YarpCloudUtils::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. More... | |
template<typename T1 , typename T2 > | |
bool | roboticslab::YarpCloudUtils::processCloud (const yarp::sig::PointCloud< T1 > &in, yarp::sig::PointCloud< T2 > &out, const yarp::os::Searchable &config, const std::string &collection="cloudPipeline") |
Processes a cloud of points. More... | |
bool roboticslab::YarpCloudUtils::loadPLY | ( | const std::string & | filename, |
yarp::sig::PointCloud< T > & | cloud | ||
) |
alpha
(RGBA types) and curvature
(normal types).filename | Path to a file with .ply extension. |
cloud | Cloud of vertices. |
bool roboticslab::YarpCloudUtils::loadPLY | ( | const std::string & | filename, |
yarp::sig::PointCloud< T > & | cloud, | ||
yarp::sig::VectorOf< int > & | indices | ||
) |
alpha
(RGBA types) and curvature
(normal types).filename | Path to a file with .ply extension. |
cloud | Cloud of vertices. |
indices | Vector of indices, each three consecutive values define a face. |
bool roboticslab::YarpCloudUtils::meshFromCloud | ( | const yarp::sig::PointCloud< T1 > & | cloud, |
yarp::sig::PointCloud< T2 > & | meshPoints, | ||
yarp::sig::VectorOf< int > & | meshIndices, | ||
const yarp::os::Searchable & | config, | ||
const std::string & | collection = "meshPipeline" |
||
) |
cloud | Input cloud. |
meshPoints | Cloud of vertices of the resulting polygon mesh. |
meshIndices | Vector if indices of the resulting polygon mesh, each three consecutive values define a face. |
config | Configuration in YARP native format to read the pipeline from. |
collection | Named section collection that identifies this pipeline in config . |
bool roboticslab::YarpCloudUtils::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 | ||
) |
cloud | Input cloud. |
meshPoints | Cloud of vertices of the resulting polygon mesh. |
meshIndices | Vector if indices of the resulting polygon mesh, each three consecutive values define a face. |
options | Vector of dictionaries, each element defines a step of the pipeline. |
bool roboticslab::YarpCloudUtils::processCloud | ( | const yarp::sig::PointCloud< T1 > & | in, |
yarp::sig::PointCloud< T2 > & | out, | ||
const yarp::os::Searchable & | config, | ||
const std::string & | collection = "cloudPipeline" |
||
) |
cloud | Input cloud. |
meshPoints | Cloud of vertices of the resulting polygon mesh. |
meshIndices | Vector if indices of the resulting polygon mesh, each three consecutive values define a face. |
config | Configuration in YARP native format to read the pipeline from. |
collection | Named section collection that identifies this pipeline in config . |
bool roboticslab::YarpCloudUtils::processCloud | ( | const yarp::sig::PointCloud< T1 > & | in, |
yarp::sig::PointCloud< T2 > & | out, | ||
const yarp::sig::VectorOf< yarp::os::Property > & | options | ||
) |
cloud | Input cloud. |
meshPoints | Cloud of vertices of the resulting polygon mesh. |
meshIndices | Vector if indices of the resulting polygon mesh, each three consecutive values define a face. |
options | Vector of dictionaries, each element defines a step of the pipeline. |
bool roboticslab::YarpCloudUtils::savePLY | ( | const std::string & | filename, |
const yarp::sig::PointCloud< T > & | cloud, | ||
bool | isBinary = true |
||
) |
filename | Path to a file with .ply extension. |
cloud | Cloud of points. |
isBinary | Whether to save file with binary format or not. |
bool roboticslab::YarpCloudUtils::savePLY | ( | const std::string & | filename, |
const yarp::sig::PointCloud< T > & | cloud, | ||
const yarp::sig::VectorOf< int > & | indices, | ||
bool | isBinary = true |
||
) |
filename | Path to a file with .ply extension. |
cloud | Cloud of vertices. |
indices | Vector of indices, each three consecutive values define a face. |
isBinary | Whether to save file with binary format or not. |