Skip to content

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

Closed
PeterBowman opened this issue Nov 18, 2020 · 19 comments
Closed

Create new library of cloud-related YARP utilities #102

PeterBowman opened this issue Nov 18, 2020 · 19 comments
Assignees

Comments

@PeterBowman
Copy link
Member

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):

  • cloudToFile
  • meshToFile
  • cloudFromFile
  • meshFromFile
  • meshFromCloud

While YARP_pcl exposes two handy methods, savePCD and loadPCD, 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, use pcl_viewer and pcl_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.

@PeterBowman PeterBowman self-assigned this Nov 18, 2020
@PeterBowman
Copy link
Member Author

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.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 19, 2020

I'm prone to offer two alternative implementations of these functions: (...), the other is basically hand-crafted file import/export in ASCII-based PLY.

To avoid reinventing the wheel, there are some valuable FOSS alternatives:

See also http://paulbourke.net/dataformats/ply/.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 22, 2020

The following program shows a sample usage of all supported specializations of savePLY and loadPLY regarding point clouds and meshes. Mind robotology/yarp#2417 regarding the toString instructions for RGBA values to be printed correctly. It is also useful for illustrating how yarp::sig::PointCloud elements can be constructed and pushed into the cloud via aggregate initialization.

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;
}

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 23, 2020

Tinyply presents two major shortcomings (especially wrt. the PCL implementation I want to align with):

  • Optional properties: for instance, in case the alpha channel in a XYZRGBA point cloud is missing, tinyply throws an exception. In contrast, PCL falls back to a value of zero while showing a warning.
  • Sort order of properties: since I'm memcpying bytes into the internal memory of the resulting YARP point cloud, it is important to preserve their order in compound assignments. For instance, regarding the 3-float array (actually it's 4-float if we account for the padding) that represents XYZ, the point cloud expects exactly that order. The same goes for the blue-green-red-alpha channels of the RGBA data buffer. There is no way I can instruct tinyply to parse those properties in that exact order so that memcpy is straightforward. Rather, I need to shuffle them as an intermediate step.

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.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 23, 2020

On my machine, reading an ASCII 31M .ply file of XYZ points takes around 1670 ms with PCL and 750 ms with tinyply AToW.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 23, 2020

Tinyply presents two major shortcomings...

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.

@PeterBowman
Copy link
Member Author

Note PCL ignores the "intensity" and "strength" properties for pcl::PointXYZI and pcl::InterestPoint, respectively, when saving meshes. Also, loading meshes with types pcl::PointXY or pcl::Normal is not possible.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 24, 2020

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.

ASCII binary
write
read write read
PCL 1220 2070 135 130
tinyply 1140 1010 80 150
tinyply
(buffered)
1020 130

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)

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 24, 2020

Given the above results, I'm prone to drop the PCL implementation in favor of the buffered tinyply solution.

Done at 6d6cf42. For the record, I'd like to link here to the deleted sample usage of type traits for future reference:

template <typename T>
struct pcl_type_from_yarp;
template <>
struct pcl_type_from_yarp<yarp::sig::DataXY>
{ typedef pcl::PointXY type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataXYZ>
{ typedef pcl::PointXYZ type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataNormal>
{ typedef pcl::Normal type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataXYZRGBA>
{ typedef pcl::PointXYZRGBA type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataXYZI>
{ typedef pcl::PointXYZI type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataInterestPointXYZ>
{ typedef pcl::InterestPoint type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataXYZNormal>
{ typedef pcl::PointNormal type; };
template <>
struct pcl_type_from_yarp<yarp::sig::DataXYZNormalRGBA>
{ typedef pcl::PointXYZRGBNormal type; };

using pcl_type = typename pcl_type_from_yarp<T>::type;
pcl::PointCloud<pcl_type> pcl;

Also, a bunch of interesting decltypes:

static_cast<decltype(triangles.vertices)::value_type>(vertices[i]),
static_cast<decltype(triangles.vertices)::value_type>(vertices[i + 1]),
static_cast<decltype(triangles.vertices)::value_type>(vertices[i + 2])

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 25, 2020

Cloud downsampling (pcl::Filter, pcl::FilterIndices, module filters):

Cloud filtering (pcl::Filter, pcl::FilterIndices, module filters):

Cloud surface processing (pcl::CloudSurfaceProcessing, module surface):

Normal estimation (pcl::Feature, module features):

Surface meshing techniques (module surface):

Mesh processing (pcl::MeshProcessing, module surface):

Removal of unused vertices from mesh: pcl::SimplificationRemoveUnusedVertices (header, impl).

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.

@PeterBowman
Copy link
Member Author

PeterBowman commented Nov 28, 2020

I'm introducing three new C++ example apps related to cloud generation and meshing:

  • exampleMeshFromCloud: load a point cloud from .ply file, generate mesh and save to disk
  • exampleMeshFromLiveDepth: connect to live depth sensor, acquire depth frame, generate cloud and/or mesh and save to disk
  • exampleSceneReconstructionClient: connect to remote Kinect Fusion server, download cloud, generate mesh and save to disk

The live sensor app requires robotology/yarp#2425 for ROI/decimation of input frames (targetting YARP 3.4.2).

@PeterBowman
Copy link
Member Author

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(...);

@PeterBowman
Copy link
Member Author

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

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 SurfaceMeshingBuilder class encapsulates the configuration of each step of the internal pipeline and produces a yarp::os::Property, which can fit into meshFromCloud as the configuration parameter. Long story short, its usage is optional, it's just a convenient way of initializing the kinda large amount of parameters that can derive from said pipeline.

@PeterBowman
Copy link
Member Author

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:

template <typename T>
bool meshFromCloud(const yarp::sig::PointCloud<T> & cloud,
yarp::sig::PointCloud<T> & meshPoints,
yarp::sig::VectorOf<int> & meshIndices,
const yarp::os::Searchable & options = yarp::os::Property({
{"downsampleAlgorithm", yarp::os::Value("VoxelGrid")},
{"downsampleLeafSize", yarp::os::Value(0.02f)},
{"estimatorAlgorithm", yarp::os::Value("NormalEstimationOMP")},
{"estimatorKSearch", yarp::os::Value(40)},
{"surfaceAlgorithm", yarp::os::Value("Poisson")}
}));

Then, I allowed the instantiation of distinct type arguments for yarp::sig::PointCloud<T> as input and output:

template <typename T1, typename T2>
bool meshFromCloud(const yarp::sig::PointCloud<T1> & cloud,
yarp::sig::PointCloud<T2> & meshPoints,
yarp::sig::VectorOf<int> & meshIndices,
const yarp::os::Searchable & options = yarp::os::Property({
{"downsampleAlgorithm", yarp::os::Value("VoxelGrid")},
{"downsampleLeafSize", yarp::os::Value(0.02f)},
{"estimatorAlgorithm", yarp::os::Value("NormalEstimationOMP")},
{"estimatorKSearch", yarp::os::Value(40)},
{"surfaceAlgorithm", yarp::os::Value("Poisson")}
}));

This is motivated by the fact that certain inputs, e.g. DataXIZ, are stripped from their additional fields throughout the pipeline. It is therefore of little use to populate the vertex cloud with so many null (zero) fields. It is expected that clients invoke this function template with at least the same input/output types or narrower ones (e.g. input is XYZI, but output is XYZ), thus avoiding those null fields and some warnings from the PCL side. It always depends on the selected algorithm, thus the proper decision must be taken on compile time attending to the expected behavior on run time. Of course, nothing prevents downstreams from requesting wider point types (e.g. input is XYZ, output is XYZRGBA), which is a waste of resources due to the consequent null fields. I'd rather grant better flexibility at the cost of potentially producing a less-optimal result if not taken proper care of. Also, 2835973 aims to signalize that at least the same point type is preferred.

The major drawback of this decision was the list of template instantiations exponentially growing on the number of allowed point types:

template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXY &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXYZRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXYZI &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXYZNormal &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXY &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZ &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudNormal &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZRGBA &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZI &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudInterestPointXYZ &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormal &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);
template bool meshFromCloud(const yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::PointCloudXYZNormalRGBA &, yarp::sig::VectorOf<int> &, const yarp::os::Searchable &);

Binaries have become only slightly bigger, I'm not worried about that.

@PeterBowman
Copy link
Member Author

PeterBowman commented Dec 6, 2020

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):

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 = {
{{"algorithm", yarp::os::Value("VoxelGrid")},
{"leafSize", yarp::os::Value(0.02f)}},
{{"algorithm", yarp::os::Value("NormalEstimationOMP")},
{"kSearch", yarp::os::Value(40)}},
{{"algorithm", yarp::os::Value("Poisson")}}
});

The new SurfaceMeshingBuilder class encapsulates the configuration of each step of the internal pipeline...

Removed at e63e69e. I'm providing an overload intended for parsing section collections, especially via .ini config files:

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");

@PeterBowman
Copy link
Member Author

PeterBowman commented Dec 12, 2020

I'm not adding bindings because YARP doesn't support translation of yarp::sig::PointCloud into Python. Also, stuff like VectorOf<Property> would need special treatment (ideally, list of dictionaries).

@PeterBowman
Copy link
Member Author

Commit 68e6e60 added a volatile dummy variable to avoid a (corner?) case of aggressive compiler optimization. Why is that:

  • Despite usual practice, I don't provide the implementation of function templates in the header file:
    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);
    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");
  • In order to hide PCL details (and void forcing users to compile a huge amount of code and more PCL templates), I moved the implementation to YarpCloudUtils-pcl.cpp and instantiated all targeted point types in YarpCloudUtils-pcl-inst.hpp.
  • As a side note, attempting to use a template for a type that has not been instantiated in this manner would result in an error during link time, and only visible by downstreams (libraries or executables that consume this library). However, we are in the safe end since yarp::sig::PointCloud performs a static assertion on supported types, therefore downstreams would get a compile error while trying to instantiate an unsupported type (since I'm instantiating my function templates precisely for those types). This is nice until YARP decides to add and support more types, of course, which would force us to update our code.
  • Let's take a look upon processCloud: there are two overloads, i.e. one "main" signature and an adapter overload which calls the former:
    template <typename T1, typename T2>
    bool processCloud(const yarp::sig::PointCloud<T1> & in,
    yarp::sig::PointCloud<T2> & out,
    const yarp::os::Searchable & config,
    const std::string & collection)
    {
    return processCloud(in, out, makeFromConfig(config, collection));
    }
  • I only need to instantiate the adapter overload, which in turn instantiates every combination of types T1 and T2 for the main signature:
    #define YCU_PCL_CLOUD_SIGNATURE(in, out) \
    template bool processCloud(const in &, out &, const yarp::os::Searchable &, const std::string &);

    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXY, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZ, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudNormal, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZRGBA, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZI, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudInterestPointXYZ, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormal, yarp::sig::PointCloudXYZNormalRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXY)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZRGBA)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZI)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudInterestPointXYZ)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZNormal)
    YCU_PCL_CLOUD_SIGNATURE(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZNormalRGBA)
  • In the implementation of the main signature, I perform a type check since among those eight available YARP point types I'm not providing support for neither yarp::sig::DataXY nor yarp::sig::DataNormal:
    if (is_unsupported_type<pcl_input_type>)
    {
    yError() << "unsupported input point type" << pcl_descriptor<pcl_input_type>::name;
    return false;
    }
    if (is_unsupported_type<pcl_output_type>)
    {
    yError() << "unsupported output point type" << pcl_descriptor<pcl_output_type>::name;
    return false;
    }
  • Here comes trouble. Apparently the compiler/linker performs DCE (dead code elimination) on anything that comes after these checks when an unsupported type is requested, i.e. whenever the if clauses are true. It makes sense since is_unsupported_type is a constexpr, therefore the compiler sees an if (true) in either of both cases. However, stripping the rest of the implementation causes the linker to omit symbols for these precise types.
  • Forcing the definition of pclCloudIn before those checks seemed to do the trick for GCC 9.3.0 (Ubuntu Focal), but GCC 7.5.0 (Ubuntu Bionic) is apparently even more aggressive and ignores that. Even moving the size check on options up doesn't help.
  • So I did this:
    volatile auto dummy = true;
    if (is_unsupported_type<pcl_input_type> && dummy)
    {
    yError() << "unsupported input point type" << pcl_descriptor<pcl_input_type>::name;
    return false;
    }
    if (is_unsupported_type<pcl_output_type> && dummy)
    {
    yError() << "unsupported output point type" << pcl_descriptor<pcl_output_type>::name;
    return false;
    }

    The compiler is forced to avoid optimizations and attend to the value of variable dummy on each check (unless shortcircuiting on supported types, in which case these ifs would be entirely stripped off). If not declared volatile, this wouldn't work. Also, mind the non-empty definition of processCloudPCL for unsupported types, which is also a must.

This is the reason why I'm using all available type instantiations in the unit tests:

TEST_F(YarpCloudUtilsTest, processCloud)
{
yarp::sig::PointCloudXYZ points;
populateCloud(points, 100, [] { return yarp::sig::DataXYZ {rnf(), rnf(), rnf()}; });
yarp::sig::PointCloudXY in_xy(points), out_xy;
yarp::sig::PointCloudXYZ in_xyz(points), out_xyz;
yarp::sig::PointCloudNormal in_normal(points), out_normal;
yarp::sig::PointCloudXYZRGBA in_xyz_rgba(points), out_xyz_rgba;
yarp::sig::PointCloudXYZI in_xyzi(points), out_xyzi;
yarp::sig::PointCloudInterestPointXYZ in_interest(points), out_interest;
yarp::sig::PointCloudXYZNormal in_xyz_normal(points), out_xyz_normal;
yarp::sig::PointCloudXYZNormalRGBA in_xyz_normal_rgba(points), out_xyz_normal_rgba;
yarp::sig::VectorOf<yarp::os::Property> options {
{{"algorithm", yarp::os::Value("ApproximateVoxelGrid")}, {"leafSize", yarp::os::Value(0.5f)}}
};
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xy, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xy, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xy, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_normal, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_normal, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_rgba, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyzi, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_xyz_rgba, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyzi, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyzi, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_interest, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_xyzi, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_interest, out_interest, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_interest, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_interest, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal, out_xyz_normal, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal, out_xyz_normal_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xy, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xyz, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_normal, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xyz_rgba, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xyzi, options));
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_interest, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xyz_normal, options));
ASSERT_TRUE(YarpCloudUtils::processCloud(in_xyz_normal_rgba, out_xyz_normal_rgba, options));
yarp::sig::VectorOf<yarp::os::Property> empty {};
ASSERT_FALSE(YarpCloudUtils::processCloud(in_xyz, out_xyz, empty));
}

PeterBowman added a commit that referenced this issue Dec 13, 2020
@PeterBowman
Copy link
Member Author

PeterBowman commented Dec 13, 2020

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:

@PeterBowman
Copy link
Member Author

PeterBowman commented Dec 16, 2020

Follow-up: a0ac04f introduces transformPointCloud and transformPointCloudWithNormals. These functions perform an affine transformation (translation+rotation) on a point cloud.

Ideally, I'd like to apply this step on the resulting surface mesh. Since these functions only accept pcl::PointCloud<T> instead of pcl::PolygonMesh, it would be possible to make meshFromCloudPCL return a pair of cloud+indices instead of this strange ROS-compatible structure, also sparing a few conversions between data representations. Sadly, all mesh processing algorithms (the VTK ones) plus pcl::surface::SimplificationRemoveUnusedVertices only accept pcl::PolygonMesh, therefore it could get even worse due to the need for converting back and forth between this creature and pcl::PointCloud<T>.

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.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant