-
Notifications
You must be signed in to change notification settings - Fork 7
Create new library of cloud-related YARP utilities #102
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Comments
I really want to provide a simple way to export clouds generated by sceneReconstruction (our new Kinect Fusion service). It makes little sense to create specific RPC commands for that purpose, chiefly because it would not store the data on the client's PC but rather on the server executing sceneReconstruction. So, a simple client app would do. It might also cover the cloud-to-mesh conversion case and saving clouds directly into .ply as polygonal meshes. |
To avoid reinventing the wheel, there are some valuable FOSS alternatives:
See also http://paulbourke.net/dataformats/ply/. |
The following program shows a sample usage of all supported specializations of cmake_minimum_required(VERSION 3.12 FATAL_ERROR)
project(vision-cloud-utils LANGUAGES CXX)
find_package(ROBOTICSLAB_VISION REQUIRED)
add_executable(${PROJECT_NAME} main.cpp)
target_link_libraries(${PROJECT_NAME} ROBOTICSLAB::YarpCloudUtils) #undef NDEBUG
#include <cassert>
#include <chrono>
#include <iostream>
#include <YarpCloudUtils.hpp>
#define ITER for (int i = 0; i < 5; i++)
int main()
{
const yarp::sig::VectorOf<int> verts {5, 1, 3, 7, 2, 9, 4, 2, 3};
yarp::sig::PointCloudXY pcXY;
ITER pcXY.push_back({1.5f, 2.5f});
roboticslab::YarpCloudUtils::savePLY("xy.ply", pcXY, verts, false);
yarp::sig::PointCloudXYZ pcXYZ;
ITER pcXYZ.push_back({1.5f, 2.5f, 3.5f});
roboticslab::YarpCloudUtils::savePLY("xyz.ply", pcXYZ, verts, false);
yarp::sig::PointCloudNormal pcNormal;
ITER pcNormal.push_back({{1.5f, 2.5f, 3.5f}, 4.5f});
roboticslab::YarpCloudUtils::savePLY("normal.ply", pcNormal, verts, false);
yarp::sig::PointCloudXYZRGBA pcXYZRGBA;
ITER pcXYZRGBA.push_back({{1.5f, 2.5f, 3.5f}, {10, 11, 12, 13}});
roboticslab::YarpCloudUtils::savePLY("xyzrgba.ply", pcXYZRGBA, verts, true);
yarp::sig::PointCloudXYZI pcXYZI;
ITER pcXYZI.push_back({{1.5f, 2.5f, 3.5f}, 4.5f});
roboticslab::YarpCloudUtils::savePLY("xyzi.ply", pcXYZI, verts, false);
yarp::sig::PointCloudInterestPointXYZ pcXYZinterest;
ITER pcXYZinterest.push_back({{1.5f, 2.5f, 3.5f}, 4.5f});
roboticslab::YarpCloudUtils::savePLY("xyzint.ply", pcXYZinterest, verts, false);
yarp::sig::PointCloudXYZNormal pcXYZNormal;
ITER pcXYZNormal.push_back({{1.5f, 2.5f, 3.5f}, {4.5f, 5.5f, 6.5f}, 7.5f});
roboticslab::YarpCloudUtils::savePLY("xyznormal.ply", pcXYZNormal, verts, false);
yarp::sig::PointCloudXYZNormalRGBA pcXYZNormalRGBA;
ITER pcXYZNormalRGBA.push_back({{1.5f, 2.5f, 3.5f}, {4.5f, 5.5f, 6.5f}, {10, 11, 12, 13, 7.5f}});
roboticslab::YarpCloudUtils::savePLY("xyznormalrgba.ply", pcXYZNormalRGBA, verts, false);
yarp::sig::PointCloudXY pcXY2;
yarp::sig::VectorOf<int> vertsXY;
assert(roboticslab::YarpCloudUtils::loadPLY("xy.ply", pcXY2, vertsXY));
std::cout << "[1]" << pcXY2.toString(1) << std::endl << vertsXY.toString() << std::endl;
yarp::sig::PointCloudXYZ pcXYZ2;
yarp::sig::VectorOf<int> vertsXYZ;
assert(roboticslab::YarpCloudUtils::loadPLY("xyz.ply", pcXYZ2, vertsXYZ));
std::cout << "[2]" << pcXYZ2.toString(1) << std::endl << vertsXYZ.toString() << std::endl;
yarp::sig::PointCloudNormal pcNormal2;
yarp::sig::VectorOf<int> vertsNormal;
assert(roboticslab::YarpCloudUtils::loadPLY("normal.ply", pcNormal2, vertsNormal));
std::cout << "[3]" << pcNormal2.toString(1) << std::endl << vertsNormal.toString() << std::endl;
yarp::sig::PointCloudXYZRGBA pcXYZRGBA2;
yarp::sig::VectorOf<int> vertsXYZRGBA;
assert(roboticslab::YarpCloudUtils::loadPLY("xyzrgba.ply", pcXYZRGBA2, vertsXYZRGBA));
std::cout << "[4]" << pcXYZRGBA2.toString(1) << std::endl << vertsXYZRGBA.toString() << std::endl;
yarp::sig::PointCloudXYZI pcXYZI2;
yarp::sig::VectorOf<int> vertsXYZI;
assert(roboticslab::YarpCloudUtils::loadPLY("xyzi.ply", pcXYZI2, vertsXYZI));
std::cout << "[5]" << pcXYZI2.toString(1) << std::endl << vertsXYZI.toString() << std::endl;
yarp::sig::PointCloudInterestPointXYZ pcXYZinterest2;
yarp::sig::VectorOf<int> vertsXYZInterest;
assert(roboticslab::YarpCloudUtils::loadPLY("xyzint.ply", pcXYZinterest2, vertsXYZInterest));
std::cout << "[6]" << pcXYZinterest2.toString(1) << std::endl << vertsXYZInterest.toString() << std::endl;
yarp::sig::PointCloudXYZNormal pcXYZNormal2;
yarp::sig::VectorOf<int> vertsXYZNormal;
assert(roboticslab::YarpCloudUtils::loadPLY("xyznormal.ply", pcXYZNormal2, vertsXYZNormal));
std::cout << "[7]" << pcXYZNormal2.toString(1) << std::endl << vertsXYZNormal.toString() << std::endl;
yarp::sig::PointCloudXYZNormalRGBA pcXYZNormalRGBA2;
yarp::sig::VectorOf<int> vertsXYZNormalRGBA;
assert(roboticslab::YarpCloudUtils::loadPLY("xyznormalrgba.ply", pcXYZNormalRGBA2, vertsXYZNormalRGBA));
std::cout << "[8]" << pcXYZNormalRGBA2.toString(1) << std::endl << vertsXYZNormalRGBA.toString() << std::endl;
return 0;
} |
Tinyply presents two major shortcomings (especially wrt. the PCL implementation I want to align with):
All of this concerns PLY data import. Exporting data to a .ply file is pretty easy and needs not to involve tinyply if we don't want to. Edit: reported at ddiakopoulos/tinyply#48. |
On my machine, reading an ASCII 31M .ply file of XYZ points takes around 1670 ms with PCL and 750 ms with tinyply AToW. |
Fixed at 5873b7c and no perf drop observed. It's even less memory-consuming since no copies into intermediary buffers are involved. |
Note PCL ignores the "intensity" and "strength" properties for |
This table compares the performance of PCL versus tinyply, tested with an XYZ cloud of 1525437 points (using the sceneReconstruction sample client). Cell values represent average elapsed time in milliseconds. The table also includes a variation of the tinyply PLY reader using buffered streams, inspired by this tinyply example, which allegedly yields a 40% parsing speed improvement for most files smaller than 1 GB.
For reference, file sizes range from 44-51 MB (ASCII) to 18 MB (binary). Given the above results, I'm prone to drop the PCL implementation in favor of the buffered tinyply solution. (PS generated with https://www.tablesgenerator.com/html_tables) |
Done at 6d6cf42. For the record, I'd like to link here to the deleted sample usage of type traits for future reference: vision/libraries/YarpCloudUtils/YarpCloudUtils-pcl.cpp Lines 14 to 47 in d0d62ed
vision/libraries/YarpCloudUtils/YarpCloudUtils-pcl.cpp Lines 95 to 96 in d0d62ed
Also, a bunch of interesting vision/libraries/YarpCloudUtils/YarpCloudUtils-pcl.cpp Lines 59 to 61 in d0d62ed
|
Cloud downsampling (
Cloud filtering (
Cloud surface processing (
Normal estimation (
Surface meshing techniques (module surface):
Mesh processing (
Removal of unused vertices from mesh: Mesh construction methods preserve the original point cloud as the surface vertices and simply construct the mesh on top, while surface reconstruction changes the topology of the input cloud. In any case, if the downsampling step is enabled, the original cloud will be altered anyway. BTW all VTK-based methods return dense vertex clouds. |
I'm introducing three new C++ example apps related to cloud generation and meshing:
The live sensor app requires robotology/yarp#2425 for ROI/decimation of input frames (targetting YARP 3.4.2). |
Not sure if I'm ever going to consider this seriously, but instead of a one-pass omnibus free function I could wrap the whole pipeline in a class and, using the builder pattern for configuration, grant the user better control of the underlying pipeline: yarp::os::Property cropOpts, downsampleOpts, smoothOpts, reconstructOpts, processOpts;
yarp::sig::PointCloud input, output;
yarp::sig::VectorOf<int> indices;
auto mesher = SurfaceMeshingBuilder::createInstance()
.setInputCloud(input)
.setOutputCloud(output) // optional for mesh construction, mandatory for surface reconstruction
.addCropStep(cropOpts)
.addDownsampleStep(downsampleOpts)
.addSmoothStep(smoothOpts)
.addReconstructStep(reconstructOpts) // required
.addProcessStep(processOpts);
bool ret = mesher.doWork(indices);
// perhaps add individual steps, too, for better user control? e.g.:
// mesher.crop(...); |
Done at ba9ed69, but quite far from my original intention. I realized that the class that shall represent the result of the builder mechanism would only have one method. It's equivalent to the current status quo of having a one-pass free function that accepts a parameter for internal configuration, so I'm just sticking to it. The new |
At first, I was enforcing that input and output clouds (i.e. input point cloud and output vertex cloud) must share the same point type: vision/libraries/YarpCloudUtils/YarpCloudUtils.hpp Lines 46 to 56 in 18e3db6
Then, I allowed the instantiation of distinct type arguments for vision/libraries/YarpCloudUtils/YarpCloudUtils.hpp Lines 46 to 56 in a04274f
This is motivated by the fact that certain inputs, e.g. The major drawback of this decision was the list of template instantiations exponentially growing on the number of allowed point types: vision/libraries/YarpCloudUtils/YarpCloudUtils-inst.hpp Lines 16 to 86 in a04274f
Binaries have become only slightly bigger, I'm not worried about that. |
I've reworked the implementation (8a8223c), thus gaining much more flexibility. Next, I allowed clients to configure their custom pipeline via vector of properties (each element is another step in said pipeline): vision/libraries/YarpCloudUtils/YarpCloudUtils.hpp Lines 45 to 55 in 4cb018b
Removed at e63e69e. I'm providing an overload intended for parsing section collections, especially via .ini config files: vision/libraries/YarpCloudUtils/YarpCloudUtils.hpp Lines 56 to 61 in e63e69e
|
I'm not adding bindings because YARP doesn't support translation of |
Commit 68e6e60 added a
This is the reason why I'm using all available type instantiations in the unit tests: vision/tests/testYarpCloudUtils.cpp Lines 456 to 548 in f0bbb9d
|
Done at 2c87861. In addition to cloud/mesh import/export and cloud2mesh, I also added plain cloud processing so that a new point cloud can be obtained through any of the 33 algorithms featured in this library (those that output another cloud, of course). Documentation:
Examples: |
Follow-up: a0ac04f introduces Ideally, I'd like to apply this step on the resulting surface mesh. Since these functions only accept At the end, copying clouds might not be that inefficient in view of the time-consuming filter and reconstruction steps. On the other hand, applying a transformation to the input point cloud might not be either. My idea was to perform this step at the end of the pipeline considering that the resulting vertex cloud could be much smaller due to downsampling/decimation, hence a (possibly) substantial reduction of compute time as opposed to doing this right at the beginning on the input cloud. Again, premature optimization is the root of all evil. |
Following on #101 (comment), I'd like to propose a new shared library of free functions focused on operations on point clouds. The point here is to interface with YARP classes, therefore I propose the name YarpCloudUtils. Functionalities envisioned so far include (temp names):
While YARP_pcl exposes two handy methods,
savePCD
andloadPCD
, note the PCD format is (perhaps too) closely related to PCL. I'd rather work with PLY files as those can be probably read by a wider range of software, starting with Meshlab and Windows' Paint3D. Anyway, in case of need, usepcl_viewer
andpcl_pcd2ply
/pcl_pcl2pcd
to perform the necessary conversions.It is worth noting that we could still internally take advantage of PCL:
pcl::io::savePLYFile
. I'm prone to offer two alternative implementations of these functions: one that uses PCL if available, the other is basically hand-crafted file import/export in ASCII-based PLY. Of course, stuff such as meshFromCloud is only feasible with an underlying PCL implementation.The text was updated successfully, but these errors were encountered: