Skip to content

Commit

Permalink
[outofcore] Migrate mutex, locks and cvs to C++14 (#3074)
Browse files Browse the repository at this point in the history
[outofcore] Migrate mutex, locks and cvs to C++14
  • Loading branch information
SergioRAgostinho authored and taketwo committed May 9, 2019
1 parent abda376 commit db7eb3c
Show file tree
Hide file tree
Showing 15 changed files with 64 additions and 75 deletions.
12 changes: 6 additions & 6 deletions outofcore/include/pcl/outofcore/impl/monitor_queue.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
#ifndef PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_
#define PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_

#include <boost/thread/condition.hpp>

#include <condition_variable>
#include <mutex>
#include <queue>

template<typename DataT>
Expand All @@ -14,15 +14,15 @@ class MonitorQueue : boost::noncopyable
void
push (const DataT& newData)
{
boost::mutex::scoped_lock lock (monitor_mutex_);
std::lock_guard<std::mutex> lock (monitor_mutex_);
queue_.push (newData);
item_available_.notify_one ();
}

DataT
pop ()
{
boost::mutex::scoped_lock lock (monitor_mutex_);
std::unique_lock<std::mutex> lock (monitor_mutex_);

if (queue_.empty ())
{
Expand All @@ -37,8 +37,8 @@ class MonitorQueue : boost::noncopyable

private:
std::queue<DataT> queue_;
boost::mutex monitor_mutex_;
boost::condition item_available_;
std::mutex monitor_mutex_;
std::condition_variable item_available_;
};

#endif //PCL_OUTOFCORE_MONITOR_QUEUE_IMPL_H_
30 changes: 15 additions & 15 deletions outofcore/include/pcl/outofcore/impl/octree_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ namespace pcl
template<typename ContainerT, typename PointT> boost::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addDataToLeaf (const AlignedPointTVector& p)
{
boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_);
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);

const bool _FORCE_BB_CHECK = true;

Expand Down Expand Up @@ -243,7 +243,7 @@ namespace pcl
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud_and_genLOD (PointCloudConstPtr point_cloud)
{
// Lock the tree while writing
boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_);
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
boost::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (point_cloud->points, false);
return (pt_added);
}
Expand All @@ -254,7 +254,7 @@ namespace pcl
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud)
{
// Lock the tree while writing
boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_);
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
boost::uint64_t pt_added = root_node_->addPointCloud_and_genLOD (input_cloud);

PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBase::%s] Points added %lu, points in input cloud, %lu\n",__FUNCTION__, pt_added, input_cloud->width*input_cloud->height );
Expand All @@ -270,7 +270,7 @@ namespace pcl
OutofcoreOctreeBase<ContainerT, PointT>::addDataToLeaf_and_genLOD (AlignedPointTVector& src)
{
// Lock the tree while writing
boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_);
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
boost::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (src, false);
return (pt_added);
}
Expand All @@ -280,7 +280,7 @@ namespace pcl
template<typename Container, typename PointT> void
OutofcoreOctreeBase<Container, PointT>::queryFrustum (const double planes[24], std::list<std::string>& file_names) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
root_node_->queryFrustum (planes, file_names, this->getTreeDepth());
}

Expand All @@ -289,7 +289,7 @@ namespace pcl
template<typename Container, typename PointT> void
OutofcoreOctreeBase<Container, PointT>::queryFrustum(const double *planes, std::list<std::string>& file_names, const boost::uint32_t query_depth) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
root_node_->queryFrustum (planes, file_names, query_depth);
}

Expand All @@ -303,7 +303,7 @@ namespace pcl
std::list<std::string>& file_names,
const boost::uint32_t query_depth) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
root_node_->queryFrustum (planes, eye, view_projection_matrix, file_names, query_depth);
}

Expand All @@ -312,7 +312,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, AlignedPointTVector& dst) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
dst.clear ();
PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBaseNode] Querying Bounding Box %.2lf %.2lf %.2lf, %.2lf %.2lf %.2lf", min[0], min[1], min[2], max[0], max[1], max[2]);
root_node_->queryBBIncludes (min, max, query_depth, dst);
Expand All @@ -323,7 +323,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);

dst_blob->data.clear ();
dst_blob->width = 0;
Expand All @@ -337,7 +337,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes_subsample (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint64_t query_depth, const double percent, AlignedPointTVector& dst) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
dst.clear ();
root_node_->queryBBIncludes_subsample (min, max, query_depth, percent, dst);
}
Expand Down Expand Up @@ -374,7 +374,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::printBoundingBox(const size_t query_depth) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
root_node_->printBoundingBox (query_depth);
}

Expand All @@ -383,7 +383,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers, const size_t query_depth) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
if (query_depth > metadata_->getDepth ())
{
root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, metadata_->getDepth ());
Expand All @@ -399,7 +399,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::getOccupiedVoxelCenters(std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &voxel_centers, const size_t query_depth) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
if (query_depth > metadata_->getDepth ())
{
root_node_->getOccupiedVoxelCentersRecursive (voxel_centers, metadata_->getDepth ());
Expand All @@ -415,7 +415,7 @@ namespace pcl
template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIntersects (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::uint32_t query_depth, std::list<std::string>& bin_name) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
bin_name.clear ();
#if defined _MSC_VER
#pragma warning(push)
Expand Down Expand Up @@ -565,7 +565,7 @@ namespace pcl
return;
}

boost::unique_lock < boost::shared_mutex > lock (read_write_mutex_);
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);

const int number_of_nodes = 1;

Expand Down
7 changes: 3 additions & 4 deletions outofcore/include/pcl/outofcore/impl/octree_base_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ namespace pcl
const std::string OutofcoreOctreeBaseNode<ContainerT, PointT>::node_container_extension = ".oct_dat";

template<typename ContainerT, typename PointT>
boost::mutex OutofcoreOctreeBaseNode<ContainerT, PointT>::rng_mutex_;
std::mutex OutofcoreOctreeBaseNode<ContainerT, PointT>::rng_mutex_;

template<typename ContainerT, typename PointT>
std::mt19937 OutofcoreOctreeBaseNode<ContainerT, PointT>::rng_;
Expand Down Expand Up @@ -594,7 +594,7 @@ namespace pcl
insertBuff.resize(samplesize);

// Create random number generator
boost::mutex::scoped_lock lock(rng_mutex_);
std::lock_guard<std::mutex> lock(rng_mutex_);
std::uniform_int_distribution<uint64_t> buffdist(0, inputsize-1);

// Randomly pick sampled points
Expand All @@ -607,7 +607,7 @@ namespace pcl
// Have to do it the slow way
else
{
boost::mutex::scoped_lock lock(rng_mutex_);
std::lock_guard<std::mutex> lock(rng_mutex_);
std::bernoulli_distribution buffdist(percent);

for(uint64_t i = 0; i < inputsize; ++i)
Expand Down Expand Up @@ -1791,7 +1791,6 @@ namespace pcl
payload_->readRange (0, payload_->size (), payload_cache);

{
//boost::mutex::scoped_lock lock(queryBBIncludes_vector_mutex);
v.insert (v.end (), payload_cache.begin (), payload_cache.end ());
}
}
Expand Down
12 changes: 6 additions & 6 deletions outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ namespace pcl
namespace outofcore
{
template<typename PointT>
boost::mutex OutofcoreOctreeDiskContainer<PointT>::rng_mutex_;
std::mutex OutofcoreOctreeDiskContainer<PointT>::rng_mutex_;

template<typename PointT> boost::mt19937
OutofcoreOctreeDiskContainer<PointT>::rand_gen_ (static_cast<unsigned int> (std::time(nullptr)));
Expand All @@ -89,7 +89,7 @@ namespace pcl
{
boost::uuids::uuid u;
{
boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);
u = uuid_gen_ ();
}

Expand Down Expand Up @@ -297,7 +297,7 @@ namespace pcl
if (buffcount > 0)
{
{
boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);
boost::bernoulli_distribution<double> buffdist (percent);
boost::variate_generator<boost::mt19937&, boost::bernoulli_distribution<double> > buffcoin (rand_gen_, buffdist);

Expand All @@ -316,7 +316,7 @@ namespace pcl
//pregen and then sort the offsets to reduce the amount of seek
std::vector < uint64_t > offsets;
{
boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);

boost::bernoulli_distribution<double> filedist (percent);
boost::variate_generator<boost::mt19937&, boost::bernoulli_distribution<double> > filecoin (rand_gen_, filedist);
Expand Down Expand Up @@ -398,7 +398,7 @@ namespace pcl
if (buffcount > 0)
{
{
boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);

boost::uniform_int < uint64_t > buffdist (0, buffcount - 1);
boost::variate_generator<boost::mt19937&, boost::uniform_int<uint64_t> > buffdie (rand_gen_, buffdist);
Expand All @@ -416,7 +416,7 @@ namespace pcl
//pregen and then sort the offsets to reduce the amount of seek
std::vector < uint64_t > offsets;
{
boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);

offsets.resize (filesamp);
boost::uniform_int < uint64_t > filedist (filestart, filestart + filecount - 1);
Expand Down
4 changes: 2 additions & 2 deletions outofcore/include/pcl/outofcore/impl/octree_ram_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace pcl
namespace outofcore
{
template<typename PointT>
boost::mutex OutofcoreOctreeRamContainer<PointT>::rng_mutex_;
std::mutex OutofcoreOctreeRamContainer<PointT>::rng_mutex_;

template<typename PointT>
std::mt19937 OutofcoreOctreeRamContainer<PointT>::rng_ ([] {std::random_device rd; return rd(); } ());
Expand Down Expand Up @@ -122,7 +122,7 @@ namespace pcl
{
uint64_t samplesize = static_cast<uint64_t> (percent * static_cast<double> (count));

boost::mutex::scoped_lock lock (rng_mutex_);
std::lock_guard<std::mutex> lock (rng_mutex_);

std::uniform_int_distribution < uint64_t > buffdist (start, start + count);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@

#pragma once

#include <mutex>
#include <string>
#include <vector>

#include <pcl/outofcore/boost.h>
#include <boost/thread/mutex.hpp>

namespace pcl
{
Expand Down Expand Up @@ -96,7 +96,7 @@ namespace pcl

AlignedPointTVector container_;

static boost::mutex rng_mutex_;
static std::mutex rng_mutex_;
};
}//namespace outofcore
}//namespace pcl
6 changes: 3 additions & 3 deletions outofcore/include/pcl/outofcore/octree_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@

#include <pcl/PCLPointCloud2.h>

#include <boost/thread/shared_mutex.hpp>
#include <shared_mutex>

namespace pcl
{
Expand Down Expand Up @@ -382,7 +382,7 @@ namespace pcl
inline virtual void
queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, std::list<std::string> &filenames) const
{
boost::shared_lock < boost::shared_mutex > lock (read_write_mutex_);
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
filenames.clear ();
this->root_node_->queryBBIntersects (min, max, query_depth, filenames);
}
Expand Down Expand Up @@ -634,7 +634,7 @@ namespace pcl
OutofcoreNodeType* root_node_;

/** \brief shared mutex for controlling read/write access to disk */
mutable boost::shared_mutex read_write_mutex_;
mutable std::shared_timed_mutex read_write_mutex_;

OutofcoreOctreeBaseMetadata::Ptr metadata_;

Expand Down
3 changes: 2 additions & 1 deletion outofcore/include/pcl/outofcore/octree_base_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

#pragma once

#include <mutex>
#include <random>

#include <pcl/common/io.h>
Expand Down Expand Up @@ -559,7 +560,7 @@ namespace pcl
boost::shared_ptr<ContainerT> payload_;

/** \brief Random number generator mutex */
static boost::mutex rng_mutex_;
static std::mutex rng_mutex_;

/** \brief Mersenne Twister: A 623-dimensionally equidistributed uniform
* pseudo-random number generator */
Expand Down
3 changes: 2 additions & 1 deletion outofcore/include/pcl/outofcore/octree_disk_container.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#pragma once

// C++
#include <mutex>
#include <vector>
#include <string>

Expand Down Expand Up @@ -296,7 +297,7 @@ namespace pcl

static const uint64_t WRITE_BUFF_MAX_;

static boost::mutex rng_mutex_;
static std::mutex rng_mutex_;
static boost::mt19937 rand_gen_;
static boost::uuids::basic_random_generator<boost::mt19937> uuid_gen_;

Expand Down
3 changes: 2 additions & 1 deletion outofcore/include/pcl/outofcore/octree_ram_container.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#pragma once

// C++
#include <mutex>
#include <random>
#include <vector>

Expand Down Expand Up @@ -165,7 +166,7 @@ namespace pcl
/** \brief linear container to hold the points */
AlignedPointTVector container_;

static boost::mutex rng_mutex_;
static std::mutex rng_mutex_;
static std::mt19937 rng_;
};
}
Expand Down
Loading

0 comments on commit db7eb3c

Please sign in to comment.