Loading [MathJax]/extensions/tex2jax.js
vision
All Classes Namespaces Functions Variables Modules Pages
YarpCloudUtils.hpp
1 // -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2 
3 #ifndef __YARP_CLOUD_UTILS_HPP__
4 #define __YARP_CLOUD_UTILS_HPP__
5 
6 #include <string>
7 
8 #include <yarp/os/Property.h>
9 #include <yarp/os/Searchable.h>
10 
11 #include <yarp/sig/PointCloud.h>
12 #include <yarp/sig/Vector.h>
13 
23 namespace roboticslab
24 {
25 
30 namespace YarpCloudUtils
31 {
32 
44 template <typename T>
45 bool savePLY(const std::string & filename, const yarp::sig::PointCloud<T> & cloud, const yarp::sig::VectorOf<int> & indices, bool isBinary = true);
46 
57 template <typename T>
58 bool savePLY(const std::string & filename, const yarp::sig::PointCloud<T> & cloud, bool isBinary = true)
59 {
60  return savePLY(filename, cloud, {}, isBinary);
61 }
62 
76 template <typename T>
77 bool loadPLY(const std::string & filename, yarp::sig::PointCloud<T> & cloud, yarp::sig::VectorOf<int> & indices);
78 
91 template <typename T>
92 bool loadPLY(const std::string & filename, yarp::sig::PointCloud<T> & cloud)
93 {
94  yarp::sig::VectorOf<int> indices;
95  return loadPLY(filename, cloud, indices);
96 }
97 
112 template <typename T1, typename T2 = T1>
113 bool meshFromCloud(const yarp::sig::PointCloud<T1> & cloud,
114  yarp::sig::PointCloud<T2> & meshPoints,
115  yarp::sig::VectorOf<int> & meshIndices,
116  const yarp::sig::VectorOf<yarp::os::Property> & options);
117 
133 template <typename T1, typename T2 = T1>
134 bool meshFromCloud(const yarp::sig::PointCloud<T1> & cloud,
135  yarp::sig::PointCloud<T2> & meshPoints,
136  yarp::sig::VectorOf<int> & meshIndices,
137  const yarp::os::Searchable & config,
138  const std::string & collection = "meshPipeline");
139 
154 template <typename T1, typename T2 = T1>
155 bool processCloud(const yarp::sig::PointCloud<T1> & in,
156  yarp::sig::PointCloud<T2> & out,
157  const yarp::sig::VectorOf<yarp::os::Property> & options);
158 
174 template <typename T1, typename T2 = T1>
175 bool processCloud(const yarp::sig::PointCloud<T1> & in,
176  yarp::sig::PointCloud<T2> & out,
177  const yarp::os::Searchable & config,
178  const std::string & collection = "cloudPipeline");
179 
180 } // namespace YarpCloudUtils
181 
182 } // namespace roboticslab
183 
184 #endif // __YARP_CLOUD_UTILS_HPP__
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