Skip to content

Commit

Permalink
Migrate unordered_map from boost -> std (#3107)
Browse files Browse the repository at this point in the history
* [registration] Add custom hasher to PPFHashMapSearch
  • Loading branch information
SergioRAgostinho authored May 31, 2019
1 parent 13e3050 commit 112d870
Show file tree
Hide file tree
Showing 17 changed files with 45 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@
# pragma GCC system_header
#endif

#include <boost/unordered_map.hpp>
#include <boost/bind/bind.hpp>
#include <boost/math/special_functions/fpclassify.hpp>
#include <boost/shared_ptr.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@
#include <mutex>
#include <iomanip>
#include <string>
#include <unordered_map>

namespace pcl
{
Expand Down Expand Up @@ -332,7 +333,7 @@ namespace pcl
typedef Eigen::Matrix <unsigned char, 3, Eigen::Dynamic> Colors;
typedef Eigen::Matrix <unsigned char, 3, 256 > Colormap;

typedef boost::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;
typedef std::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;

typedef pcl::ihs::PointIHS PointIHS;
typedef pcl::ihs::CloudIHS CloudIHS;
Expand All @@ -342,7 +343,7 @@ namespace pcl
typedef pcl::ihs::detail::FaceVertexMesh FaceVertexMesh;
typedef boost::shared_ptr < FaceVertexMesh> FaceVertexMeshPtr;
typedef boost::shared_ptr <const FaceVertexMesh> FaceVertexMeshConstPtr;
typedef boost::unordered_map <std::string, FaceVertexMeshPtr> FaceVertexMeshMap;
typedef std::unordered_map <std::string, FaceVertexMeshPtr> FaceVertexMeshMap;

/** \brief Check if the mesh with the given id is added.
* \note Must lock the mutex before calling this method.
Expand Down
3 changes: 0 additions & 3 deletions features/include/pcl/features/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,6 @@
# pragma GCC system_header
#endif

#include <boost/unordered_map.hpp>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <boost/property_map/property_map.hpp>
//#include <boost/graph/adjacency_list.hpp>
//#include <boost/graph/johnson_all_pairs_shortest.hpp>
1 change: 0 additions & 1 deletion filters/include/pcl/filters/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,6 @@
#include <boost/make_shared.hpp>
#include <boost/dynamic_bitset.hpp>
#include <boost/mpl/size.hpp>
#include <boost/unordered_map.hpp>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include <boost/bind.hpp>
#include <boost/function.hpp>
Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/impl/uniform_sampling.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,8 @@ pcl::UniformSampling<PointT>::applyFilter (PointCloud &output)
output.points.resize (leaves_.size ());
int cp = 0;

for (typename boost::unordered_map<size_t, Leaf>::const_iterator it = leaves_.begin (); it != leaves_.end (); ++it)
output.points[cp++] = input_->points[it->second.idx];
for (const auto& leaf : leaves_)
output.points[cp++] = input_->points[leaf.second.idx];
output.width = static_cast<uint32_t> (output.points.size ());
}

Expand Down
5 changes: 3 additions & 2 deletions filters/include/pcl/filters/uniform_sampling.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@
#pragma once

#include <pcl/filters/filter.h>
#include <boost/unordered_map.hpp>

#include <unordered_map>

namespace pcl
{
Expand Down Expand Up @@ -115,7 +116,7 @@ namespace pcl
};

/** \brief The 3D grid leaves. */
boost::unordered_map<size_t, Leaf> leaves_;
std::unordered_map<size_t, Leaf> leaves_;

/** \brief The size of a leaf. */
Eigen::Vector4f leaf_size_;
Expand Down
2 changes: 0 additions & 2 deletions recognition/include/pcl/recognition/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,4 @@
# pragma GCC system_header
#endif

#include <boost/unordered_map.hpp>
#include <boost/graph/graph_traits.hpp>
//#include <boost/graph/adjacency_list.hpp>
5 changes: 3 additions & 2 deletions recognition/include/pcl/recognition/cg/hough_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#include <pcl/recognition/boost.h>
#include <pcl/point_types.h>

#include <unordered_map>

namespace pcl
{
namespace recognition
Expand Down Expand Up @@ -122,10 +124,9 @@ namespace pcl

/** \brief The Hough Space. */
std::vector<double> hough_space_;
//boost::unordered_map<int, double> hough_space_;

/** \brief List of voters for each bin. */
boost::unordered_map<int, std::vector<int> > voter_ids_;
std::unordered_map<int, std::vector<int> > voter_ids_;
};
}

Expand Down
1 change: 0 additions & 1 deletion registration/include/pcl/registration/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@
#include <boost/graph/dijkstra_shortest_paths.hpp>
#include <boost/property_map/property_map.hpp>

#include <boost/unordered_map.hpp>
#include <boost/noncopyable.hpp>
#include <boost/make_shared.hpp>
#include <boost/function.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@
#include <pcl/point_representation.h>
#include <pcl/registration/boost.h>

#include <unordered_map>

namespace pcl
{
namespace registration
Expand Down Expand Up @@ -163,7 +165,7 @@ namespace pcl
typedef boost::shared_ptr<FeatureContainerInterface> Ptr;
};

typedef boost::unordered_map<std::string, FeatureContainerInterface::Ptr> FeaturesMap;
typedef std::unordered_map<std::string, FeatureContainerInterface::Ptr> FeaturesMap;

/** \brief An STL map containing features to use when performing the correspondence search.*/
FeaturesMap features_map_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_HPP_
#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_HPP_

#include <boost/unordered_map.hpp>
#include <unordered_map>

///////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> void
Expand Down Expand Up @@ -113,7 +113,7 @@ pcl::registration::CorrespondenceRejectorSampleConsensus<PointT>::getRemainingCo
best_transformation_.setIdentity ();
return;
}
boost::unordered_map<int, int> index_to_correspondence;
std::unordered_map<int, int> index_to_correspondence;
for (int i = 0; i < nr_correspondences; ++i)
index_to_correspondence[original_correspondences[i].index_query] = i;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@
#include <pcl/sample_consensus/sac_model_registration_2d.h>
#include <pcl/sample_consensus/ransac.h>

#include <unordered_map>

///////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> void
pcl::registration::CorrespondenceRejectorSampleConsensus2D<PointT>::getRemainingCorrespondences (
Expand Down Expand Up @@ -114,7 +116,7 @@ pcl::registration::CorrespondenceRejectorSampleConsensus2D<PointT>::getRemaining
return;
}

boost::unordered_map<int, int> index_to_correspondence;
std::unordered_map<int, int> index_to_correspondence;
for (int i = 0; i < nr_correspondences; ++i)
index_to_correspondence[original_correspondences[i].index_query] = i;

Expand Down
15 changes: 14 additions & 1 deletion registration/include/pcl/registration/ppf_registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
#include <pcl/registration/registration.h>
#include <pcl/features/ppf.h>

#include <unordered_map>

namespace pcl
{
class PCL_EXPORTS PPFHashMapSearch
Expand All @@ -56,15 +58,26 @@ namespace pcl
*/
struct HashKeyStruct : public std::pair <int, std::pair <int, std::pair <int, int> > >
{
HashKeyStruct () = default;

HashKeyStruct(int a, int b, int c, int d)
{
this->first = a;
this->second.first = b;
this->second.second.first = c;
this->second.second.second = d;
}

std::size_t operator()(const HashKeyStruct& s) const noexcept
{
const std::size_t h1 = std::hash<int>{} (s.first);
const std::size_t h2 = std::hash<int>{} (s.second.first);
const std::size_t h3 = std::hash<int>{} (s.second.second.first);
const std::size_t h4 = std::hash<int>{} (s.second.second.second);
return h1 ^ (h2 << 1) ^ (h3 << 2) ^ (h4 << 3);
}
};
typedef boost::unordered_multimap<HashKeyStruct, std::pair<size_t, size_t> > FeatureHashMapType;
typedef std::unordered_multimap<HashKeyStruct, std::pair<size_t, size_t>, HashKeyStruct> FeatureHashMapType;
typedef boost::shared_ptr<FeatureHashMapType> FeatureHashMapTypePtr;
typedef boost::shared_ptr<PPFHashMapSearch> Ptr;

Expand Down
1 change: 0 additions & 1 deletion surface/include/pcl/surface/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,5 @@

#include <boost/bind.hpp>
#include <boost/function.hpp>
#include <boost/unordered_map.hpp>
#include <boost/dynamic_bitset/dynamic_bitset.hpp>
#include <boost/shared_ptr.hpp>
4 changes: 3 additions & 1 deletion surface/include/pcl/surface/grid_projection.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include <pcl/surface/boost.h>
#include <pcl/surface/reconstruction.h>

#include <unordered_map>

namespace pcl
{
/** \brief The 12 edges of a cell. */
Expand Down Expand Up @@ -92,7 +94,7 @@ namespace pcl
Eigen::Vector3f vect_at_grid_pt;
};

typedef boost::unordered_map<int, Leaf, boost::hash<int>, std::equal_to<int>, Eigen::aligned_allocator<int> > HashMap;
typedef std::unordered_map<int, Leaf, std::hash<int>, std::equal_to<int>, Eigen::aligned_allocator<std::pair<const int, Leaf>>> HashMap;

/** \brief Constructor. */
GridProjection ();
Expand Down
1 change: 0 additions & 1 deletion visualization/include/pcl/visualization/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@
#include <boost/algorithm/string/split.hpp>
#include <boost/algorithm/string/classification.hpp>
#include <boost/bind.hpp>
#include <boost/unordered_map.hpp>
#include <boost/foreach.hpp>
#ifndef Q_MOC_RUN
#include <boost/date_time/posix_time/posix_time.hpp>
Expand Down
17 changes: 9 additions & 8 deletions visualization/include/pcl/visualization/common/actor_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,16 @@

#pragma once

#include <pcl/visualization/boost.h>
#include <pcl/visualization/point_cloud_handlers.h>
#include <vector>
#include <map>
#include <pcl/PCLPointCloud2.h>
#include <boost/unordered_map.hpp>

#include <vtkLODActor.h>
#include <vtkSmartPointer.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/visualization/boost.h>

#include <map>
#include <unordered_map>
#include <vector>

template <typename T> class vtkSmartPointer;
class vtkLODActor;
Expand Down Expand Up @@ -96,13 +97,13 @@ namespace pcl
vtkSmartPointer<vtkIdTypeArray> cells;
};

typedef boost::unordered_map<std::string, CloudActor> CloudActorMap;
typedef std::unordered_map<std::string, CloudActor> CloudActorMap;
typedef boost::shared_ptr<CloudActorMap> CloudActorMapPtr;

typedef boost::unordered_map<std::string, vtkSmartPointer<vtkProp> > ShapeActorMap;
typedef std::unordered_map<std::string, vtkSmartPointer<vtkProp> > ShapeActorMap;
typedef boost::shared_ptr<ShapeActorMap> ShapeActorMapPtr;

typedef boost::unordered_map<std::string, vtkSmartPointer<vtkProp> > CoordinateActorMap;
typedef std::unordered_map<std::string, vtkSmartPointer<vtkProp> > CoordinateActorMap;
typedef boost::shared_ptr<CoordinateActorMap> CoordinateActorMapPtr;
}
}

0 comments on commit 112d870

Please sign in to comment.