-
Notifications
You must be signed in to change notification settings - Fork 7
/
YarpCloudUtils.hpp
184 lines (166 loc) · 6.43 KB
/
YarpCloudUtils.hpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
#ifndef __YARP_CLOUD_UTILS_HPP__
#define __YARP_CLOUD_UTILS_HPP__
#include <string>
#include <yarp/os/Property.h>
#include <yarp/os/Searchable.h>
#include <yarp/sig/PointCloud.h>
#include <yarp/sig/Vector.h>
/**
* @ingroup vision_libraries
* @defgroup YarpCloudUtils
* @brief Collection of cloud-related utilities for YARP.
*
* @see [Instructions](@ref yarpcloudutils).
* @see @cite lukawski2024jjaa
*/
namespace roboticslab
{
/**
* @ingroup YarpCloudUtils
* @brief Collection of cloud-related utilities for YARP.
*/
namespace YarpCloudUtils
{
/**
* @ingroup YarpCloudUtils
* @brief Writes a triangular polygon mesh to file.
*
* @param filename Path to a file with .ply extension.
* @param cloud Cloud of vertices.
* @param indices Vector of indices, each three consecutive values define a face.
* @param isBinary Whether to save file with binary format or not.
*
* @return Whether the mesh has been successfully exported or not.
*/
template <typename T>
bool savePLY(const std::string & filename, const yarp::sig::PointCloud<T> & cloud, const yarp::sig::VectorOf<int> & indices, bool isBinary = true);
/**
* @ingroup YarpCloudUtils
* @brief Writes a point cloud to file.
*
* @param filename Path to a file with .ply extension.
* @param cloud Cloud of points.
* @param isBinary Whether to save file with binary format or not.
*
* @return Whether the cloud has been successfully exported or not.
*/
template <typename T>
bool savePLY(const std::string & filename, const yarp::sig::PointCloud<T> & cloud, bool isBinary = true)
{
return savePLY(filename, cloud, {}, isBinary);
}
/**
* @ingroup YarpCloudUtils
* @brief Reads a triangular polygon mesh from file.
*
* @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).
*
* @param filename Path to a file with .ply extension.
* @param cloud Cloud of vertices.
* @param indices Vector of indices, each three consecutive values define a face.
*
* @return Whether the mesh has been successfully imported or not.
*/
template <typename T>
bool loadPLY(const std::string & filename, yarp::sig::PointCloud<T> & cloud, yarp::sig::VectorOf<int> & indices);
/**
* @ingroup YarpCloudUtils
* @brief Reads a point cloud from file.
*
* @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).
*
* @param filename Path to a file with .ply extension.
* @param cloud Cloud of vertices.
*
* @return Whether the cloud has been successfully imported or not.
*/
template <typename T>
bool loadPLY(const std::string & filename, yarp::sig::PointCloud<T> & cloud)
{
yarp::sig::VectorOf<int> indices;
return loadPLY(filename, cloud, indices);
}
/**
* @ingroup YarpCloudUtils
* @brief Constructs a triangular polygon mesh from a point cloud.
*
* @note Implements a set of PCL algorithms. Refer to [instructions](@ref yarpcloudutils).
*
* @param cloud Input cloud.
* @param meshPoints Cloud of vertices of the resulting polygon mesh.
* @param meshIndices Vector if indices of the resulting polygon mesh, each three
* consecutive values define a face.
* @param options Vector of dictionaries, each element defines a step of the pipeline.
*
* @return Whether any failure occurred throughout the pipeline.
*/
template <typename T1, typename T2 = T1>
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);
/**
* @ingroup YarpCloudUtils
* @brief Constructs a triangular polygon mesh from a point cloud.
*
* @note Implements a set of PCL algorithms. Refer to [instructions](@ref yarpcloudutils).
*
* @param cloud Input cloud.
* @param meshPoints Cloud of vertices of the resulting polygon mesh.
* @param meshIndices Vector if indices of the resulting polygon mesh, each three
* consecutive values define a face.
* @param config Configuration in YARP native format to read the pipeline from.
* @param collection Named section collection that identifies this pipeline in @p config.
*
* @return Whether any failure occurred throughout the pipeline.
*/
template <typename T1, typename T2 = T1>
bool 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");
/**
* @ingroup YarpCloudUtils
* @brief Processes a cloud of points.
*
* @note Implements a set of PCL algorithms. Refer to [instructions](@ref yarpcloudutils).
*
* @param cloud Input cloud.
* @param meshPoints Cloud of vertices of the resulting polygon mesh.
* @param meshIndices Vector if indices of the resulting polygon mesh, each three
* consecutive values define a face.
* @param options Vector of dictionaries, each element defines a step of the pipeline.
*
* @return Whether any failure occurred throughout the pipeline.
*/
template <typename T1, typename T2 = T1>
bool processCloud(const yarp::sig::PointCloud<T1> & in,
yarp::sig::PointCloud<T2> & out,
const yarp::sig::VectorOf<yarp::os::Property> & options);
/**
* @ingroup YarpCloudUtils
* @brief Processes a cloud of points.
*
* @note Implements a set of PCL algorithms. Refer to [instructions](@ref yarpcloudutils).
*
* @param cloud Input cloud.
* @param meshPoints Cloud of vertices of the resulting polygon mesh.
* @param meshIndices Vector if indices of the resulting polygon mesh, each three
* consecutive values define a face.
* @param config Configuration in YARP native format to read the pipeline from.
* @param collection Named section collection that identifies this pipeline in @p config.
*
* @return Whether any failure occurred throughout the pipeline.
*/
template <typename T1, typename T2 = T1>
bool processCloud(const yarp::sig::PointCloud<T1> & in,
yarp::sig::PointCloud<T2> & out,
const yarp::os::Searchable & config,
const std::string & collection = "cloudPipeline");
} // namespace YarpCloudUtils
} // namespace roboticslab
#endif // __YARP_CLOUD_UTILS_HPP__