vision
Functions
YarpCloudUtils

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...
 

Detailed Description

See also
Instructions.
[1]

Function Documentation

◆ loadPLY() [1/2]

template<typename T >
bool roboticslab::YarpCloudUtils::loadPLY ( const std::string &  filename,
yarp::sig::PointCloud< T > &  cloud 
)
Note
Failure is reported if required fields are missing, depending on the requested point type. Optional fields are alpha (RGBA types) and curvature (normal types).
Parameters
filenamePath to a file with .ply extension.
cloudCloud of vertices.
Returns
Whether the cloud has been successfully imported or not.

◆ loadPLY() [2/2]

template<typename T >
bool roboticslab::YarpCloudUtils::loadPLY ( const std::string &  filename,
yarp::sig::PointCloud< T > &  cloud,
yarp::sig::VectorOf< int > &  indices 
)
Note
Failure is reported if required fields are missing, depending on the requested point type. Optional fields are alpha (RGBA types) and curvature (normal types).
Parameters
filenamePath to a file with .ply extension.
cloudCloud of vertices.
indicesVector of indices, each three consecutive values define a face.
Returns
Whether the mesh has been successfully imported or not.

◆ meshFromCloud() [1/2]

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" 
)
Note
Implements a set of PCL algorithms. Refer to instructions.
Parameters
cloudInput cloud.
meshPointsCloud of vertices of the resulting polygon mesh.
meshIndicesVector if indices of the resulting polygon mesh, each three consecutive values define a face.
configConfiguration in YARP native format to read the pipeline from.
collectionNamed section collection that identifies this pipeline in config.
Returns
Whether any failure occurred throughout the pipeline.

◆ meshFromCloud() [2/2]

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 
)
Note
Implements a set of PCL algorithms. Refer to instructions.
Parameters
cloudInput cloud.
meshPointsCloud of vertices of the resulting polygon mesh.
meshIndicesVector if indices of the resulting polygon mesh, each three consecutive values define a face.
optionsVector of dictionaries, each element defines a step of the pipeline.
Returns
Whether any failure occurred throughout the pipeline.

◆ processCloud() [1/2]

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" 
)
Note
Implements a set of PCL algorithms. Refer to instructions.
Parameters
cloudInput cloud.
meshPointsCloud of vertices of the resulting polygon mesh.
meshIndicesVector if indices of the resulting polygon mesh, each three consecutive values define a face.
configConfiguration in YARP native format to read the pipeline from.
collectionNamed section collection that identifies this pipeline in config.
Returns
Whether any failure occurred throughout the pipeline.

◆ processCloud() [2/2]

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 
)
Note
Implements a set of PCL algorithms. Refer to instructions.
Parameters
cloudInput cloud.
meshPointsCloud of vertices of the resulting polygon mesh.
meshIndicesVector if indices of the resulting polygon mesh, each three consecutive values define a face.
optionsVector of dictionaries, each element defines a step of the pipeline.
Returns
Whether any failure occurred throughout the pipeline.

◆ savePLY() [1/2]

template<typename T >
bool roboticslab::YarpCloudUtils::savePLY ( const std::string &  filename,
const yarp::sig::PointCloud< T > &  cloud,
bool  isBinary = true 
)
Parameters
filenamePath to a file with .ply extension.
cloudCloud of points.
isBinaryWhether to save file with binary format or not.
Returns
Whether the cloud has been successfully exported or not.

◆ savePLY() [2/2]

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 
)
Parameters
filenamePath to a file with .ply extension.
cloudCloud of vertices.
indicesVector of indices, each three consecutive values define a face.
isBinaryWhether to save file with binary format or not.
Returns
Whether the mesh has been successfully exported or not.