Skip to content

Commit

Permalink
Small fixes and improvements
Browse files Browse the repository at this point in the history
- openni_klt.cpp: initialize counter_ to 0
- conversions.h: use std::size_t instead of uindex_t. This is an improvement when loading large clouds (e.g. more than 2^28 = 268 million XYZI points, because 2^28*16 overflows 32 bit unsigned, 16 being the point step/bytes per point). The user can switch uindex_t from 32 bit unsigned to 64 bit unsigned to solve this, but simply using std::size_t here is easier
- voxel_grid_covariance.h: construct array with appropriate size
- gicp.hpp: de-mean point neighbourhoods when computing covariance matrices
- ppf_registration.hpp: switch messages from info to debug
- region_growing.hpp: use auto for indices
- opennurbs_system.h: do not throw error when WIN32 is defined (see also https://github.com/microsoft/vcpkg/blob/master/ports/pcl/fix_opennurbs_win32.patch)
- octree_viewer.cpp: program name in help text
- openni2_viewer.cpp: remove unused variables
  • Loading branch information
mvieth committed Mar 3, 2023
1 parent 2b1ebdd commit d47f6d7
Show file tree
Hide file tree
Showing 9 changed files with 36 additions and 39 deletions.
2 changes: 1 addition & 1 deletion apps/src/openni_klt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ class OpenNIViewer {
using CloudConstPtr = typename Cloud::ConstPtr;

OpenNIViewer(pcl::Grabber& grabber)
: grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0)
: grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0), counter_(0)
{}

void
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -198,10 +198,10 @@ namespace pcl
else
{
// If not, memcpy each group of contiguous fields separately
for (uindex_t row = 0; row < msg.height; ++row)
for (std::size_t row = 0; row < msg.height; ++row)
{
const std::uint8_t* row_data = msg_data + row * msg.row_step;
for (uindex_t col = 0; col < msg.width; ++col)
for (std::size_t col = 0; col < msg.width; ++col)
{
const std::uint8_t* msg_data = row_data + col * msg.point_step;
for (const detail::FieldMapping& mapping : field_map)
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/voxel_grid_covariance.h
Original file line number Diff line number Diff line change
Expand Up @@ -464,7 +464,7 @@ namespace pcl
}

// Find k-nearest neighbors in the occupied voxel centroid cloud
Indices k_indices;
Indices k_indices (k);
k = kdtree_.nearestKSearch (point, k, k_indices, k_sqr_distances);

// Find leaves corresponding to neighbors
Expand Down
29 changes: 15 additions & 14 deletions registration/include/pcl/registration/impl/gicp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,8 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar
}

Eigen::Vector3d mean;
pcl::Indices nn_indices;
nn_indices.reserve(k_correspondences_);
std::vector<float> nn_dist_sq;
nn_dist_sq.reserve(k_correspondences_);
pcl::Indices nn_indices(k_correspondences_);
std::vector<float> nn_dist_sq(k_correspondences_);

// We should never get there but who knows
if (cloud_covariances.size() < cloud->size())
Expand All @@ -85,20 +83,23 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovar

// Find the covariance matrix
for (int j = 0; j < k_correspondences_; j++) {
const PointT& pt = (*cloud)[nn_indices[j]];
// de-mean neighbourhood to avoid inaccuracies when far away from origin
const double ptx = (*cloud)[nn_indices[j]].x - query_point.x,
pty = (*cloud)[nn_indices[j]].y - query_point.y,
ptz = (*cloud)[nn_indices[j]].z - query_point.z;

mean[0] += pt.x;
mean[1] += pt.y;
mean[2] += pt.z;
mean[0] += ptx;
mean[1] += pty;
mean[2] += ptz;

cov(0, 0) += pt.x * pt.x;
cov(0, 0) += ptx * ptx;

cov(1, 0) += pt.y * pt.x;
cov(1, 1) += pt.y * pt.y;
cov(1, 0) += pty * ptx;
cov(1, 1) += pty * pty;

cov(2, 0) += pt.z * pt.x;
cov(2, 1) += pt.z * pt.y;
cov(2, 2) += pt.z * pt.z;
cov(2, 0) += ptz * ptx;
cov(2, 1) += ptz * pty;
cov(2, 2) += ptz * ptz;
}

mean /= static_cast<double>(k_correspondences_);
Expand Down
14 changes: 7 additions & 7 deletions registration/include/pcl/registration/impl/ppf_registration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ pcl::PPFRegistration<PointSource, PointTarget>::computeTransformation(
const std::vector<unsigned int> tmp_vec(aux_size, 0);
std::vector<std::vector<unsigned int>> accumulator_array(input_->size(), tmp_vec);

PCL_INFO("Accumulator array size: %u x %u.\n",
accumulator_array.size(),
accumulator_array.back().size());
PCL_DEBUG("Accumulator array size: %u x %u.\n",
accumulator_array.size(),
accumulator_array.back().size());

PoseWithVotesList voted_poses;
// Consider every <scene_reference_point_sampling_rate>-th point as the reference
Expand Down Expand Up @@ -232,7 +232,7 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList& poses,
typename pcl::PPFRegistration<PointSource, PointTarget>::PoseWithVotesList& result)
{
PCL_INFO("Clustering poses ...\n");
PCL_DEBUG("Clustering poses ...\n");
// Start off by sorting the poses by the number of votes
sort(poses.begin(), poses.end(), poseWithVotesCompareFunction);

Expand Down Expand Up @@ -268,9 +268,9 @@ pcl::PPFRegistration<PointSource, PointTarget>::clusterPoses(
result.clear();
std::size_t max_clusters = (clusters.size() < 3) ? clusters.size() : 3;
for (std::size_t cluster_i = 0; cluster_i < max_clusters; ++cluster_i) {
PCL_INFO("Winning cluster has #votes: %d and #poses voted: %d.\n",
cluster_votes[cluster_i].second,
clusters[cluster_votes[cluster_i].first].size());
PCL_DEBUG("Winning cluster has #votes: %d and #poses voted: %d.\n",
cluster_votes[cluster_i].second,
clusters[cluster_votes[cluster_i].first].size());
Eigen::Vector3f translation_average(0.0, 0.0, 0.0);
Eigen::Vector4f rotation_average(0.0, 0.0, 0.0, 0.0);
for (typename PoseWithVotesList::iterator v_it =
Expand Down
8 changes: 4 additions & 4 deletions segmentation/include/pcl/segmentation/impl/region_growing.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -351,7 +351,7 @@ pcl::RegionGrowing<PointT, NormalT>::findPointNeighbours ()
{
for (int i_point = 0; i_point < point_number; i_point++)
{
int point_index = (*indices_)[i_point];
const auto point_index = (*indices_)[i_point];
neighbours.clear ();
search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
point_neighbours_[point_index].swap (neighbours);
Expand All @@ -362,7 +362,7 @@ pcl::RegionGrowing<PointT, NormalT>::findPointNeighbours ()
for (int i_point = 0; i_point < point_number; i_point++)
{
neighbours.clear ();
int point_index = (*indices_)[i_point];
const auto point_index = (*indices_)[i_point];
if (!pcl::isFinite ((*input_)[point_index]))
continue;
search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances);
Expand All @@ -386,7 +386,7 @@ pcl::RegionGrowing<PointT, NormalT>::applySmoothRegionGrowingAlgorithm ()
{
for (int i_point = 0; i_point < num_of_pts; i_point++)
{
int point_index = (*indices_)[i_point];
const auto point_index = (*indices_)[i_point];
point_residual[i_point].first = (*normals_)[point_index].curvature;
point_residual[i_point].second = point_index;
}
Expand All @@ -396,7 +396,7 @@ pcl::RegionGrowing<PointT, NormalT>::applySmoothRegionGrowingAlgorithm ()
{
for (int i_point = 0; i_point < num_of_pts; i_point++)
{
int point_index = (*indices_)[i_point];
const auto point_index = (*indices_)[i_point];
point_residual[i_point].first = 0;
point_residual[i_point].second = point_index;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,15 +137,15 @@
#if defined(_M_X64) && defined(WIN32) && defined(WIN64)
// 23 August 2007 Dale Lear

#if defined(_INC_WINDOWS)
//#if defined(_INC_WINDOWS)
// The user has included Microsoft's windows.h before opennurbs.h,
// and windows.h has nested includes that unconditionally define WIN32.
// Just undo the damage here or everybody that includes opennurbs.h after
// windows.h has to fight with this Microsoft bug.
#undef WIN32
#else
#error do not define WIN32 for x64 builds
#endif
//#else
//#error do not define WIN32 for x64 builds
//#endif

// NOTE _WIN32 is defined for any type of Windows build
#endif
Expand Down
4 changes: 2 additions & 2 deletions tools/octree_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -459,8 +459,8 @@ int main(int argc, char ** argv)
{
if (argc != 3)
{
std::cerr << "ERROR: Syntax is octreeVisu <pcd file> <resolution>" << std::endl;
std::cerr << "EXAMPLE: ./octreeVisu bun0.pcd 0.001" << std::endl;
std::cerr << "ERROR: Syntax is " << argv[0] << " <pcd file> <resolution>" << std::endl;
std::cerr << "EXAMPLE: ./" << argv[0] << " bun0.pcd 0.001" << std::endl;
return -1;
}

Expand Down
4 changes: 0 additions & 4 deletions tools/openni2_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,10 +275,6 @@ class OpenNI2Viewer
unsigned rgb_data_size_;
};

// Create the PCLVisualizer object
pcl::visualization::PCLVisualizer::Ptr cld;
pcl::visualization::ImageViewer::Ptr img;

/* ---[ */
int
main (int argc, char** argv)
Expand Down

0 comments on commit d47f6d7

Please sign in to comment.