Skip to content

Commit

Permalink
Replacing boost::int_t with std::int_t
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi committed Oct 18, 2019
1 parent 25f236c commit 57412c5
Show file tree
Hide file tree
Showing 23 changed files with 154 additions and 154 deletions.
2 changes: 1 addition & 1 deletion cuda/io/include/pcl/cuda/io/disparity_to_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ namespace cuda
bool downsample = false, int stride = 2, int smoothing_nr_iterations = 0, int smoothing_filter_size = 2);

template <template <typename> class Storage> void
compute (const boost::uint16_t* depth_image,
compute (const std::uint16_t* depth_image,
const OpenNIRGB* rgb_image,
int width, int height,
float constant,
Expand Down
6 changes: 3 additions & 3 deletions cuda/io/src/disparity_to_cloud.cu
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ ComputeXYZRGB::operator () (const Tuple &t)

//////////////////////////////////////////////////////////////////////////
template <template <typename> class Storage> void
DisparityToCloud::compute (const boost::uint16_t* depth_image,
DisparityToCloud::compute (const std::uint16_t* depth_image,
const OpenNIRGB* rgb_image,
int width, int height,
float constant,
Expand Down Expand Up @@ -512,14 +512,14 @@ DisparityToCloud::compute<Device> (const boost::shared_ptr<openni_wrapper::Depth
PointCloudAOS<Device>::Ptr &output,
bool downsample, int stridem, int, int);
template PCL_EXPORTS void
DisparityToCloud::compute<Host> (const boost::uint16_t* depth_image,
DisparityToCloud::compute<Host> (const std::uint16_t* depth_image,
const OpenNIRGB* rgb_image,
int width, int height,
float constant,
typename PointCloudAOS<Host>::Ptr &output,
int smoothing_nr_iterations, int smoothing_filter_size);
template PCL_EXPORTS void
DisparityToCloud::compute<Device> (const boost::uint16_t* depth_image,
DisparityToCloud::compute<Device> (const std::uint16_t* depth_image,
const OpenNIRGB* rgb_image,
int width, int height,
float constant,
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/gfpfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,7 @@ pcl::GFPFHEstimation<PointInT, PointNT, PointOutT>::computeHIKDistance (const st
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT> boost::uint32_t
template <typename PointInT, typename PointNT, typename PointOutT> std::uint32_t
pcl::GFPFHEstimation<PointInT, PointNT, PointOutT>::getDominantLabel (const std::vector<int>& indices)
{
std::vector<uint32_t> counts (getNumberOfClasses () + 1, 0);
Expand Down
10 changes: 5 additions & 5 deletions gpu/people/include/pcl/gpu/people/tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,11 +63,11 @@ namespace pcl
// ###############################################
// base data types used in the structures

using boost::uint8_t;
using boost::int16_t;
using boost::uint16_t;
using boost::int32_t;
using boost::uint32_t;
using std::uint8_t;
using std::int16_t;
using std::uint16_t;
using std::int32_t;
using std::uint32_t;

using Attrib = int16_t;
using Label = uint8_t;
Expand Down
6 changes: 3 additions & 3 deletions gpu/people/src/trees.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ namespace pcl
*/
struct Tex2Dfetcher
{
Tex2Dfetcher( const boost::uint16_t* dmap, int W, int H ) : m_dmap(dmap), m_W(W), m_H(H) {}
Tex2Dfetcher( const std::uint16_t* dmap, int W, int H ) : m_dmap(dmap), m_W(W), m_H(H) {}

inline boost::uint16_t operator () ( float uf, float vf )
inline std::uint16_t operator () ( float uf, float vf )
{
int u = static_cast<int>(uf);
int v = static_cast<int>(vf);
Expand All @@ -76,7 +76,7 @@ namespace pcl

return m_dmap[u+v*m_W]; // this is going to be SLOOOWWW
}
const boost::uint16_t* m_dmap;
const std::uint16_t* m_dmap;
const int m_W;
const int m_H;
};
Expand Down
10 changes: 5 additions & 5 deletions io/include/pcl/compression/entropy_range_coder.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,9 @@
namespace pcl
{

using boost::uint8_t;
using boost::uint32_t;
using boost::uint64_t;
using std::uint8_t;
using std::uint32_t;
using std::uint64_t;

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/** \brief @b AdaptiveRangeCoder compression class
Expand Down Expand Up @@ -97,7 +97,7 @@ namespace pcl
decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector<char>& outputByteVector_arg);

protected:
using DWord = boost::uint32_t; // 4 bytes
using DWord = std::uint32_t; // 4 bytes

private:
/** vector containing compressed data
Expand Down Expand Up @@ -162,7 +162,7 @@ namespace pcl
decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector<char>& outputByteVector_arg);

protected:
using DWord = boost::uint32_t; // 4 bytes
using DWord = std::uint32_t; // 4 bytes

/** \brief Helper function to calculate the binary logarithm
* \param n_arg: some value
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/ply/ply.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,12 +55,12 @@ namespace pcl
{
namespace ply
{
using int8 = boost::int8_t;
using int16 = boost::int16_t;
using int32 = boost::int32_t;
using uint8 = boost::uint8_t;
using uint16 = boost::uint16_t;
using uint32 = boost::uint32_t;
using int8 = std::int8_t;
using int16 = std::int16_t;
using int32 = std::int32_t;
using uint8 = std::uint8_t;
using uint16 = std::uint16_t;
using uint32 = std::uint32_t;

using float32 = float;
using float64 = double;
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/robot_eye_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,6 @@ namespace pcl
void socketCallback (const boost::system::error_code& error, std::size_t number_of_bytes);
void convertPacketData (unsigned char *data_packet, size_t length);
void computeXYZI (pcl::PointXYZI& point_XYZI, unsigned char* point_data);
void computeTimestamp (boost::uint32_t& timestamp, unsigned char* point_data);
void computeTimestamp (std::uint32_t& timestamp, unsigned char* point_data);
};
}
2 changes: 1 addition & 1 deletion io/src/ascii_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ pcl::ASCIIReader::parse (
}

//////////////////////////////////////////////////////////////////////////////
boost::uint32_t
std::uint32_t
pcl::ASCIIReader::typeSize (int type)
{
switch (type)
Expand Down
6 changes: 3 additions & 3 deletions io/src/robot_eye_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ pcl::RobotEyeGrabber::convertPacketData (unsigned char *data_packet, size_t leng
size_t response_size = 6; //"EBRBEP"
if( !strncmp((char*)(data_packet), "EBRBEP", response_size) )
{
boost::uint32_t timestamp; // counts of a 66 MHz clock since power-on of eye.
std::uint32_t timestamp; // counts of a 66 MHz clock since power-on of eye.
computeTimestamp(timestamp, data_packet + response_size);
//std::cout << "Timestamp: " << timestamp << std::endl;
offset = (response_size + sizeof(timestamp));
Expand Down Expand Up @@ -247,9 +247,9 @@ pcl::RobotEyeGrabber::computeXYZI (pcl::PointXYZI& point, unsigned char* point_d

/////////////////////////////////////////////////////////////////////////////
void
pcl::RobotEyeGrabber::computeTimestamp (boost::uint32_t& timestamp, unsigned char* point_data)
pcl::RobotEyeGrabber::computeTimestamp (std::uint32_t& timestamp, unsigned char* point_data)
{
boost::uint32_t buffer;
std::uint32_t buffer;
buffer = point_data[0] << 24;
buffer |= point_data[1] << 16;
buffer |= point_data[2] << 8;
Expand Down
42 changes: 21 additions & 21 deletions outofcore/include/pcl/outofcore/impl/octree_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ namespace pcl
this->enlargeToCube (tmp_min, tmp_max);

//Compute the depth of the tree given the resolution
boost::uint64_t depth = this->calculateDepth (tmp_min, tmp_max, resolution_arg);
std::uint64_t depth = this->calculateDepth (tmp_min, tmp_max, resolution_arg);

//Create a new outofcore tree
this->init (depth, tmp_min, tmp_max, root_node_name, coord_sys);
Expand All @@ -124,7 +124,7 @@ namespace pcl
////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT>
OutofcoreOctreeBase<ContainerT, PointT>::OutofcoreOctreeBase (const boost::uint64_t max_depth, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::filesystem::path& root_node_name, const std::string& coord_sys)
OutofcoreOctreeBase<ContainerT, PointT>::OutofcoreOctreeBase (const std::uint64_t max_depth, const Eigen::Vector3d& min, const Eigen::Vector3d& max, const boost::filesystem::path& root_node_name, const std::string& coord_sys)
: root_node_()
, read_write_mutex_ ()
, metadata_ (new OutofcoreOctreeBaseMetadata ())
Expand Down Expand Up @@ -204,7 +204,7 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addDataToLeaf (const AlignedPointTVector& p)
{
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
Expand All @@ -220,15 +220,15 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud (PointCloudConstPtr point_cloud)
{
return (addDataToLeaf (point_cloud->points));
}

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check)
{
uint64_t pt_added = this->root_node_->addPointCloud (input_cloud, skip_bb_check) ;
Expand All @@ -239,23 +239,23 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud_and_genLOD (PointCloudConstPtr point_cloud)
{
// Lock the tree while writing
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);
std::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (point_cloud->points, false);
return (pt_added);
}

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud)
{
// Lock the tree while writing
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
boost::uint64_t pt_added = root_node_->addPointCloud_and_genLOD (input_cloud);
std::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 @@ -266,12 +266,12 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::addDataToLeaf_and_genLOD (AlignedPointTVector& src)
{
// Lock the tree while writing
std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_);
boost::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (src, false);
std::uint64_t pt_added = root_node_->addDataToLeaf_and_genLOD (src, false);
return (pt_added);
}

Expand All @@ -287,7 +287,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
OutofcoreOctreeBase<Container, PointT>::queryFrustum(const double *planes, std::list<std::string>& file_names, const std::uint32_t query_depth) const
{
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
root_node_->queryFrustum (planes, file_names, query_depth);
Expand All @@ -301,7 +301,7 @@ namespace pcl
const Eigen::Vector3d &eye,
const Eigen::Matrix4d &view_projection_matrix,
std::list<std::string>& file_names,
const boost::uint32_t query_depth) const
const std::uint32_t query_depth) const
{
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 @@ -310,7 +310,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
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const std::uint64_t query_depth, AlignedPointTVector& dst) const
{
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
dst.clear ();
Expand All @@ -321,7 +321,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
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const std::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr& dst_blob) const
{
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);

Expand All @@ -335,7 +335,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
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIncludes_subsample (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const std::uint64_t query_depth, const double percent, AlignedPointTVector& dst) const
{
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
dst.clear ();
Expand Down Expand Up @@ -413,7 +413,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
OutofcoreOctreeBase<ContainerT, PointT>::queryBBIntersects (const Eigen::Vector3d& min, const Eigen::Vector3d& max, const std::uint32_t query_depth, std::list<std::string>& bin_name) const
{
std::shared_lock < std::shared_timed_mutex > lock (read_write_mutex_);
bin_name.clear ();
Expand Down Expand Up @@ -546,7 +546,7 @@ namespace pcl
////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> double
OutofcoreOctreeBase<ContainerT, PointT>::getVoxelSideLength (const boost::uint64_t& depth) const
OutofcoreOctreeBase<ContainerT, PointT>::getVoxelSideLength (const std::uint64_t& depth) const
{
Eigen::Vector3d min, max;
this->getBoundingBox (min, max);
Expand Down Expand Up @@ -681,7 +681,7 @@ namespace pcl
////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> void
OutofcoreOctreeBase<ContainerT, PointT>::incrementPointsInLOD (boost::uint64_t depth, boost::uint64_t new_point_count)
OutofcoreOctreeBase<ContainerT, PointT>::incrementPointsInLOD (std::uint64_t depth, std::uint64_t new_point_count)
{
if (std::numeric_limits<uint64_t>::max () - metadata_->getLODPoints (depth) < new_point_count)
{
Expand Down Expand Up @@ -725,7 +725,7 @@ namespace pcl

////////////////////////////////////////////////////////////////////////////////

template<typename ContainerT, typename PointT> boost::uint64_t
template<typename ContainerT, typename PointT> std::uint64_t
OutofcoreOctreeBase<ContainerT, PointT>::calculateDepth (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb, const double leaf_resolution)
{
//Assume cube
Expand All @@ -734,7 +734,7 @@ namespace pcl
if (side_length < leaf_resolution)
return (0);

boost::uint64_t res = static_cast<boost::uint64_t> (std::ceil (std::log2 (side_length / leaf_resolution)));
std::uint64_t res = static_cast<std::uint64_t> (std::ceil (std::log2 (side_length / leaf_resolution)));

PCL_DEBUG ("[pcl::outofcore::OutofcoreOctreeBase::calculateDepth] Setting depth to %d\n",res);
return (res);
Expand Down
Loading

0 comments on commit 57412c5

Please sign in to comment.