Skip to content

Commit

Permalink
Merge pull request #5747 from mvieth/misc11
Browse files Browse the repository at this point in the history
Misc small changes and improvements
  • Loading branch information
larshg committed Jun 16, 2023
2 parents cf46790 + 8fb956d commit 6c23c85
Show file tree
Hide file tree
Showing 22 changed files with 55 additions and 47 deletions.
8 changes: 4 additions & 4 deletions .ci/azure-pipelines/ubuntu-variety.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,12 @@ jobs:
displayName: "BuildUbuntuVariety"
steps:
- script: |
POSSIBLE_VTK_VERSION=("7" "9") \
POSSIBLE_VTK_VERSION=("9") \
POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \
POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \
POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15") \
POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15") \
POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15") \
POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \
POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \
POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16") \
CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \
dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \
echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs"
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/PCLPointCloud2.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ namespace pcl
for (std::size_t i = 0; i < v.data.size (); ++i)
{
s << " data[" << i << "]: ";
s << " " << v.data[i] << std::endl;
s << " " << static_cast<int>(v.data[i]) << std::endl;
}
s << "is_dense: ";
s << " " << v.is_dense << std::endl;
Expand Down
1 change: 1 addition & 0 deletions common/include/pcl/impl/pcl_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,7 @@ pcl::PCLBase<PointT>::initCompute ()
catch (const std::bad_alloc&)
{
PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", input_->size ());
return (false);
}
for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast<int>(i); }
}
Expand Down
1 change: 1 addition & 0 deletions common/src/pcl_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,7 @@ pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
catch (const std::bad_alloc&)
{
PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", (input_->width * input_->height));
return (false);
}
if (indices_size < indices_->size ())
std::iota(indices_->begin () + indices_size, indices_->end (), indices_size);
Expand Down
9 changes: 4 additions & 5 deletions doc/tutorials/content/compiling_pcl_posix.rst
Original file line number Diff line number Diff line change
Expand Up @@ -89,14 +89,13 @@ The following code libraries are **required** for the compilation and usage of t
+---------------------------------------------------------------+-----------------+-------------------------+-------------------+
| Logo | Library | Minimum version | Mandatory |
+===============================================================+=================+=========================+===================+
| .. image:: images/posix_building_pcl/boost_logo.png | Boost | | 1.40 (without OpenNI) | pcl_* |
| | | | 1.47 (with OpenNI) | |
| .. image:: images/posix_building_pcl/boost_logo.png | Boost | 1.65 | pcl_* |
+---------------------------------------------------------------+-----------------+-------------------------+-------------------+
| .. image:: images/posix_building_pcl/eigen_logo.png | Eigen | 3.0 | pcl_* |
| .. image:: images/posix_building_pcl/eigen_logo.png | Eigen | 3.3 | pcl_* |
+---------------------------------------------------------------+-----------------+-------------------------+-------------------+
| .. image:: images/posix_building_pcl/flann_logo.png | FLANN | 1.7.1 | pcl_* |
| .. image:: images/posix_building_pcl/flann_logo.png | FLANN | 1.9.1 | pcl_* |
+---------------------------------------------------------------+-----------------+-------------------------+-------------------+
| .. image:: images/posix_building_pcl/vtk_logo.png | VTK | 5.6 | pcl_visualization |
| .. image:: images/posix_building_pcl/vtk_logo.png | VTK | 6.2 | pcl_visualization |
+---------------------------------------------------------------+-----------------+-------------------------+-------------------+

Optional
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/global_hypothesis_verification.rst
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ Take a look at the full pipeline:
:lines: 245-374
:emphasize-lines: 6,9

For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping <http://pointclouds.org/documentation/tutorials/correspondence_grouping.php>`_.
For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping <https://pcl.readthedocs.io/projects/tutorials/en/master/correspondence_grouping.html>`_.


Model-in-Scene Projection
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/moment_of_inertia.rst
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ The code
--------

First of all you will need the point cloud for this tutorial.
`This <https://github.com/PointCloudLibrary/data/blob/master/tutorials/min_cut_segmentation_tutorial.pcd>`_ is the one presented on the screenshots.
`This <https://github.com/PointCloudLibrary/data/blob/master/tutorials/lamppost.pcd>`_ is the one presented on the screenshots.
Next what you need to do is to create a file ``moment_of_inertia.cpp`` in any editor you prefer and copy the following code inside of it:

.. literalinclude:: sources/moment_of_inertia/moment_of_inertia.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ The following normal estimation methods are available:
{
COVARIANCE_MATRIX,
AVERAGE_3D_GRADIENT,
AVERAGE_DEPTH_CHANGE
AVERAGE_DEPTH_CHANGE,
SIMPLE_3D_GRADIENT
};
The COVARIANCE_MATRIX mode creates 9 integral images to compute the normal for
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/registration_api.rst
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ keypoints as well. The problem with "feeding two kinect datasets into a correspo
Feature descriptors
===================

Based on the keypoints found we have to extract [features](http://www.pointclouds.org/documentation/tutorials/how_features_work.php), where we assemble the information and generate vectors to compare them with each other. Again there
Based on the keypoints found we have to extract `features <https://pcl.readthedocs.io/projects/tutorials/en/master/how_features_work.html>`_, where we assemble the information and generate vectors to compare them with each other. Again there
is a number of feature options to choose from, for example NARF, FPFH, BRIEF or
SIFT.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/segmentation/extract_clusters.h>

#include <iomanip> // for setw, setfill

int
main ()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
int
main (int argc, char** argv)
{
if (argc == 0 || argc % 2 == 0)
if (argc < 5 || argc % 2 == 0) // needs at least one training cloud with class id, plus testing cloud with class id (plus name of executable)
return (-1);

unsigned int number_of_training_clouds = (argc - 3) / 2;
Expand Down
6 changes: 3 additions & 3 deletions doc/tutorials/content/using_pcl_pcl_config.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ CMakeLists.txt that contains:
cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
project(MY_GRAND_PROJECT)
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
find_package(PCL 1.3 REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
Expand Down Expand Up @@ -53,7 +53,7 @@ invoking cmake (MY_GRAND_PROJECT_BINARY_DIR).

.. code-block:: cmake
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
find_package(PCL 1.3 REQUIRED)
We are requesting to find the PCL package at minimum version 1.3. We
also say that it is ``REQUIRED`` meaning that cmake will fail
Expand Down Expand Up @@ -204,4 +204,4 @@ before this one:

.. code-block:: cmake
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
find_package(PCL 1.3 REQUIRED)
18 changes: 9 additions & 9 deletions doc/tutorials/content/walkthrough.rst
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ Features
**Background**

A theoretical primer explaining how features work in PCL can be found in the `3D Features tutorial
<http://pointclouds.org/documentation/tutorials/how_features_work.php>`_.
<https://pcl.readthedocs.io/projects/tutorials/en/master/how_features_work.html>`_.

The *features* library contains data structures and mechanisms for 3D feature estimation from point cloud data. 3D features are representations at certain 3D points, or positions, in space, which describe geometrical patterns based on the information available around the point. The data space selected around the query point is usually referred to as the *k-neighborhood*.

Expand Down Expand Up @@ -247,7 +247,7 @@ Kd-tree

**Background**

A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial <http://pointclouds.org/documentation/tutorials/kdtree_search.php#kdtree-search>`_.
A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/kdtree_search.html>`_.

The *kdtree* library provides the kd-tree data-structure, using `FLANN <http://www.cs.ubc.ca/~mariusm/index.php/FLANN/FLANN>`_, that allows for fast `nearest neighbor searches <https://en.wikipedia.org/wiki/Nearest_neighbor_search>`_.

Expand Down Expand Up @@ -331,7 +331,7 @@ Segmentation

The *segmentation* library contains algorithms for segmenting a point cloud into distinct clusters. These algorithms are best suited for processing a point cloud that is composed of a number of spatially isolated regions. In such cases, clustering is often used to break the cloud down into its constituent parts, which can then be processed independently.

A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial <http://pointclouds.org/documentation/tutorials/cluster_extraction.php#cluster-extraction>`_.
A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/cluster_extraction.html>`_.
The two figures illustrate the results of plane model segmentation (left) and cylinder model segmentation (right).

.. image:: images/plane_model_seg.jpg
Expand Down Expand Up @@ -378,7 +378,7 @@ Sample Consensus

The *sample_consensus* library holds SAmple Consensus (SAC) methods like RANSAC and models like planes and cylinders. These can be combined freely in order to detect specific models and their parameters in point clouds.

A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial <http://pointclouds.org/documentation/tutorials/random_sample_consensus.php#random-sample-consensus>`_
A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/random_sample_consensus.html>`_

Some of the models implemented in this library include: lines, planes, cylinders, and spheres. Plane fitting is often applied to the task of detecting common indoor surfaces, such as walls, floors, and table tops. Other models can be used to detect and segment objects with common geometric structures (e.g., fitting a cylinder model to a mug).

Expand Down Expand Up @@ -505,10 +505,10 @@ I/O

The *io* library contains classes and functions for reading and writing point cloud data (PCD) files, as well as capturing point clouds from a variety of sensing devices. An introduction to some of these capabilities can be found in the following tutorials:

* `The PCD (Point Cloud Data) file format <http://pointclouds.org/documentation/tutorials/pcd_file_format.php#pcd-file-format>`_
* `Reading PointCloud data from PCD files <http://pointclouds.org/documentation/tutorials/reading_pcd.php#reading-pcd>`_
* `Writing PointCloud data to PCD files <http://pointclouds.org/documentation/tutorials/writing_pcd.php#writing-pcd>`_
* `The OpenNI Grabber Framework in PCL <http://pointclouds.org/documentation/tutorials/openni_grabber.php#openni-grabber>`_
* `The PCD (Point Cloud Data) file format <https://pcl.readthedocs.io/projects/tutorials/en/master/pcd_file_format.html>`_
* `Reading PointCloud data from PCD files <https://pcl.readthedocs.io/projects/tutorials/en/master/reading_pcd.html>`_
* `Writing PointCloud data to PCD files <https://pcl.readthedocs.io/projects/tutorials/en/master/writing_pcd.html>`_
* `The OpenNI Grabber Framework in PCL <https://pcl.readthedocs.io/projects/tutorials/en/master/openni_grabber.html>`_


|
Expand Down Expand Up @@ -682,7 +682,7 @@ Binaries
This section provides a quick reference for some of the common tools in PCL.


* ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial <http://pointclouds.org/documentation/tutorials/pcd_file_format.php>`_.
* ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial <https://pcl.readthedocs.io/projects/tutorials/en/master/pcd_file_format.html>`_.

**Syntax is: pcl_viewer <file_name 1..N>.<pcd or vtk> <options>**, where options are:

Expand Down
11 changes: 7 additions & 4 deletions features/include/pcl/features/impl/normal_3d_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,17 @@
template <typename PointInT, typename PointOutT> void
pcl::NormalEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
{
if (nr_threads == 0)
#ifdef _OPENMP
if (nr_threads == 0)
threads_ = omp_get_num_procs();
#else
threads_ = 1;
#endif
else
threads_ = nr_threads;
PCL_DEBUG ("[pcl::NormalEstimationOMP::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
#else
threads_ = 1;
if (nr_threads != 1)
PCL_WARN ("[pcl::NormalEstimationOMP::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
#endif // _OPENMP
}

///////////////////////////////////////////////////////////////////////////////////////////
Expand Down
1 change: 1 addition & 0 deletions io/include/pcl/io/io.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,5 +38,6 @@
*/

#pragma once
#include <pcl/pcl_macros.h> // for PCL_DEPRECATED_HEADER
PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/io.h directly.")
#include <pcl/common/io.h>
2 changes: 1 addition & 1 deletion io/src/lzf_image_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ pcl::io::LZFImageWriter::compress (const char* input,
if (itype.size () > 16)
{
PCL_WARN ("[pcl::io::LZFImageWriter::compress] Image type should be a string of maximum 16 characters! Cutting %s to %s.\n", image_type.c_str (), image_type.substr (0, 15).c_str ());
itype = itype.substr (0, 15);
itype.resize(16);
}
if (itype.size () < 16)
itype.insert (itype.end (), 16 - itype.size (), ' ');
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -192,8 +192,8 @@ pcl::features::ISMVoteList<PointT>::findStrongestPeaks (
best_density = peak_densities[i];
strongest_peak = peaks[i];
best_peak_ind = i;
++peak_counter;
}
++peak_counter;
}

if( peak_counter == 0 )
Expand Down
13 changes: 5 additions & 8 deletions segmentation/include/pcl/segmentation/impl/region_growing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,30 +342,27 @@ pcl::RegionGrowing<PointT, NormalT>::prepareForSegmentation ()
template <typename PointT, typename NormalT> void
pcl::RegionGrowing<PointT, NormalT>::findPointNeighbours ()
{
int point_number = static_cast<int> (indices_->size ());
pcl::Indices neighbours;
std::vector<float> distances;

point_neighbours_.resize (input_->size (), neighbours);
if (input_->is_dense)
{
for (int i_point = 0; i_point < point_number; i_point++)
for (const auto& point_index: (*indices_))
{
const auto point_index = (*indices_)[i_point];
neighbours.clear ();
search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances);
point_neighbours_[point_index].swap (neighbours);
}
}
else
{
for (int i_point = 0; i_point < point_number; i_point++)
for (const auto& point_index: (*indices_))
{
neighbours.clear ();
const auto point_index = (*indices_)[i_point];
if (!pcl::isFinite ((*input_)[point_index]))
continue;
search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
neighbours.clear ();
search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances);
point_neighbours_[point_index].swap (neighbours);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -272,19 +272,17 @@ pcl::RegionGrowingRGB<PointT, NormalT>::prepareForSegmentation ()
template <typename PointT, typename NormalT> void
pcl::RegionGrowingRGB<PointT, NormalT>::findPointNeighbours ()
{
int point_number = static_cast<int> (indices_->size ());
pcl::Indices neighbours;
std::vector<float> distances;

point_neighbours_.resize (input_->size (), neighbours);
point_distances_.resize (input_->size (), distances);

for (int i_point = 0; i_point < point_number; i_point++)
for (const auto& point_index: (*indices_))
{
int point_index = (*indices_)[i_point];
neighbours.clear ();
distances.clear ();
search_->nearestKSearch (i_point, region_neighbour_number_, neighbours, distances);
search_->nearestKSearch (point_index, region_neighbour_number_, neighbours, distances);
point_neighbours_[point_index].swap (neighbours);
point_distances_[point_index].swap (distances);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ namespace pcl
* The description can be found in the article:
* "Min-Cut Based Segmentation of Point Clouds"
* \author: Aleksey Golovinskiy and Thomas Funkhouser.
* \ingroup segmentation
*/
template <typename PointT>
class PCL_EXPORTS MinCutSegmentation : public pcl::PCLBase<PointT>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ namespace pcl
* See OrganizedMultiPlaneSegmentation for an example application.
*
* \author Alex Trevor, Suat Gedikli
* \ingroup segmentation
*/
template <typename PointT, typename PointLT>
class OrganizedConnectedComponentSegmentation : public PCLBase<PointT>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -906,6 +906,8 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
for (vtkIdType x = 0; x < normals->width; x += point_step)
{
PointT p = (*cloud)(x, y);
if (!pcl::isFinite(p) || !pcl::isNormalFinite((*normals)(x, y)))
continue;
p.x += (*normals)(x, y).normal[0] * scale;
p.y += (*normals)(x, y).normal[1] * scale;
p.z += (*normals)(x, y).normal[2] * scale;
Expand All @@ -928,8 +930,10 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
nr_normals = (cloud->size () - 1) / level + 1 ;
pts = new float[2 * nr_normals * 3];

for (vtkIdType i = 0, j = 0; j < nr_normals; j++, i = j * level)
for (vtkIdType i = 0, j = 0; (j < nr_normals) && (i < static_cast<vtkIdType>(cloud->size())); i += level)
{
if (!pcl::isFinite((*cloud)[i]) || !pcl::isNormalFinite((*normals)[i]))
continue;
PointT p = (*cloud)[i];
p.x += (*normals)[i].normal[0] * scale;
p.y += (*normals)[i].normal[1] * scale;
Expand All @@ -945,6 +949,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals (
lines->InsertNextCell (2);
lines->InsertCellPoint (2 * j);
lines->InsertCellPoint (2 * j + 1);
++j;
}
}

Expand Down

0 comments on commit 6c23c85

Please sign in to comment.