Skip to content

Commit

Permalink
Added modernize-use-auto to clang-tidy-checks (PointCloudLibrary#5397)
Browse files Browse the repository at this point in the history
* Enabled modernize-use-auto with MinTypeNameLength 7

* Fixed clang-tidy and clang-format escapes

* Addressed further issues from CI

* Fixed constness of cast

* Fixed issues flagged by review and CI

* Fixed constness of casts (again?)

* Unconsted reinterpret_cast

* Fixed copy-paste error

* Ran clang-tidy after rebase

* Fixed merge error

* Made changes per review

* Fixed typo

* Revised per review
  • Loading branch information
gnawme committed Sep 9, 2022
1 parent c7db524 commit c80bfd2
Show file tree
Hide file tree
Showing 176 changed files with 649 additions and 669 deletions.
6 changes: 4 additions & 2 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
---
Checks: '-*,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn'
WarningsAsErrors: '-*,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn'
Checks: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn'
WarningsAsErrors: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn'
CheckOptions:
- {key: modernize-use-auto.MinTypeNameLength, value: 7}
6 changes: 3 additions & 3 deletions common/include/pcl/common/impl/spring.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ duplicateColumns (const PointCloud<PointT>& input, PointCloud<PointT>& output,
for (std::size_t j = 0; j < old_height; ++j)
for(std::size_t i = 0; i < amount; ++i)
{
typename PointCloud<PointT>::iterator start = output.begin () + (j * new_width);
auto start = output.begin () + (j * new_width);
output.insert (start, *start);
start = output.begin () + (j * new_width) + old_width + i;
output.insert (start, *start);
Expand Down Expand Up @@ -182,7 +182,7 @@ mirrorColumns (const PointCloud<PointT>& input, PointCloud<PointT>& output,
for (std::size_t j = 0; j < old_height; ++j)
for(std::size_t i = 0; i < amount; ++i)
{
typename PointCloud<PointT>::iterator start = output.begin () + (j * new_width);
auto start = output.begin () + (j * new_width);
output.insert (start, *(start + 2*i));
start = output.begin () + (j * new_width) + old_width + 2*i;
output.insert (start+1, *(start - 2*i));
Expand Down Expand Up @@ -254,7 +254,7 @@ deleteCols (const PointCloud<PointT>& input, PointCloud<PointT>& output,
std::uint32_t new_width = old_width - 2 * amount;
for(std::size_t j = 0; j < old_height; j++)
{
typename PointCloud<PointT>::iterator start = output.begin () + j * new_width;
auto start = output.begin () + j * new_width;
output.erase (start, start + amount);
start = output.begin () + (j+1) * new_width;
output.erase (start, start + amount);
Expand Down
2 changes: 1 addition & 1 deletion common/src/feature_histogram.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ pcl::FeatureHistogram::addValue (float value)
++number_of_elements_;

// Increase the bin.
std::size_t bin_number = static_cast<std::size_t> ((value - threshold_min_) / step_);
auto bin_number = static_cast<std::size_t> ((value - threshold_min_) / step_);
++histogram_[bin_number];
}
}
Expand Down
2 changes: 1 addition & 1 deletion examples/segmentation/example_cpc_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -455,7 +455,7 @@ CPCSegmentation Parameters: \n\

// Create a polydata to store everything in
vtkSmartPointer<vtkPolyData> polyData = vtkSmartPointer<vtkPolyData>::New ();
for (VertexIterator itr = vertex_iterator_range.first; itr != vertex_iterator_range.second; ++itr)
for (auto itr = vertex_iterator_range.first; itr != vertex_iterator_range.second; ++itr)
{
const std::uint32_t sv_label = sv_adjacency_list[*itr];
std::pair<AdjacencyIterator, AdjacencyIterator> neighbors = boost::adjacent_vertices (*itr, sv_adjacency_list);
Expand Down
2 changes: 1 addition & 1 deletion examples/segmentation/example_lccp_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,7 +379,7 @@ LCCPSegmentation Parameters: \n\

// Create a polydata to store everything in
vtkSmartPointer<vtkPolyData> polyData = vtkSmartPointer<vtkPolyData>::New ();
for (VertexIterator itr = vertex_iterator_range.first; itr != vertex_iterator_range.second; ++itr)
for (auto itr = vertex_iterator_range.first; itr != vertex_iterator_range.second; ++itr)
{
const std::uint32_t sv_label = sv_adjacency_list[*itr];
std::pair<AdjacencyIterator, AdjacencyIterator> neighbors = boost::adjacent_vertices (*itr, sv_adjacency_list);
Expand Down
12 changes: 6 additions & 6 deletions features/include/pcl/features/impl/brisk_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
pattern_iterator->sigma = static_cast<float> (sigma_scale * scale_list_[scale] * (double (radius_list[ring])) * sin (M_PI / double (number_list[ring])));

// adapt the sizeList if necessary
const unsigned int size = static_cast<unsigned int> (std::ceil (((scale_list_[scale] * radius_list[ring]) + pattern_iterator->sigma)) + 1);
const auto size = static_cast<unsigned int> (std::ceil (((scale_list_[scale] * radius_list[ring]) + pattern_iterator->sigma)) + 1);

if (size_list_[scale] < size)
size_list_[scale] = size;
Expand Down Expand Up @@ -453,8 +453,8 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
}

// image size
const index_t width = static_cast<index_t>(input_cloud_->width);
const index_t height = static_cast<index_t>(input_cloud_->height);
const auto width = static_cast<index_t>(input_cloud_->width);
const auto height = static_cast<index_t>(input_cloud_->height);

// destination for intensity data; will be forwarded to BRISK
std::vector<unsigned char> image_data (width*height);
Expand All @@ -470,8 +470,8 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
// initialize constants
static const float lb_scalerange = std::log2 (scalerange_);

typename std::vector<KeypointT, Eigen::aligned_allocator<KeypointT> >::iterator beginning = keypoints_->points.begin ();
std::vector<int>::iterator beginningkscales = kscales.begin ();
auto beginning = keypoints_->points.begin ();
auto beginningkscales = kscales.begin ();

static const float basic_size_06 = basic_size_ * 0.6f;
unsigned int basicscale = 0;
Expand Down Expand Up @@ -636,7 +636,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
#endif

// now iterate through all the pairings
UINT32_ALIAS* ptr2 = reinterpret_cast<UINT32_ALIAS*> (ptr);
auto* ptr2 = reinterpret_cast<UINT32_ALIAS*> (ptr);
const BriskShortPair* max = short_pairs_ + no_short_pairs_;

for (BriskShortPair* iter = short_pairs_; iter < max; ++iter)
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/integral_image2D.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ IntegralImage2D<DataType, Dimension>::computeIntegralImages (
{
current_row [colIdx + 1] = previous_row [colIdx + 1] + current_row [colIdx] - previous_row [colIdx];
count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];
const InputType* element = reinterpret_cast <const InputType*> (&data [valIdx]);
const auto* element = reinterpret_cast <const InputType*> (&data [valIdx]);
if (std::isfinite (element->sum ()))
{
current_row [colIdx + 1] += element->template cast<typename IntegralImageTypeTraits<DataType>::IntegralType>();
Expand Down Expand Up @@ -208,7 +208,7 @@ IntegralImage2D<DataType, Dimension>::computeIntegralImages (
so_current_row [colIdx + 1] = so_previous_row [colIdx + 1] + so_current_row [colIdx] - so_previous_row [colIdx];
count_current_row [colIdx + 1] = count_previous_row [colIdx + 1] + count_current_row [colIdx] - count_previous_row [colIdx];

const InputType* element = reinterpret_cast <const InputType*> (&data [valIdx]);
const auto* element = reinterpret_cast <const InputType*> (&data [valIdx]);
if (std::isfinite (element->sum ()))
{
current_row [colIdx + 1] += element->template cast<typename IntegralImageTypeTraits<DataType>::IntegralType>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeOBB ()
obb_max_point_.y = std::numeric_limits <float>::min ();
obb_max_point_.z = std::numeric_limits <float>::min ();

unsigned int number_of_points = static_cast <unsigned int> (indices_->size ());
auto number_of_points = static_cast <unsigned int> (indices_->size ());
for (unsigned int i_point = 0; i_point < number_of_points; i_point++)
{
float x = ((*input_)[(*indices_)[i_point]].x - mean_value_ (0)) * major_axis_ (0) +
Expand Down Expand Up @@ -332,7 +332,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeMeanValue ()
aabb_max_point_.y = -std::numeric_limits <float>::max ();
aabb_max_point_.z = -std::numeric_limits <float>::max ();

unsigned int number_of_points = static_cast <unsigned int> (indices_->size ());
auto number_of_points = static_cast <unsigned int> (indices_->size ());
for (unsigned int i_point = 0; i_point < number_of_points; i_point++)
{
mean_value_ (0) += (*input_)[(*indices_)[i_point]].x;
Expand Down Expand Up @@ -362,7 +362,7 @@ pcl::MomentOfInertiaEstimation<PointT>::computeCovarianceMatrix (Eigen::Matrix <
{
covariance_matrix.setZero ();

unsigned int number_of_points = static_cast <unsigned int> (indices_->size ());
auto number_of_points = static_cast <unsigned int> (indices_->size ());
float factor = 1.0f / static_cast <float> ((number_of_points - 1 > 0)?(number_of_points - 1):1);
for (unsigned int i_point = 0; i_point < number_of_points; i_point++)
{
Expand Down Expand Up @@ -482,7 +482,7 @@ template <typename PointT> float
pcl::MomentOfInertiaEstimation<PointT>::calculateMomentOfInertia (const Eigen::Vector3f& current_axis, const Eigen::Vector3f& mean_value) const
{
float moment_of_inertia = 0.0f;
unsigned int number_of_points = static_cast <unsigned int> (indices_->size ());
auto number_of_points = static_cast <unsigned int> (indices_->size ());
for (unsigned int i_point = 0; i_point < number_of_points; i_point++)
{
Eigen::Vector3f vector;
Expand All @@ -506,7 +506,7 @@ pcl::MomentOfInertiaEstimation<PointT>::getProjectedCloud (const Eigen::Vector3f
{
const float D = - normal_vector.dot (point);

unsigned int number_of_points = static_cast <unsigned int> (indices_->size ());
auto number_of_points = static_cast <unsigned int> (indices_->size ());
projected_cloud->points.resize (number_of_points, PointT ());

for (unsigned int i_point = 0; i_point < number_of_points; i_point++)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ pcl::OrganizedEdgeBase<PointT, PointLT>::compute (pcl::PointCloud<PointLT>& labe
template<typename PointT, typename PointLT> void
pcl::OrganizedEdgeBase<PointT, PointLT>::assignLabelIndices (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const
{
const unsigned invalid_label = unsigned (0);
const auto invalid_label = unsigned (0);
label_indices.resize (num_of_edgetype_);
for (std::size_t idx = 0; idx < input_->size (); idx++)
{
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/pfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computePointPFHSignature (
key = std::pair<int, int> (p1, p2);

// Check to see if we already estimated this pair in the global hashmap
std::map<std::pair<int, int>, Eigen::Vector4f, std::less<>, Eigen::aligned_allocator<std::pair<const std::pair<int, int>, Eigen::Vector4f> > >::iterator fm_it = feature_map_.find (key);
auto fm_it = feature_map_.find (key);
if (fm_it != feature_map_.end ())
{
pfh_tuple_ = fm_it->second;
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/rops_estimation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -481,11 +481,11 @@ pcl::ROPSEstimation <PointInT, PointOutT>::getDistributionMatrix (const unsigned
const float v_length = point (coord[projection][1]) - min[coord[projection][1]];

const float u_ratio = u_length / u_bin_length;
unsigned int row = static_cast <unsigned int> (u_ratio);
auto row = static_cast <unsigned int> (u_ratio);
if (row == number_of_bins_) row--;

const float v_ratio = v_length / v_bin_length;
unsigned int col = static_cast <unsigned int> (v_ratio);
auto col = static_cast <unsigned int> (v_ratio);
if (col == number_of_bins_) col--;

matrix (row, col) += 1.0f;
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/shot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ pcl::SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSing


unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0;
unsigned char bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);
auto bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);

assert (bit3 == 0 || bit3 == 1);

Expand Down Expand Up @@ -455,7 +455,7 @@ pcl::SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::interpolateDou
zInFeatRef = 0;

unsigned char bit4 = ((yInFeatRef > 0) || ((yInFeatRef == 0.0) && (xInFeatRef < 0))) ? 1 : 0;
unsigned char bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);
auto bit3 = static_cast<unsigned char> (((xInFeatRef > 0) || ((xInFeatRef == 0.0) && (yInFeatRef > 0))) ? !bit4 : bit4);

assert (bit3 == 0 || bit3 == 1);

Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/vfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ pcl::VFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
(*normals_)[index].normal[2], 0);
// Normalize
double alpha = (normal.dot (d_vp_p) + 1.0) * 0.5;
std::size_t fi = static_cast<std::size_t> (std::floor (alpha * hist_vp_.size ()));
auto fi = static_cast<std::size_t> (std::floor (alpha * hist_vp_.size ()));
fi = std::max<std::size_t> (0u, fi);
fi = std::min<std::size_t> (hist_vp_.size () - 1, fi);
// Bin into the histogram
Expand Down
6 changes: 3 additions & 3 deletions features/src/narf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -477,14 +477,14 @@ Narf::getRotations (std::vector<float>& rotations, std::vector<float>& strengths

while (!scored_orientations.empty())
{
std::multimap<float, float>::iterator best_remaining_orientation_it = scored_orientations.end();
auto best_remaining_orientation_it = scored_orientations.end();
--best_remaining_orientation_it;
rotations.push_back(best_remaining_orientation_it->second);
strengths.push_back(best_remaining_orientation_it->first);
scored_orientations.erase(best_remaining_orientation_it);
for (std::multimap<float, float>::iterator it = scored_orientations.begin(); it!=scored_orientations.end();)
for (auto it = scored_orientations.begin(); it!=scored_orientations.end();)
{
std::multimap<float, float>::iterator current_it = it++;
auto current_it = it++;
if (normAngle(current_it->second - rotations.back()) < min_angle_dist_between_rotations)
scored_orientations.erase(current_it);
}
Expand Down
4 changes: 2 additions & 2 deletions features/src/range_image_border_extractor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -493,7 +493,7 @@ RangeImageBorderExtractor::calculateBorderDirections ()
}
}

Eigen::Vector3f** average_border_directions = new Eigen::Vector3f*[size];
auto** average_border_directions = new Eigen::Vector3f*[size];
int radius = parameters_.pixel_radius_border_direction;
int minimum_weight = radius+1;
float min_cos_angle=std::cos(deg2rad(120.0f));
Expand Down Expand Up @@ -614,7 +614,7 @@ RangeImageBorderExtractor::blurSurfaceChanges ()

const RangeImage& range_image = *range_image_;

Eigen::Vector3f* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height];
auto* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height];
float* blurred_scores = new float[range_image.width*range_image.height];
for (int y=0; y<int(range_image.height); ++y)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ pcl::ApproximateVoxelGrid<PointT>::applyFilter (PointCloud &output)
int ix = static_cast<int> (std::floor (point.x * inverse_leaf_size_[0]));
int iy = static_cast<int> (std::floor (point.y * inverse_leaf_size_[1]));
int iz = static_cast<int> (std::floor (point.z * inverse_leaf_size_[2]));
unsigned int hash = static_cast<unsigned int> ((ix * 7171 + iy * 3079 + iz * 4231) & (histsize_ - 1));
auto hash = static_cast<unsigned int> ((ix * 7171 + iy * 3079 + iz * 4231) & (histsize_ - 1));
he *hhe = &history_[hash];
if (hhe->count && ((ix != hhe->ix) || (iy != hhe->iy) || (iz != hhe->iz)))
{
Expand Down
8 changes: 4 additions & 4 deletions filters/include/pcl/filters/impl/conditional_removal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ template <typename PointT> bool
pcl::PackedRGBComparison<PointT>::evaluate (const PointT &point) const
{
// extract the component value
const std::uint8_t* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
std::uint8_t my_val = *(pt_data + component_offset_);

// now do the comparison
Expand Down Expand Up @@ -298,8 +298,8 @@ pcl::PackedHSIComparison<PointT>::evaluate (const PointT &point) const
static std::uint8_t i_ = 0;

// We know that rgb data is 32 bit aligned (verified in the ctor) so...
const std::uint8_t* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
const std::uint32_t* rgb_data = reinterpret_cast<const std::uint32_t*> (pt_data + rgb_offset_);
const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
const auto* rgb_data = reinterpret_cast<const std::uint32_t*> (pt_data + rgb_offset_);
std::uint32_t new_rgb_val = *rgb_data;

if (rgb_val_ != new_rgb_val)
Expand Down Expand Up @@ -523,7 +523,7 @@ pcl::PointDataAtOffset<PointT>::compare (const PointT& p, const double& val)
// if p(data) == val return 0
// if p(data) < val return -1

const std::uint8_t* pt_data = reinterpret_cast<const std::uint8_t*> (&p);
const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&p);

switch (datatype_)
{
Expand Down
8 changes: 4 additions & 4 deletions filters/include/pcl/filters/impl/extract_indices.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,15 +58,15 @@ pcl::ExtractIndices<PointT>::filterDirectly (PointCloudPtr &cloud)
pcl::for_each_type<FieldList> (pcl::detail::FieldAdder<PointT> (fields));
for (const auto& rii : (*removed_indices_)) // rii = removed indices iterator
{
uindex_t pt_index = (uindex_t) rii;
auto pt_index = (uindex_t) rii;
if (pt_index >= input_->size ())
{
PCL_ERROR ("[pcl::%s::filterDirectly] The index exceeds the size of the input. Do nothing.\n",
getClassName ().c_str ());
*cloud = *input_;
return;
}
std::uint8_t* pt_data = reinterpret_cast<std::uint8_t*> (&(*cloud)[pt_index]);
auto* pt_data = reinterpret_cast<std::uint8_t*> (&(*cloud)[pt_index]);
for (const auto &field : fields)
memcpy (pt_data + field.offset, &user_filter_value_, sizeof (float));
}
Expand All @@ -91,15 +91,15 @@ pcl::ExtractIndices<PointT>::applyFilter (PointCloud &output)
pcl::for_each_type<FieldList> (pcl::detail::FieldAdder<PointT> (fields));
for (const auto ri : *removed_indices_) // ri = removed index
{
std::size_t pt_index = (std::size_t)ri;
auto pt_index = (std::size_t)ri;
if (pt_index >= input_->size ())
{
PCL_ERROR ("[pcl::%s::applyFilter] The index exceeds the size of the input. Do nothing.\n",
getClassName ().c_str ());
output = *input_;
return;
}
std::uint8_t* pt_data = reinterpret_cast<std::uint8_t*> (&output[pt_index]);
auto* pt_data = reinterpret_cast<std::uint8_t*> (&output[pt_index]);
for (const auto &field : fields)
memcpy (pt_data + field.offset, &user_filter_value_, sizeof (float));
}
Expand Down
Loading

0 comments on commit c80bfd2

Please sign in to comment.