Skip to content

Commit

Permalink
Replacing int* with std::int*
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi committed Oct 20, 2019
1 parent f8c37bd commit aa8a90c
Show file tree
Hide file tree
Showing 28 changed files with 190 additions and 190 deletions.
12 changes: 6 additions & 6 deletions common/include/pcl/point_traits.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,22 +74,22 @@ namespace pcl
{
// Metafunction to return enum value representing a type
template<typename T> struct asEnum {};
template<> struct asEnum<int8_t> { static const std::uint8_t value = pcl::PCLPointField::INT8; };
template<> struct asEnum<std::int8_t> { static const std::uint8_t value = pcl::PCLPointField::INT8; };
template<> struct asEnum<std::uint8_t> { static const std::uint8_t value = pcl::PCLPointField::UINT8; };
template<> struct asEnum<int16_t> { static const std::uint8_t value = pcl::PCLPointField::INT16; };
template<> struct asEnum<std::int16_t> { static const std::uint8_t value = pcl::PCLPointField::INT16; };
template<> struct asEnum<std::uint16_t> { static const std::uint8_t value = pcl::PCLPointField::UINT16; };
template<> struct asEnum<int32_t> { static const std::uint8_t value = pcl::PCLPointField::INT32; };
template<> struct asEnum<std::int32_t> { static const std::uint8_t value = pcl::PCLPointField::INT32; };
template<> struct asEnum<std::uint32_t> { static const std::uint8_t value = pcl::PCLPointField::UINT32; };
template<> struct asEnum<float> { static const std::uint8_t value = pcl::PCLPointField::FLOAT32; };
template<> struct asEnum<double> { static const std::uint8_t value = pcl::PCLPointField::FLOAT64; };

// Metafunction to return type of enum value
template<int> struct asType {};
template<> struct asType<pcl::PCLPointField::INT8> { using type = int8_t; };
template<> struct asType<pcl::PCLPointField::INT8> { using type = std::int8_t; };
template<> struct asType<pcl::PCLPointField::UINT8> { using type = std::uint8_t; };
template<> struct asType<pcl::PCLPointField::INT16> { using type = int16_t; };
template<> struct asType<pcl::PCLPointField::INT16> { using type = std::int16_t; };
template<> struct asType<pcl::PCLPointField::UINT16> { using type = std::uint16_t; };
template<> struct asType<pcl::PCLPointField::INT32> { using type = int32_t; };
template<> struct asType<pcl::PCLPointField::INT32> { using type = std::int32_t; };
template<> struct asType<pcl::PCLPointField::UINT32> { using type = std::uint32_t; };
template<> struct asType<pcl::PCLPointField::FLOAT32> { using type = float; };
template<> struct asType<pcl::PCLPointField::FLOAT64> { using type = double; };
Expand Down
26 changes: 13 additions & 13 deletions filters/include/pcl/filters/impl/conditional_removal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ pcl::PackedHSIComparison<PointT>::evaluate (const PointT &point) const
static std::uint8_t r_ = 0;
static std::uint8_t g_ = 0;
static std::uint8_t b_ = 0;
static int8_t h_ = 0;
static std::int8_t h_ = 0;
static std::uint8_t s_ = 0;
static std::uint8_t i_ = 0;

Expand All @@ -317,12 +317,12 @@ pcl::PackedHSIComparison<PointT>::evaluate (const PointT &point) const
// definitions taken from http://en.wikipedia.org/wiki/HSL_and_HSI
float hx = (2.0f * r_ - g_ - b_) / 4.0f; // hue x component -127 to 127
float hy = static_cast<float> (g_ - b_) * 111.0f / 255.0f; // hue y component -111 to 111
h_ = static_cast<int8_t> (std::atan2(hy, hx) * 128.0f / M_PI);
h_ = static_cast<std::int8_t> (std::atan2(hy, hx) * 128.0f / M_PI);

int32_t i = (r_+g_+b_)/3; // 0 to 255
std::int32_t i = (r_+g_+b_)/3; // 0 to 255
i_ = static_cast<std::uint8_t> (i);

int32_t m; // min(r,g,b)
std::int32_t m; // min(r,g,b)
m = (r_ < g_) ? r_ : g_;
m = (m < b_) ? m : b_;

Expand Down Expand Up @@ -533,9 +533,9 @@ pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val)
{
case pcl::PCLPointField::INT8 :
{
int8_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (int8_t));
return (pt_val > static_cast<int8_t>(val)) - (pt_val < static_cast<int8_t> (val));
std::int8_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (std::int8_t));
return (pt_val > static_cast<std::int8_t>(val)) - (pt_val < static_cast<std::int8_t> (val));
}
case pcl::PCLPointField::UINT8 :
{
Expand All @@ -545,9 +545,9 @@ pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val)
}
case pcl::PCLPointField::INT16 :
{
int16_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (int16_t));
return (pt_val > static_cast<int16_t>(val)) - (pt_val < static_cast<int16_t> (val));
std::int16_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (std::int16_t));
return (pt_val > static_cast<std::int16_t>(val)) - (pt_val < static_cast<std::int16_t> (val));
}
case pcl::PCLPointField::UINT16 :
{
Expand All @@ -557,9 +557,9 @@ pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val)
}
case pcl::PCLPointField::INT32 :
{
int32_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (int32_t));
return (pt_val > static_cast<int32_t> (val)) - (pt_val < static_cast<int32_t> (val));
std::int32_t pt_val;
memcpy (&pt_val, pt_data + this->offset_, sizeof (std::int32_t));
return (pt_val > static_cast<std::int32_t> (val)) - (pt_val < static_cast<std::int32_t> (val));
}
case pcl::PCLPointField::UINT32 :
{
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/impl/convolution_3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ pcl::filters::Convolution3D<PointInT, PointOutT, KernelT>::convolve (PointCloudO
#ifdef _OPENMP
#pragma omp parallel for shared (output) private (nn_indices, nn_distances) num_threads (threads_)
#endif
for (int64_t point_idx = 0; point_idx < static_cast<int64_t> (surface_->size ()); ++point_idx)
for (std::int64_t point_idx = 0; point_idx < static_cast<std::int64_t> (surface_->size ()); ++point_idx)
{
const PointInT& point_in = surface_->points [point_idx];
PointOutT& point_out = output [point_idx];
Expand Down
6 changes: 3 additions & 3 deletions filters/include/pcl/filters/impl/grid_minimum.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,10 +87,10 @@ pcl::GridMinimum<PointT>::applyFilterIndices (std::vector<int> &indices)
getMinMax3D<PointT> (*input_, *indices_, min_p, max_p);

// Check that the resolution is not too small, given the size of the data
int64_t dx = static_cast<int64_t> ((max_p[0] - min_p[0]) * inverse_resolution_)+1;
int64_t dy = static_cast<int64_t> ((max_p[1] - min_p[1]) * inverse_resolution_)+1;
std::int64_t dx = static_cast<std::int64_t> ((max_p[0] - min_p[0]) * inverse_resolution_)+1;
std::int64_t dy = static_cast<std::int64_t> ((max_p[1] - min_p[1]) * inverse_resolution_)+1;

if ((dx*dy) > static_cast<int64_t> (std::numeric_limits<int32_t>::max ()))
if ((dx*dy) > static_cast<std::int64_t> (std::numeric_limits<std::int32_t>::max ()))
{
PCL_WARN ("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName ().c_str ());
return;
Expand Down
8 changes: 4 additions & 4 deletions filters/include/pcl/filters/impl/voxel_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,11 +234,11 @@ pcl::VoxelGrid<PointT>::applyFilter (PointCloud &output)
getMinMax3D<PointT> (*input_, *indices_, min_p, max_p);

// Check that the leaf size is not too small, given the size of the data
int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;

if ((dx*dy*dz) > static_cast<int64_t>(std::numeric_limits<int32_t>::max()))
if ((dx*dy*dz) > static_cast<std::int64_t>(std::numeric_limits<std::int32_t>::max()))
{
PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
output = *input_;
Expand Down
8 changes: 4 additions & 4 deletions filters/include/pcl/filters/impl/voxel_grid_covariance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,11 +72,11 @@ pcl::VoxelGridCovariance<PointT>::applyFilter (PointCloud &output)
getMinMax3D<PointT> (*input_, min_p, max_p);

// Check that the leaf size is not too small, given the size of the data
int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;

if((dx*dy*dz) > std::numeric_limits<int32_t>::max())
if((dx*dy*dz) > std::numeric_limits<std::int32_t>::max())
{
PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
output.clear();
Expand Down
8 changes: 4 additions & 4 deletions filters/src/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,11 +222,11 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
getMinMax3D (input_, x_idx_, y_idx_, z_idx_, min_p, max_p);

// Check that the leaf size is not too small, given the size of the data
int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;

if( (dx*dy*dz) > static_cast<int64_t>(std::numeric_limits<int32_t>::max()) )
if( (dx*dy*dz) > static_cast<std::int64_t>(std::numeric_limits<std::int32_t>::max()) )
{
PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
//output.width = output.height = 0;
Expand Down
8 changes: 4 additions & 4 deletions filters/src/voxel_grid_label.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,11 +66,11 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output)
getMinMax3D<pcl::PointXYZRGBL>(*input_, min_p, max_p);

// Check that the leaf size is not too small, given the size of the data
int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;

if( (dx*dy*dz) > static_cast<int64_t>(std::numeric_limits<int32_t>::max()) )
if( (dx*dy*dz) > static_cast<std::int64_t>(std::numeric_limits<std::int32_t>::max()) )
{
PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.", getClassName().c_str());
output.clear();
Expand Down
12 changes: 6 additions & 6 deletions gpu/people/include/pcl/gpu/people/tree.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,21 +69,21 @@ namespace pcl
using std::int32_t;
using std::uint32_t;

using Attrib = int16_t;
using Attrib = std::int16_t;
using Label = std::uint8_t;
using Label32 = std::uint32_t;
using Depth = std::uint16_t;

struct AttribLocation
{
inline AttribLocation () {du1=dv1=du2=dv2=0;}
inline AttribLocation (int u1, int v1, int u2, int v2): du1 (static_cast<int16_t>(u1)),
dv1 (static_cast<int16_t>(v1)),
du2 (static_cast<int16_t>(u2)),
dv2 (static_cast<int16_t>(v2))
inline AttribLocation (int u1, int v1, int u2, int v2): du1 (static_cast<std::int16_t>(u1)),
dv1 (static_cast<std::int16_t>(v1)),
du2 (static_cast<std::int16_t>(u2)),
dv2 (static_cast<std::int16_t>(v2))
{}

int16_t du1,dv1,du2,dv2;
std::int16_t du1,dv1,du2,dv2;
};

////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion gpu/people/src/bodyparts_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,7 +270,7 @@ pcl::gpu::people::RDFBodyPartsDetector::processProb (const pcl::device::Depth& d

// Process the depthimage into probabilities (CUDA)
//impl_->process(depth, labels_);
//impl_->processProb(depth, labels_, P_l_, (int) std::numeric_limits<int16_t>::max());
//impl_->processProb(depth, labels_, P_l_, (int) std::numeric_limits<std::int16_t>::max());
impl_->processProb(depth, labels_, P_l_, std::numeric_limits<int>::max());
}

Expand Down
4 changes: 2 additions & 2 deletions gpu/people/src/trees.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,8 @@ pcl::gpu::people::trees::runThroughTree( int maxDepth,
const AttribLocation& loc = node.loc;
std::uint16_t d1 = tfetch((float)(x+loc.du1*scale), (float)(y+loc.dv1*scale));
std::uint16_t d2 = tfetch((float)(x+loc.du2*scale), (float)(y+loc.dv2*scale));
int32_t delta = int32_t(d1) - int32_t(d2);
bool test = delta > int32_t(node.thresh);
std::int32_t delta = std::int32_t(d1) - std::int32_t(d2);
bool test = delta > std::int32_t(node.thresh);

nid = test ? (nid*2+2) : (nid*2+1);
}
Expand Down
16 changes: 8 additions & 8 deletions io/include/pcl/io/file_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -263,15 +263,15 @@ namespace pcl
}

template <> inline void
copyValueString<int8_t> (const pcl::PCLPointCloud2 &cloud,
copyValueString<std::int8_t> (const pcl::PCLPointCloud2 &cloud,
const unsigned int point_index,
const int point_size,
const unsigned int field_idx,
const unsigned int fields_count,
std::ostream &stream)
{
int8_t value;
memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (int8_t)], sizeof (int8_t));
std::int8_t value;
memcpy (&value, &cloud.data[point_index * point_size + cloud.fields[field_idx].offset + fields_count * sizeof (std::int8_t)], sizeof (std::int8_t));
//Cast to int to prevent value is handled as char
stream << boost::numeric_cast<int>(value);
}
Expand Down Expand Up @@ -359,13 +359,13 @@ namespace pcl
}

template <> inline void
copyStringValue<int8_t> (const std::string &st, pcl::PCLPointCloud2 &cloud,
copyStringValue<std::int8_t> (const std::string &st, pcl::PCLPointCloud2 &cloud,
unsigned int point_index, unsigned int field_idx, unsigned int fields_count)
{
int8_t value;
std::int8_t value;
if (boost::iequals(st, "nan"))
{
value = static_cast<int8_t> (std::numeric_limits<int>::quiet_NaN ());
value = static_cast<std::int8_t> (std::numeric_limits<int>::quiet_NaN ());
cloud.is_dense = false;
}
else
Expand All @@ -376,12 +376,12 @@ namespace pcl
//is >> val; -- unfortunately this fails on older GCC versions and CLANG on MacOS
if (!(is >> val))
val = static_cast<int> (atof (st.c_str ()));
value = static_cast<int8_t> (val);
value = static_cast<std::int8_t> (val);
}

memcpy (&cloud.data[point_index * cloud.point_step +
cloud.fields[field_idx].offset +
fields_count * sizeof (int8_t)], reinterpret_cast<char*> (&value), sizeof (int8_t));
fields_count * sizeof (std::int8_t)], reinterpret_cast<char*> (&value), sizeof (std::int8_t));
}

template <> inline void
Expand Down
36 changes: 18 additions & 18 deletions io/include/pcl/io/impl/pcd_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -488,9 +488,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
{
case pcl::PCLPointField::INT8:
{
int8_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t));
stream << boost::numeric_cast<int32_t>(value);
std::int8_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (std::int8_t), sizeof (std::int8_t));
stream << boost::numeric_cast<std::int32_t>(value);
break;
}
case pcl::PCLPointField::UINT8:
Expand All @@ -502,9 +502,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
}
case pcl::PCLPointField::INT16:
{
int16_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t));
stream << boost::numeric_cast<int16_t>(value);
std::int16_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (std::int16_t), sizeof (std::int16_t));
stream << boost::numeric_cast<std::int16_t>(value);
break;
}
case pcl::PCLPointField::UINT16:
Expand All @@ -516,9 +516,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud<
}
case pcl::PCLPointField::INT32:
{
int32_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t));
stream << boost::numeric_cast<int32_t>(value);
std::int32_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[i]) + fields[d].offset + c * sizeof (std::int32_t), sizeof (std::int32_t));
stream << boost::numeric_cast<std::int32_t>(value);
break;
}
case pcl::PCLPointField::UINT32:
Expand Down Expand Up @@ -771,9 +771,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
{
case pcl::PCLPointField::INT8:
{
int8_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (int8_t), sizeof (int8_t));
stream << boost::numeric_cast<int32_t>(value);
std::int8_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (std::int8_t), sizeof (std::int8_t));
stream << boost::numeric_cast<std::int32_t>(value);
break;
}
case pcl::PCLPointField::UINT8:
Expand All @@ -785,9 +785,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
}
case pcl::PCLPointField::INT16:
{
int16_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (int16_t), sizeof (int16_t));
stream << boost::numeric_cast<int16_t>(value);
std::int16_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (std::int16_t), sizeof (std::int16_t));
stream << boost::numeric_cast<std::int16_t>(value);
break;
}
case pcl::PCLPointField::UINT16:
Expand All @@ -799,9 +799,9 @@ pcl::PCDWriter::writeASCII (const std::string &file_name,
}
case pcl::PCLPointField::INT32:
{
int32_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (int32_t), sizeof (int32_t));
stream << boost::numeric_cast<int32_t>(value);
std::int32_t value;
memcpy (&value, reinterpret_cast<const char*> (&cloud.points[index]) + fields[d].offset + c * sizeof (std::int32_t), sizeof (std::int32_t));
stream << boost::numeric_cast<std::int32_t>(value);
break;
}
case pcl::PCLPointField::UINT32:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ namespace openni_wrapper
lookupTable_.resize(table_size);

// constants taken from openni driver
constexpr int16_t nConstShift = 800;
constexpr std::int16_t nConstShift = 800;
constexpr double nParamCoeff = 4.000000;
constexpr double dPlanePixelSize = 0.104200;
constexpr double nShiftScale = 10.000000;
Expand Down
Loading

0 comments on commit aa8a90c

Please sign in to comment.