Skip to content

Commit

Permalink
Added readability-container-data-pointer clang-tidy check
Browse files Browse the repository at this point in the history
Removed extraneous parentheses left from conversion to data()


Removed extraneous conversion to data()


Disabled clang-tidy for more Eigen::Vector4f


Fixed typo in NOLINTEND
  • Loading branch information
gnawme committed Jan 24, 2023
1 parent 407ee41 commit 8223fb2
Show file tree
Hide file tree
Showing 45 changed files with 169 additions and 154 deletions.
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ Checks: >
performance-no-automatic-move,
performance-noexcept-move-constructor,
performance-type-promotion-in-math-fn,
readability-container-data-pointer,
readability-container-size-empty,
readability-delete-null-pointer,
readability-duplicate-include,
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/common/impl/intersections.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ lineWithLineIntersection (const pcl::ModelCoefficients &line_a,
const pcl::ModelCoefficients &line_b,
Eigen::Vector4f &point, double sqr_eps)
{
Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a.values[0], line_a.values.size ());
Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b.values[0], line_b.values.size ());
Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (line_a.values.data(), line_a.values.size ());
Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (line_b.values.data(), line_b.values.size ());
return (lineWithLineIntersection (coeff1, coeff2, point, sqr_eps));
}

Expand Down
16 changes: 8 additions & 8 deletions common/include/pcl/common/impl/io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ namespace detail
pcl::PointCloud<PointT> &cloud_out)
{
// Use std::copy directly, if the point types of two clouds are same
std::copy (&cloud_in[0], (&cloud_in[0]) + cloud_in.size (), &cloud_out[0]);
std::copy (cloud_in.data(), cloud_in.data() + cloud_in.size (), cloud_out.data());
}

} // namespace detail
Expand Down Expand Up @@ -360,8 +360,8 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>

if (border_type == pcl::BORDER_TRANSPARENT)
{
const PointT* in = &(cloud_in[0]);
PointT* out = &(cloud_out[0]);
const PointT* in = cloud_in.data();
PointT* out = cloud_out.data();
PointT* out_inner = out + cloud_out.width*top + left;
for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
{
Expand All @@ -387,8 +387,8 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>
for (int i = 0; i < right; i++)
padding[i+left] = pcl::interpolatePointIndex (cloud_in.width+i, cloud_in.width, border_type);

const PointT* in = &(cloud_in[0]);
PointT* out = &(cloud_out[0]);
const PointT* in = cloud_in.data();
PointT* out = cloud_out.data();
PointT* out_inner = out + cloud_out.width*top + left;

for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
Expand Down Expand Up @@ -428,9 +428,9 @@ copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT>
int right = cloud_out.width - cloud_in.width - left;
int bottom = cloud_out.height - cloud_in.height - top;
std::vector<PointT> buff (cloud_out.width, value);
PointT* buff_ptr = &(buff[0]);
const PointT* in = &(cloud_in[0]);
PointT* out = &(cloud_out[0]);
PointT* buff_ptr = buff.data();
const PointT* in = cloud_in.data();
PointT* out = cloud_out.data();
PointT* out_inner = out + cloud_out.width*top + left;

for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width)
Expand Down
2 changes: 1 addition & 1 deletion common/src/range_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -826,7 +826,7 @@ RangeImage::extractFarRanges (const pcl::PCLPointCloud2& point_cloud_data,
}

int point_step = point_cloud_data.point_step;
const unsigned char* data = &point_cloud_data.data[0];
const unsigned char* data = point_cloud_data.data.data();
int x_offset = point_cloud_data.fields[x_idx].offset,
y_offset = point_cloud_data.fields[y_idx].offset,
z_offset = point_cloud_data.fields[z_idx].offset,
Expand Down
8 changes: 4 additions & 4 deletions features/include/pcl/features/impl/brisk_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
const int r_y_1 = (1024 - r_y);

//+const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x + y * imagecols;
const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x + y * imagecols;
const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x + y * imagecols;

// just interpolate:
ret_val = (r_x_1 * r_y_1 * static_cast<int>(*ptr));
Expand Down Expand Up @@ -312,7 +312,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
// now the calculation:

//+const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x_left + imagecols * y_top;
const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x_left + imagecols * y_top;
const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x_left + imagecols * y_top;

// first the corners:
ret_val = A * static_cast<int>(*ptr);
Expand All @@ -334,7 +334,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity

// next the edges:
//+int* ptr_integral;// = static_cast<int*> (integral.data) + x_left + integralcols * y_top + 1;
const int* ptr_integral = static_cast<const int*> (&integral_image[0]) + x_left + integralcols * y_top + 1;
const int* ptr_integral = static_cast<const int*> (integral_image.data()) + x_left + integralcols * y_top + 1;

// find a simple path through the different surface corners
const int tmp1 = (*ptr_integral);
Expand Down Expand Up @@ -374,7 +374,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
// now the calculation:

//const unsigned char* ptr = static_cast<const unsigned char*> (&image[0].r) + x_left + imagecols * y_top;
const unsigned char* ptr = static_cast<const unsigned char*>(&image[0]) + x_left + imagecols * y_top;
const unsigned char* ptr = static_cast<const unsigned char*>(image.data()) + x_left + imagecols * y_top;

// first row:
ret_val = A * static_cast<int>(*ptr);
Expand Down
12 changes: 6 additions & 6 deletions features/include/pcl/features/impl/integral_image2D.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,12 +156,12 @@ template <typename DataType, unsigned Dimension> void
IntegralImage2D<DataType, Dimension>::computeIntegralImages (
const DataType *data, unsigned row_stride, unsigned element_stride)
{
ElementType* previous_row = &first_order_integral_image_[0];
ElementType* previous_row = first_order_integral_image_.data();
ElementType* current_row = previous_row + (width_ + 1);
for (unsigned int i = 0; i < (width_ + 1); ++i)
previous_row[i].setZero();

unsigned* count_previous_row = &finite_values_integral_image_[0];
unsigned* count_previous_row = finite_values_integral_image_.data();
unsigned* count_current_row = count_previous_row + (width_ + 1);
std::fill_n(count_previous_row, width_ + 1, 0);

Expand All @@ -188,7 +188,7 @@ IntegralImage2D<DataType, Dimension>::computeIntegralImages (
}
else
{
SecondOrderType* so_previous_row = &second_order_integral_image_[0];
SecondOrderType* so_previous_row = second_order_integral_image_.data();
SecondOrderType* so_current_row = so_previous_row + (width_ + 1);
for (unsigned int i = 0; i < (width_ + 1); ++i)
so_previous_row[i].setZero();
Expand Down Expand Up @@ -327,11 +327,11 @@ template <typename DataType> void
IntegralImage2D<DataType, 1>::computeIntegralImages (
const DataType *data, unsigned row_stride, unsigned element_stride)
{
ElementType* previous_row = &first_order_integral_image_[0];
ElementType* previous_row = first_order_integral_image_.data();
ElementType* current_row = previous_row + (width_ + 1);
std::fill_n(previous_row, width_ + 1, 0);

unsigned* count_previous_row = &finite_values_integral_image_[0];
unsigned* count_previous_row = finite_values_integral_image_.data();
unsigned* count_current_row = count_previous_row + (width_ + 1);
std::fill_n(count_previous_row, width_ + 1, 0);

Expand All @@ -357,7 +357,7 @@ IntegralImage2D<DataType, 1>::computeIntegralImages (
}
else
{
SecondOrderType* so_previous_row = &second_order_integral_image_[0];
SecondOrderType* so_previous_row = second_order_integral_image_.data();
SecondOrderType* so_current_row = so_previous_row + (width_ + 1);
std::fill_n(so_previous_row, width_ + 1, 0);

Expand Down
4 changes: 2 additions & 2 deletions filters/src/passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
}

// Unoptimized memcpys: assume fields x, y, z are in random order
memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));

Expand Down Expand Up @@ -245,7 +245,7 @@ pcl::PassThrough<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step)
{
// Unoptimized memcpys: assume fields x, y, z are in random order
memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float));
memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer)
memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float));
memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float));

Expand Down
4 changes: 2 additions & 2 deletions filters/src/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include <array>

using Array4size_t = Eigen::Array<std::size_t, 4, 1>;

// NOLINTBEGIN(readability-container-data-pointer)
///////////////////////////////////////////////////////////////////////////////////////////
void
pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
Expand Down Expand Up @@ -525,7 +525,7 @@ pcl::VoxelGrid<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
++index;
}
}

// NOLINTEND(readability-container-data-pointer)
#ifndef PCL_NO_PRECOMPILE
#include <pcl/impl/instantiate.hpp>
#include <pcl/point_types.h>
Expand Down
6 changes: 3 additions & 3 deletions io/include/pcl/compression/impl/entropy_range_coder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector<char>& inpu
}

// write to stream
outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());

return (static_cast<unsigned long> (outputCharVector_.size ()));
}
Expand Down Expand Up @@ -340,7 +340,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector<unsigned int>& input
}

// write encoded data to stream
outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());

streamByteCount += static_cast<unsigned long> (outputCharVector_.size ());

Expand Down Expand Up @@ -528,7 +528,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector<char>& inputB
}

// write encoded data to stream
outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ());
outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ());

streamByteCount += static_cast<unsigned long> (outputCharVector_.size ());

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ namespace pcl
// Encode size of compressed disparity image data
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
// Output compressed disparity to ostream
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t));
compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t));

// Compress color information
if (CompressionPointTraits<PointT>::hasColor && doColorEncoding)
Expand All @@ -127,7 +127,7 @@ namespace pcl
// Encode size of compressed Color image data
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColorSize), sizeof (compressedColorSize));
// Output compressed disparity to ostream
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t));
compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t));

if (bShowStatistics_arg)
{
Expand Down Expand Up @@ -194,8 +194,8 @@ namespace pcl
std::uint32_t compressedColorSize = 0;

// Remove color information of invalid points
std::uint16_t* depth_ptr = &disparityMap_arg[0];
std::uint8_t* color_ptr = &colorImage_arg[0];
std::uint16_t* depth_ptr = disparityMap_arg.data();
std::uint8_t* color_ptr = colorImage_arg.data();

for (std::size_t i = 0; i < cloud_size; ++i, ++depth_ptr, color_ptr += sizeof(std::uint8_t) * 3)
{
Expand All @@ -211,7 +211,7 @@ namespace pcl
// Encode size of compressed disparity image data
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
// Output compressed disparity to ostream
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t));
compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t));

// Compress color information
if (!colorImage_arg.empty () && doColorEncoding)
Expand Down Expand Up @@ -244,7 +244,7 @@ namespace pcl
// Encode size of compressed Color image data
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColorSize), sizeof (compressedColorSize));
// Output compressed disparity to ostream
compressedDataOut_arg.write (reinterpret_cast<const char*> (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t));
compressedDataOut_arg.write (reinterpret_cast<const char*> (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t));

if (bShowStatistics_arg)
{
Expand Down Expand Up @@ -320,12 +320,12 @@ namespace pcl
// reading compressed disparity data
compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedDisparitySize), sizeof (compressedDisparitySize));
compressedDisparity.resize (compressedDisparitySize);
compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedDisparity[0]), compressedDisparitySize * sizeof(std::uint8_t));
compressedDataIn_arg.read (reinterpret_cast<char*> (compressedDisparity.data()), compressedDisparitySize * sizeof(std::uint8_t));

// reading compressed rgb data
compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedColorSize), sizeof (compressedColorSize));
compressedColor.resize (compressedColorSize);
compressedDataIn_arg.read (reinterpret_cast<char*> (&compressedColor[0]), compressedColorSize * sizeof(std::uint8_t));
compressedDataIn_arg.read (reinterpret_cast<char*> (compressedColor.data()), compressedColorSize * sizeof(std::uint8_t));

std::size_t png_width = 0;
std::size_t png_height = 0;
Expand Down
16 changes: 8 additions & 8 deletions io/include/pcl/io/impl/lzf_image_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ LZFRGB24ImageReader::read (
cloud.resize (getWidth () * getHeight ());

int rgb_idx = 0;
auto *color_r = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
auto *color_r = reinterpret_cast<unsigned char*> (uncompressed_data.data());
auto *color_g = reinterpret_cast<unsigned char*> (&uncompressed_data[getWidth () * getHeight ()]);
auto *color_b = reinterpret_cast<unsigned char*> (&uncompressed_data[2 * getWidth () * getHeight ()]);

Expand Down Expand Up @@ -284,7 +284,7 @@ LZFRGB24ImageReader::readOMP (
cloud.height = getHeight ();
cloud.resize (getWidth () * getHeight ());

auto *color_r = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
auto *color_r = reinterpret_cast<unsigned char*> (uncompressed_data.data());
auto *color_g = reinterpret_cast<unsigned char*> (&uncompressed_data[getWidth () * getHeight ()]);
auto *color_b = reinterpret_cast<unsigned char*> (&uncompressed_data[2 * getWidth () * getHeight ()]);

Expand Down Expand Up @@ -341,7 +341,7 @@ LZFYUV422ImageReader::read (
cloud.resize (getWidth () * getHeight ());

int wh2 = getWidth () * getHeight () / 2;
auto *color_u = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
auto *color_u = reinterpret_cast<unsigned char*> (uncompressed_data.data());
auto *color_y = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2]);
auto *color_v = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2 + getWidth () * getHeight ()]);

Expand Down Expand Up @@ -399,7 +399,7 @@ LZFYUV422ImageReader::readOMP (
cloud.resize (getWidth () * getHeight ());

int wh2 = getWidth () * getHeight () / 2;
auto *color_u = reinterpret_cast<unsigned char*> (&uncompressed_data[0]);
auto *color_u = reinterpret_cast<unsigned char*> (uncompressed_data.data());
auto *color_y = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2]);
auto *color_v = reinterpret_cast<unsigned char*> (&uncompressed_data[wh2 + getWidth () * getHeight ()]);

Expand Down Expand Up @@ -462,8 +462,8 @@ LZFBayer8ImageReader::read (
// Convert Bayer8 to RGB24
std::vector<unsigned char> rgb_buffer (getWidth () * getHeight () * 3);
DeBayer i;
i.debayerEdgeAware (reinterpret_cast<unsigned char*> (&uncompressed_data[0]),
static_cast<unsigned char*> (&rgb_buffer[0]),
i.debayerEdgeAware (reinterpret_cast<unsigned char*> (uncompressed_data.data()),
static_cast<unsigned char*> (rgb_buffer.data()),
getWidth (), getHeight ());
// Copy to PointT
cloud.width = getWidth ();
Expand Down Expand Up @@ -512,8 +512,8 @@ LZFBayer8ImageReader::readOMP (
// Convert Bayer8 to RGB24
std::vector<unsigned char> rgb_buffer (getWidth () * getHeight () * 3);
DeBayer i;
i.debayerEdgeAware (reinterpret_cast<unsigned char*> (&uncompressed_data[0]),
static_cast<unsigned char*> (&rgb_buffer[0]),
i.debayerEdgeAware (reinterpret_cast<unsigned char*> (uncompressed_data.data()),
static_cast<unsigned char*> (rgb_buffer.data()),
getWidth (), getHeight ());
// Copy to PointT
cloud.width = getWidth ();
Expand Down
4 changes: 2 additions & 2 deletions io/include/pcl/io/impl/point_cloud_image_extractors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ pcl::io::PointCloudImageExtractorFromLabelField<PointT>::extractImpl (const Poin
img.height = cloud.height;
img.step = img.width * sizeof (unsigned short);
img.data.resize (img.step * img.height);
auto* data = reinterpret_cast<unsigned short*>(&img.data[0]);
auto* data = reinterpret_cast<unsigned short*>(img.data.data());
for (std::size_t i = 0; i < cloud.size (); ++i)
{
std::uint32_t val;
Expand Down Expand Up @@ -255,7 +255,7 @@ pcl::io::PointCloudImageExtractorWithScaling<PointT>::extractImpl (const PointCl
img.height = cloud.height;
img.step = img.width * sizeof (unsigned short);
img.data.resize (img.step * img.height);
auto* data = reinterpret_cast<unsigned short*>(&img.data[0]);
auto* data = reinterpret_cast<unsigned short*>(img.data.data());

float scaling_factor = scaling_factor_;
float data_min = 0.0f;
Expand Down
2 changes: 1 addition & 1 deletion io/src/ascii_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ pcl::ASCIIReader::read (

int total=0;

std::uint8_t* data = &cloud.data[0];
std::uint8_t* data = cloud.data.data();
while (std::getline (ifile, line))
{
boost::algorithm::trim (line);
Expand Down
Loading

0 comments on commit 8223fb2

Please sign in to comment.