Skip to content

Commit

Permalink
Merge pull request #790 from desinghkar/grsd_request
Browse files Browse the repository at this point in the history
Including GRSD a global radius-based surface descriptor
  • Loading branch information
taketwo committed Jul 31, 2014
2 parents 4cc066f + 6854ddb commit 5a621c3
Show file tree
Hide file tree
Showing 11 changed files with 640 additions and 8 deletions.
14 changes: 14 additions & 0 deletions common/include/pcl/impl/point_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@
(pcl::NormalBasedSignature12) \
(pcl::FPFHSignature33) \
(pcl::VFHSignature308) \
(pcl::GRSDSignature21) \
(pcl::ESFSignature640) \
(pcl::BRISKSignature512) \
(pcl::Narf36) \
Expand Down Expand Up @@ -138,6 +139,7 @@
(pcl::NormalBasedSignature12) \
(pcl::FPFHSignature33) \
(pcl::VFHSignature308) \
(pcl::GRSDSignature21) \
(pcl::ESFSignature640) \
(pcl::BRISKSignature512) \
(pcl::Narf36)
Expand Down Expand Up @@ -1299,6 +1301,18 @@ namespace pcl

friend std::ostream& operator << (std::ostream& os, const VFHSignature308& p);
};

PCL_EXPORTS std::ostream& operator << (std::ostream& os, const GRSDSignature21& p);
/** \brief A point structure representing the Global Radius-based Surface Descriptor (GRSD).
* \ingroup common
*/
struct GRSDSignature21
{
float histogram[21];
static int descriptorSize () { return 21; }

friend std::ostream& operator << (std::ostream& os, const GRSDSignature21& p);
};

PCL_EXPORTS std::ostream& operator << (std::ostream& os, const BRISKSignature512& p);
/** \brief A point structure representing the Binary Robust Invariant Scalable Keypoints (BRISK).
Expand Down
9 changes: 9 additions & 0 deletions common/include/pcl/point_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -255,6 +255,11 @@ namespace pcl
*/
struct VFHSignature308;

/** \brief Members: float grsd[21]
* \ingroup common
*/
struct GRSDSignature21;

/** \brief Members: float esf[640]
* \ingroup common
*/
Expand Down Expand Up @@ -584,6 +589,10 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::VFHSignature308,
(float[308], histogram, vfh)
)

POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::GRSDSignature21,
(float[21], histogram, grsd)
)

POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ESFSignature640,
(float[640], histogram, esf)
)
Expand Down
9 changes: 6 additions & 3 deletions features/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ if(build)
"include/pcl/${SUBSYS_NAME}/principal_curvatures.h"
"include/pcl/${SUBSYS_NAME}/rift.h"
"include/pcl/${SUBSYS_NAME}/rops_estimation.h"
#"include/pcl/${SUBSYS_NAME}/rsd.h"
"include/pcl/${SUBSYS_NAME}/rsd.h"
"include/pcl/${SUBSYS_NAME}/grsd.h"
"include/pcl/${SUBSYS_NAME}/statistical_multiscale_interest_region_extraction.h"
"include/pcl/${SUBSYS_NAME}/vfh.h"
"include/pcl/${SUBSYS_NAME}/esf.h"
Expand Down Expand Up @@ -99,7 +100,8 @@ if(build)
"include/pcl/${SUBSYS_NAME}/impl/principal_curvatures.hpp"
"include/pcl/${SUBSYS_NAME}/impl/rift.hpp"
"include/pcl/${SUBSYS_NAME}/impl/rops_estimation.hpp"
#"include/pcl/${SUBSYS_NAME}/impl/rsd.hpp"
"include/pcl/${SUBSYS_NAME}/impl/rsd.hpp"
"include/pcl/${SUBSYS_NAME}/impl/grsd.hpp"
"include/pcl/${SUBSYS_NAME}/impl/statistical_multiscale_interest_region_extraction.hpp"
"include/pcl/${SUBSYS_NAME}/impl/vfh.hpp"
"include/pcl/${SUBSYS_NAME}/impl/esf.hpp"
Expand Down Expand Up @@ -139,7 +141,8 @@ if(build)
src/principal_curvatures.cpp
src/rift.cpp
src/rops_estimation.cpp
#src/rsd.cpp
src/rsd.cpp
src/grsd.cpp
src/statistical_multiscale_interest_region_extraction.cpp
src/vfh.cpp
src/esf.cpp
Expand Down
148 changes: 148 additions & 0 deletions features/include/pcl/features/grsd.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,148 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2009-2014, Willow Garage, Inc.
* Copyright (c) 2014-, Open Perception, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder(s) nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*/

#ifndef PCL_FEATURES_GRSD_H_
#define PCL_FEATURES_GRSD_H_

#include <pcl/features/feature.h>
#include <pcl/features/rsd.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/kdtree/kdtree_flann.h>

namespace pcl
{
/** \brief @b GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud dataset
* containing points and normals.
*
* @note If you use this code in any academic work, please cite (first for the ray-casting and second for the additive version):
*
* <ul>
* <li> Z.C. Marton, D. Pangercic, N. Blodow, Michael Beetz.
* Combined 2D-3D Categorization and Classification for Multimodal Perception Systems.
* In The International Journal of Robotics Research, Sage Publications
* pages 1378--1402, Volume 30, Number 11, September 2011.
* </li>
* <li> A. Kanezaki, Z.C. Marton, D. Pangercic, T. Harada, Y. Kuniyoshi, M. Beetz.
* Voxelized Shape and Color Histograms for RGB-D
* In the Workshop on Active Semantic Perception and Object Search in the Real World, in conjunction with the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)
* San Francisco, California, September 25-30, 2011.
* </li>
* </ul>
*
* @note The code is stateful as we do not expect this class to be multicore parallelized. Please look at
* \ref FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
* \author Zoltan Csaba Marton
* \ingroup features
*/

template <typename PointInT, typename PointNT, typename PointOutT>
class GRSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
{
public:
using Feature<PointInT, PointOutT>::feature_name_;
using Feature<PointInT, PointOutT>::getClassName;
using Feature<PointInT, PointOutT>::indices_;
using Feature<PointInT, PointOutT>::search_radius_;
using Feature<PointInT, PointOutT>::search_parameter_;
using Feature<PointInT, PointOutT>::input_;
using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
using Feature<PointInT, PointOutT>::setSearchSurface;
//using Feature<PointInT, PointOutT>::computeFeature;

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
typedef typename Feature<PointInT, PointOutT>::PointCloudInPtr PointCloudInPtr;

/** \brief Constructor. */
GRSDEstimation () : additive_ (true)
{
feature_name_ = "GRSDEstimation";
relative_coordinates_all_ = getAllNeighborCellIndices ();
};

/** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature
* estimation. Same value will be used for the internal voxel grid leaf size.
* \param[in] radius the sphere radius used as the maximum distance to consider a point a neighbor
*/
inline void
setRadiusSearch (double radius) { width_ = search_radius_ = radius; }

/** \brief Get the sphere radius used for determining the neighbors.
* \return the sphere radius used as the maximum distance to consider a point a neighbor
*/
inline double
getRadiusSearch () const { return (search_radius_); }

/** \brief Get the type of the local surface based on the min and max radius computed.
* \return the integer that represents the type of the local surface with values as
* Plane (1), Cylinder (2), Noise or corner (0), Sphere (3) and Edge (4)
*/
static inline int
getSimpleType (float min_radius, float max_radius, double min_radius_plane, double max_radius_noise,
double min_radius_cylinder, double max_min_radius_diff);

protected:

/** \brief Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by
* <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
* setSearchMethod ()
* \param output the resultant point cloud that contains the GRSD feature
*/
void
computeFeature (PointCloudOut &output);

private:

/** \brief Defines if an additive feature is computed or ray-casting is used to get a more descriptive feature. */
bool additive_;

/** \brief Defines the voxel size to be used. */
double width_;

/** \brief Pre-computed the relative cell indices of all the 26 neighbors. */
Eigen::MatrixXi relative_coordinates_all_;

};

}

#ifdef PCL_NO_PRECOMPILE
#include <pcl/features/impl/grsd.hpp>
#endif

#endif /* PCL_FEATURES_GRSD_H_ */
130 changes: 130 additions & 0 deletions features/include/pcl/features/impl/grsd.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,130 @@
/*
* Software License Agreement (BSD License)
*
* Point Cloud Library (PCL) - www.pointclouds.org
* Copyright (c) 2009-2014, Willow Garage, Inc.
* Copyright (c) 2014-, Open Perception, Inc.
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder(s) nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*/

#ifndef PCL_FEATURES_IMPL_GRSD_H_
#define PCL_FEATURES_IMPL_GRSD_H_

#include <pcl/features/grsd.h>
///////// STATIC /////////
template <typename PointInT, typename PointNT, typename PointOutT> int
pcl::GRSDEstimation<PointInT, PointNT, PointOutT>::getSimpleType (float min_radius, float max_radius,
double min_radius_plane = 0.100,
double max_radius_noise = 0.015,
double min_radius_cylinder = 0.175,
double max_min_radius_diff = 0.050)
{
if (min_radius > min_radius_plane)
return (1); // plane
else if (max_radius > min_radius_cylinder)
return (2); // cylinder (rim)
else if (min_radius < max_radius_noise)
return (0); // noise/corner
else if (max_radius - min_radius < max_min_radius_diff)
return (3); // sphere/corner
else
return (4); // edge
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT> void
pcl::GRSDEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
{
// Check if search_radius_ was set
if (width_ < 0)
{
PCL_ERROR ("[pcl::%s::computeFeature] A voxel cell width needs to be set!\n", getClassName ().c_str ());
output.width = output.height = 0;
output.points.clear ();
return;
}

// Create the voxel grid
PointCloudInPtr cloud_downsampled (new PointCloudIn());
pcl::VoxelGrid<PointInT> grid;
grid.setLeafSize (width_, width_, width_);
grid.setInputCloud (input_);
grid.setSaveLeafLayout (true); // TODO maybe avoid this using nearest neighbor search
grid.filter (*cloud_downsampled);

// Compute RSD
pcl::PointCloud<pcl::PrincipalRadiiRSD>::Ptr radii (new pcl::PointCloud<pcl::PrincipalRadiiRSD>());
pcl::RSDEstimation<PointInT, PointNT, pcl::PrincipalRadiiRSD> rsd;
rsd.setInputCloud (cloud_downsampled);
rsd.setSearchSurface (input_);
rsd.setInputNormals (normals_);
rsd.setRadiusSearch (std::max (search_radius_, sqrt (3) * width_ / 2));
// pcl::KdTree<PointInT>::Ptr tree = boost::make_shared<pcl::KdTreeFLANN<PointInT> >();
// tree->setInputCloud(input_);
// rsd.setSearchMethod(tree);
rsd.compute (*radii);

// Save the type of each point
int NR_CLASS = 5; // TODO make this nicer
std::vector<int> types (radii->points.size ());
for (size_t idx = 0; idx < radii->points.size (); ++idx)
types[idx] = getSimpleType (radii->points[idx].r_min, radii->points[idx].r_max);

// Get the transitions between surface types between neighbors of occupied cells
Eigen::MatrixXi transition_matrix = Eigen::MatrixXi::Zero (NR_CLASS + 1, NR_CLASS + 1);
for (size_t idx = 0; idx < cloud_downsampled->points.size (); ++idx)
{
int source_type = types[idx];
std::vector<int> neighbors = grid.getNeighborCentroidIndices (cloud_downsampled->points[idx], relative_coordinates_all_);
for (unsigned id_n = 0; id_n < neighbors.size (); id_n++)
{
int neighbor_type;
if (neighbors[id_n] == -1) // empty
neighbor_type = NR_CLASS;
else
neighbor_type = types[neighbors[id_n]];
transition_matrix (source_type, neighbor_type)++;
}
}

// Save feature values
output.points.resize (1);
output.height = output.width = 1;
int nrf = 0;
for (int i = 0; i < NR_CLASS + 1; i++)
for (int j = i; j < NR_CLASS + 1; j++)
output.points[0].histogram[nrf++] = transition_matrix (i, j) + transition_matrix (j, i);
}

#define PCL_INSTANTIATE_GRSDEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::GRSDEstimation<T,NT,OutT>;

#endif /* PCL_FEATURES_IMPL_GRSD_H_ */
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/rsd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,4 +293,4 @@ pcl::RSDEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut

#define PCL_INSTANTIATE_RSDEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::RSDEstimation<T,NT,OutT>;

#endif // PCL_FEATURES_IMPL_VFH_H_
#endif // PCL_FEATURES_IMPL_RSD_H_
Loading

0 comments on commit 5a621c3

Please sign in to comment.