Skip to content

Commit 2c87861

Browse files
committed
Merge branch 'cloud-utils'
#102
2 parents 3d34e2b + f0b8937 commit 2c87861

26 files changed

+5425
-19
lines changed

.travis.yml

+12
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,21 @@ before_script:
8080
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleHaarDetector" && cd "$_"
8181
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleHaarDetector" && make
8282

83+
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleMeshFromCloud" && cd "$_"
84+
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleMeshFromCloud" && make
85+
86+
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleMeshFromLiveDepth" && cd "$_"
87+
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleMeshFromLiveDepth" && make
88+
89+
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleProcessCloud" && cd "$_"
90+
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleProcessCloud" && make
91+
8392
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleRemoteRGBDSensor" && cd "$_"
8493
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleRemoteRGBDSensor" && make
8594

95+
- mkdir -p "$TRAVIS_BUILD_DIR/build/exampleSceneReconstructionClient" && cd "$_"
96+
- cmake "$TRAVIS_BUILD_DIR/examples/cpp/exampleSceneReconstructionClient" && make
97+
8698
script:
8799
- cd "$TRAVIS_BUILD_DIR/build/tests" && ctest -V
88100

CMakeLists.txt

+3-13
Original file line numberDiff line numberDiff line change
@@ -39,29 +39,19 @@ list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake
3939
# Hard dependencies.
4040
find_package(YCM 0.11 REQUIRED)
4141
find_package(YARP 3.3 REQUIRED COMPONENTS os dev sig
42-
OPTIONAL_COMPONENTS cv)
42+
OPTIONAL_COMPONENTS cv pcl)
4343
find_package(COLOR_DEBUG REQUIRED)
4444

4545
# Soft dependencies.
4646

4747
find_package(OpenCV QUIET)
48-
if(CREATE_BINDINGS_PYTHON_VERSION VERSION_GREATER_EQUAL 3)
49-
message(AUTHOR_WARNING "Skipping find_package(PCL 1.6 QUIET) so we can compile Python 3 bindings")
50-
else()
51-
find_package(PCL 1.6 QUIET)
52-
endif()
48+
find_package(PCL 1.8 QUIET)
5349
find_package(TensorflowCC 1.12 QUIET)
5450
find_package(GTestSources 1.6.0 QUIET)
5551
find_package(SWIG QUIET)
5652
find_package(Doxygen QUIET)
5753

58-
# Xenial + PCL 1.7 bug
59-
# https://github.com/PointCloudLibrary/pcl/issues/2406
60-
if(DEFINED PCL_LIBRARIES)
61-
list(REMOVE_ITEM PCL_LIBRARIES "vtkproj4")
62-
endif()
63-
64-
# Focal + PCL 1.10 + OpenNI workaround (idea: use CMake components to find_package(PCL)?)
54+
# Focal + PCL 1.10 + OpenNI workaround (idea: use CMake components to find_package(PCL)?).
6555
if(PCL_VERSION VERSION_EQUAL 1.10)
6656
include_directories(/usr/include/ni)
6757
link_libraries(/usr/lib/libOpenNI.so)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
cmake_minimum_required(VERSION 3.12 FATAL_ERROR)
2+
3+
project(exampleMeshFromCloud LANGUAGES CXX)
4+
5+
find_package(YARP 3.3 REQUIRED os)
6+
find_package(ROBOTICSLAB_VISION REQUIRED)
7+
8+
add_executable(exampleMeshFromCloud main.cpp)
9+
10+
target_link_libraries(exampleMeshFromCloud YARP::YARP_os
11+
ROBOTICSLAB::YarpCloudUtils)
+92
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
/**
2+
* @ingroup vision_examples
3+
* @defgroup exampleMeshFromCloud exampleMeshFromCloud
4+
* @brief Sample usage of roboticslab::YarpCloudUtils::meshFromCloud.
5+
*/
6+
7+
#include <yarp/os/LogStream.h>
8+
#include <yarp/os/Property.h>
9+
#include <yarp/os/SystemClock.h>
10+
11+
#include <YarpCloudUtils.hpp>
12+
13+
constexpr const char * DEFAULT_COLLECTION = "meshPipeline";
14+
15+
int main(int argc, char * argv[])
16+
{
17+
yarp::os::Property options;
18+
options.fromCommand(argc, argv);
19+
20+
if (options.check("help"))
21+
{
22+
yInfo() << argv[0] << "commands:";
23+
yInfo() << "\t--cloud " << "\tpath to file with .ply extension to import the point cloud from";
24+
yInfo() << "\t--mesh " << "\tpath to file with .ply extension to export the surface mesh to";
25+
yInfo() << "\t--steps " << "\tsection collection defining the meshing pipeline, defaults to:" << DEFAULT_COLLECTION;
26+
yInfo() << "\t--binary" << "\texport data in binary format, defaults to: true";
27+
yInfo() << "\t--height" << "\tnumber of rows (for organized clouds)";
28+
yInfo() << "\t--width " << "\tnumber of columns (for organized clouds)";
29+
return 0;
30+
}
31+
32+
auto fileCloud = options.check("cloud", yarp::os::Value("")).asString();
33+
auto fileMesh = options.check("mesh", yarp::os::Value("")).asString();
34+
auto collection = options.check("steps", yarp::os::Value(DEFAULT_COLLECTION)).asString();
35+
auto binary = options.check("binary", yarp::os::Value(true)).asBool();
36+
37+
if (fileCloud.empty() || fileMesh.empty())
38+
{
39+
yError() << "either of the --cloud and --mesh parameters are missing or empty";
40+
return 1;
41+
}
42+
43+
yarp::sig::PointCloudXYZ cloud;
44+
45+
if (!roboticslab::YarpCloudUtils::loadPLY(fileCloud, cloud))
46+
{
47+
yError() << "unable to import cloud from" << fileCloud;
48+
return 1;
49+
}
50+
51+
yInfo() << "got cloud of" << cloud.size() << "points";
52+
53+
if (options.check("height") && options.check("width"))
54+
{
55+
auto height = options.find("height").asInt32();
56+
auto width = options.find("width").asInt32();
57+
58+
if (height * width != cloud.size())
59+
{
60+
yWarning() << "organized cloud dimensions do not match number of points:" << height << "*" << width << "=" << height * width;
61+
}
62+
63+
cloud.resize(width, height);
64+
}
65+
66+
yarp::sig::PointCloudXYZ meshPoints;
67+
yarp::sig::VectorOf<int> meshIndices;
68+
69+
auto start = yarp::os::SystemClock::nowSystem();
70+
71+
if (!roboticslab::YarpCloudUtils::meshFromCloud(cloud, meshPoints, meshIndices, options, collection))
72+
{
73+
yError() << "unable to reconstruct surface from cloud";
74+
return 1;
75+
}
76+
77+
auto end = yarp::os::SystemClock::nowSystem();
78+
auto elapsed = static_cast<int>((end - start) * 1000);
79+
80+
yInfo() << "surface reconstructed in" << elapsed << "ms, got mesh of" << meshPoints.size() << "points and"
81+
<< meshIndices.size() / 3 << "faces";
82+
83+
if (!roboticslab::YarpCloudUtils::savePLY(fileMesh, meshPoints, meshIndices, binary))
84+
{
85+
yError() << "unable to export mesh to" << fileMesh;
86+
return 1;
87+
}
88+
89+
yInfo() << "mesh exported to" << fileMesh;
90+
91+
return 0;
92+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
cmake_minimum_required(VERSION 3.12 FATAL_ERROR)
2+
3+
project(exampleMeshFromLiveRGBD LANGUAGES CXX)
4+
5+
find_package(YARP 3.3 REQUIRED os dev sig)
6+
find_package(ROBOTICSLAB_VISION REQUIRED)
7+
8+
add_executable(exampleMeshFromLiveRGBD main.cpp)
9+
10+
target_link_libraries(exampleMeshFromLiveRGBD YARP::YARP_os
11+
YARP::YARP_init
12+
YARP::YARP_dev
13+
YARP::YARP_sig
14+
ROBOTICSLAB::YarpCloudUtils)
15+
16+
target_compile_definitions(exampleMeshFromLiveRGBD PRIVATE SAMPLE_CONFIG="${CMAKE_CURRENT_SOURCE_DIR}/pipeline.ini")
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,181 @@
1+
/**
2+
* @ingroup vision_examples
3+
* @defgroup exampleMeshFromLiveRGBD exampleMeshFromLiveRGBD
4+
* @brief Transform RGBD frame to cloud/mesh.
5+
*/
6+
7+
#include <yarp/conf/version.h>
8+
9+
#include <yarp/os/LogStream.h>
10+
#include <yarp/os/Network.h>
11+
#include <yarp/os/Property.h>
12+
#include <yarp/os/SystemClock.h>
13+
#include <yarp/os/Value.h>
14+
15+
#include <yarp/dev/IRGBDSensor.h>
16+
#include <yarp/dev/PolyDriver.h>
17+
18+
#include <yarp/sig/Image.h>
19+
#include <yarp/sig/IntrinsicParams.h>
20+
#include <yarp/sig/PointCloud.h>
21+
#include <yarp/sig/PointCloudUtils.h>
22+
23+
#include <YarpCloudUtils.hpp>
24+
25+
constexpr const char * DEFAULT_REMOTE = "/realsense2";
26+
constexpr const char * DEFAULT_PREFIX = "/exampleMeshFromLiveRGBD";
27+
constexpr const char * DEFAULT_COLLECTION = "meshPipeline";
28+
29+
int main(int argc, char * argv[])
30+
{
31+
yarp::os::Network yarp;
32+
33+
if (!yarp::os::Network::checkNetwork())
34+
{
35+
yError() << "no YARP server available";
36+
return 1;
37+
}
38+
39+
yarp::os::Property options;
40+
options.fromCommand(argc, argv);
41+
42+
if (options.check("help"))
43+
{
44+
yInfo() << argv[0] << "commands:";
45+
yInfo() << "\t--remote" << "\tremote port prefix to connect to, defaults to:" << DEFAULT_REMOTE;
46+
yInfo() << "\t--prefix" << "\tlocal port prefix, defaults to:" << DEFAULT_PREFIX;
47+
yInfo() << "\t--cloud " << "\tpath to file with .ply extension to export the point cloud to";
48+
yInfo() << "\t--mesh " << "\tpath to file with .ply extension to export the surface mesh to";
49+
yInfo() << "\t--steps " << "\tsection collection defining the meshing pipeline, defaults to:" << DEFAULT_COLLECTION;
50+
yInfo() << "\t--binary" << "\texport data in binary format, defaults to: true";
51+
return 0;
52+
}
53+
54+
auto remote = options.check("remote", yarp::os::Value(DEFAULT_REMOTE)).asString();
55+
auto prefix = options.check("prefix", yarp::os::Value(DEFAULT_PREFIX)).asString();
56+
auto fileCloud = options.check("cloud", yarp::os::Value("")).asString();
57+
auto fileMesh = options.check("mesh", yarp::os::Value("")).asString();
58+
auto collection = options.check("steps", yarp::os::Value(DEFAULT_COLLECTION)).asString();
59+
auto binary = options.check("binary", yarp::os::Value(true)).asBool();
60+
61+
yarp::sig::FlexImage colorImage;
62+
yarp::sig::ImageOf<yarp::sig::PixelFloat> depthImage;
63+
yarp::sig::IntrinsicParams colorParams;
64+
65+
{
66+
yarp::os::Property sensorOptions {
67+
{"device", yarp::os::Value("RGBDSensorClient")},
68+
{"localImagePort", yarp::os::Value(prefix + "/client/rgbImage:i")},
69+
{"localDepthPort", yarp::os::Value(prefix + "/client/depthImage:i")},
70+
{"localRpcPort", yarp::os::Value(prefix + "/client/rpc:o")},
71+
{"remoteImagePort", yarp::os::Value(remote + "/rgbImage:o")},
72+
{"remoteDepthPort", yarp::os::Value(remote + "/depthImage:o")},
73+
{"remoteRpcPort", yarp::os::Value(remote + "/rpc:i")}
74+
};
75+
76+
yarp::dev::PolyDriver sensorDevice;
77+
78+
if (!sensorDevice.open(sensorOptions))
79+
{
80+
yError() << "unable to establish connection with remote RGBD sensor";
81+
return 1;
82+
}
83+
84+
yarp::dev::IRGBDSensor * iRGBDSensor;
85+
86+
if (!sensorDevice.view(iRGBDSensor))
87+
{
88+
yError() << "unable to view IRGBDSensor interface";
89+
return 1;
90+
}
91+
92+
#if YARP_VERSION_MINOR < 5
93+
// Wait for the first few frames to arrive. We kept receiving invalid pixel codes
94+
// from the depthCamera device if started straight away.
95+
// https://github.com/roboticslab-uc3m/vision/issues/88
96+
yarp::os::SystemClock::delaySystem(1.0);
97+
#endif
98+
99+
yarp::os::Property intrinsic;
100+
101+
if (!iRGBDSensor->getRgbIntrinsicParam(intrinsic))
102+
{
103+
yError() << "unable to retrieve RGB intrinsic parameters";
104+
return 1;
105+
}
106+
107+
colorParams.fromProperty(intrinsic);
108+
109+
for (auto n = 0;; n++)
110+
{
111+
iRGBDSensor->getImages(colorImage, depthImage);
112+
113+
if (colorImage.getRawImageSize() != 0 && depthImage.getRawImageSize() != 0)
114+
{
115+
break;
116+
}
117+
else if (n == 10)
118+
{
119+
yError() << "unable to acquire RGBD frames";
120+
return 1;
121+
}
122+
123+
yarp::os::SystemClock::delaySystem(0.1);
124+
}
125+
}
126+
127+
yarp::sig::ImageOf<yarp::sig::PixelRgb> temp;
128+
temp.copy(colorImage);
129+
auto cloud = yarp::sig::utils::depthRgbToPC<yarp::sig::DataXYZRGBA>(depthImage, temp, colorParams);
130+
yInfo() << "got cloud of" << cloud.size() << "points, organized as" << cloud.width() << "x" << cloud.height();
131+
132+
if (!fileCloud.empty())
133+
{
134+
if (!roboticslab::YarpCloudUtils::savePLY(fileCloud, cloud, binary))
135+
{
136+
yWarning() << "unable to export cloud to" << fileCloud;
137+
}
138+
else
139+
{
140+
yInfo() << "cloud exported to" << fileCloud;
141+
}
142+
}
143+
144+
if (!fileMesh.empty())
145+
{
146+
#ifdef SAMPLE_CONFIG
147+
// set sensible defaults, most suitable for organized clouds
148+
std::string sampleConfigFile = SAMPLE_CONFIG;
149+
options.fromConfigFile(sampleConfigFile, false);
150+
#endif
151+
152+
yarp::sig::PointCloudXYZRGBA meshPoints;
153+
yarp::sig::VectorOf<int> meshIndices;
154+
155+
auto start = yarp::os::SystemClock::nowSystem();
156+
157+
if (!roboticslab::YarpCloudUtils::meshFromCloud(cloud, meshPoints, meshIndices, options, collection))
158+
{
159+
yWarning() << "unable to reconstruct surface from cloud";
160+
}
161+
else
162+
{
163+
auto end = yarp::os::SystemClock::nowSystem();
164+
auto elapsed = static_cast<int>((end - start) * 1000);
165+
166+
yInfo() << "surface reconstructed in" << elapsed << "ms, got mesh of" << meshPoints.size() << "points and"
167+
<< meshIndices.size() / 3 << "faces";
168+
169+
if (!roboticslab::YarpCloudUtils::savePLY(fileMesh, meshPoints, meshIndices, binary))
170+
{
171+
yWarning() << "unable to export mesh to" << fileMesh;
172+
}
173+
else
174+
{
175+
yInfo() << "mesh exported to" << fileMesh;
176+
}
177+
}
178+
}
179+
180+
return 0;
181+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
[meshPipeline surface]
2+
algorithm "OrganizedFastMesh"
3+
maxEdgeLengthA 0.05
4+
useDepthAsDistance true
5+
6+
[meshPipeline simplify]
7+
algorithm "SimplificationRemoveUnusedVertices"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
cmake_minimum_required(VERSION 3.12 FATAL_ERROR)
2+
3+
project(exampleProcessCloud LANGUAGES CXX)
4+
5+
find_package(YARP 3.3 REQUIRED os)
6+
find_package(ROBOTICSLAB_VISION REQUIRED)
7+
8+
add_executable(exampleProcessCloud main.cpp)
9+
10+
target_link_libraries(exampleProcessCloud YARP::YARP_os
11+
ROBOTICSLAB::YarpCloudUtils)

0 commit comments

Comments
 (0)