Skip to content
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

exchange header order and replace pcl_isfinite with std::isfinite #32

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion include/pclomp/voxel_grid_covariance_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@
#ifndef PCL_VOXEL_GRID_COVARIANCE_OMP_H_
#define PCL_VOXEL_GRID_COVARIANCE_OMP_H_

#include <pcl/pcl_macros.h>
#include <pcl/filters/boost.h>
#include <pcl/filters/voxel_grid.h>
#include <map>
#include <unordered_map>
#include <pcl/pcl_macros.h>
#include <pcl/point_types.h>
#include <pcl/kdtree/kdtree_flann.h>

Expand Down
12 changes: 6 additions & 6 deletions include/pclomp/voxel_grid_covariance_omp_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,9 +133,9 @@ pclomp::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
{
if (!input_->is_dense)
// Check if the point is invalid
if (!pcl_isfinite (input_->points[cp].x) ||
!pcl_isfinite (input_->points[cp].y) ||
!pcl_isfinite (input_->points[cp].z))
if (!std::isfinite (input_->points[cp].x) ||
!std::isfinite (input_->points[cp].y) ||
!std::isfinite (input_->points[cp].z))
continue;

// Get the distance value
Expand Down Expand Up @@ -210,9 +210,9 @@ pclomp::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
{
if (!input_->is_dense)
// Check if the point is invalid
if (!pcl_isfinite (input_->points[cp].x) ||
!pcl_isfinite (input_->points[cp].y) ||
!pcl_isfinite (input_->points[cp].z))
if (!std::isfinite (input_->points[cp].x) ||
!std::isfinite (input_->points[cp].y) ||
!std::isfinite (input_->points[cp].z))
continue;

int ijk0 = static_cast<int> (floor (input_->points[cp].x * inverse_leaf_size_[0]) - static_cast<float> (min_b_[0]));
Expand Down