Skip to content

Commit f17f6dd

Browse files
authored
Merge pull request #5522 from SunBlack/fix_C26814
Use constexpr variables if possible
2 parents 222036f + ec6ad8e commit f17f6dd

File tree

99 files changed

+275
-276
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

99 files changed

+275
-276
lines changed

apps/in_hand_scanner/src/icp.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -161,7 +161,7 @@ pcl::ihs::ICP::findTransformation(const MeshConstPtr& mesh_model,
161161
{
162162
// Check the input
163163
// TODO: Double check the minimum number of points necessary for icp
164-
const std::size_t n_min = 4;
164+
constexpr std::size_t n_min = 4;
165165

166166
if (mesh_model->sizeVertices() < n_min || cloud_data->size() < n_min) {
167167
std::cerr << "ERROR in icp.cpp: Not enough input points!\n";

apps/in_hand_scanner/src/integration.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ pcl::ihs::Integration::reconstructMesh(const CloudXYZRGBNormalConstPtr& cloud_da
124124
// * 3 - 0 //
125125
const int offset_1 = -width;
126126
const int offset_2 = -width - 1;
127-
const int offset_3 = -1;
127+
constexpr int offset_3 = -1;
128128
const int offset_4 = -width - 2;
129129

130130
for (int r = 1; r < height; ++r) {
@@ -262,7 +262,7 @@ pcl::ihs::Integration::merge(const CloudXYZRGBNormalConstPtr& cloud_data,
262262
// * 3 - 0 //
263263
const int offset_1 = -width;
264264
const int offset_2 = -width - 1;
265-
const int offset_3 = -1;
265+
constexpr int offset_3 = -1;
266266
const int offset_4 = -width - 2;
267267

268268
const float dot_min = std::cos(max_angle_ * 17.45329252e-3); // deg to rad

apps/in_hand_scanner/src/main_window.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ pcl::ihs::MainWindow::MainWindow(QWidget* parent)
7070
spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
7171
ui_->toolBar->insertWidget(ui_->actionHelp, spacer);
7272

73-
const double max = std::numeric_limits<double>::max();
73+
constexpr double max = std::numeric_limits<double>::max();
7474

7575
// In hand scanner
7676
QHBoxLayout* layout = new QHBoxLayout(ui_->placeholder_in_hand_scanner);

apps/in_hand_scanner/src/opengl_viewer.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -484,7 +484,7 @@ pcl::ihs::OpenGLViewer::addMesh(const CloudXYZRGBNormalConstPtr& cloud,
484484
const int h = cloud->height;
485485
const int offset_1 = -w;
486486
const int offset_2 = -w - 1;
487-
const int offset_3 = -1;
487+
constexpr int offset_3 = -1;
488488

489489
FaceVertexMeshPtr mesh(new FaceVertexMesh());
490490
mesh->transformation = T;
@@ -1083,7 +1083,7 @@ pcl::ihs::OpenGLViewer::initializeGL()
10831083
void
10841084
pcl::ihs::OpenGLViewer::setupViewport(const int w, const int h)
10851085
{
1086-
const float aspect_ratio = 4. / 3.;
1086+
constexpr float aspect_ratio = 4. / 3.;
10871087

10881088
// Use the biggest possible area of the window to draw to
10891089
// case 1 (w < w_scaled): case 2 (w >= w_scaled):

apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h

+7-7
Original file line numberDiff line numberDiff line change
@@ -167,25 +167,25 @@ struct IncIndex
167167
/// A helpful const representing the number of elements in our vectors.
168168
/// This is used for all operations that require the copying of the vector.
169169
/// Although this is used in a fairly generic way, the display requires 3D.
170-
const unsigned int XYZ_SIZE = 3;
170+
constexpr unsigned int XYZ_SIZE = 3;
171171

172172
/// A helpful const representing the number of elements in each row/col in
173173
/// our matrices. This is used for all operations that require the copying of
174174
/// the matrix.
175-
const unsigned int MATRIX_SIZE_DIM = 4;
175+
constexpr unsigned int MATRIX_SIZE_DIM = 4;
176176

177177
/// A helpful const representing the number of elements in our matrices.
178178
/// This is used for all operations that require the copying of the matrix.
179-
const unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM;
179+
constexpr unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM;
180180

181181
/// The default window width
182-
const unsigned int WINDOW_WIDTH = 1200;
182+
constexpr unsigned int WINDOW_WIDTH = 1200;
183183
/// The default window height
184-
const unsigned int WINDOW_HEIGHT = 1000;
184+
constexpr unsigned int WINDOW_HEIGHT = 1000;
185185

186186
/// The default z translation used to push the world origin in front of the
187187
/// display
188-
const float DISPLAY_Z_TRANSLATION = -2.0f;
188+
constexpr float DISPLAY_Z_TRANSLATION = -2.0f;
189189

190190
/// The radius of the trackball given as a percentage of the screen width
191-
const float TRACKBALL_RADIUS_SCALE = 0.4f;
191+
constexpr float TRACKBALL_RADIUS_SCALE = 0.4f;

apps/src/feature_matching.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -324,7 +324,7 @@ ICCVTutorial<FeatureType>::findCorrespondences(
324324

325325
// Find the index of the best match for each keypoint, and store it in
326326
// "correspondences_out"
327-
const int k = 1;
327+
constexpr int k = 1;
328328
pcl::Indices k_indices(k);
329329
std::vector<float> k_squared_distances(k);
330330
for (int i = 0; i < static_cast<int>(source->size()); ++i) {

apps/src/multiscale_feature_persistence_example.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@
4747
using namespace pcl;
4848

4949
const Eigen::Vector4f subsampling_leaf_size(0.01f, 0.01f, 0.01f, 0.0f);
50-
const float normal_estimation_search_radius = 0.05f;
50+
constexpr float normal_estimation_search_radius = 0.05f;
5151

5252
void
5353
subsampleAndCalculateNormals(PointCloud<PointXYZ>::Ptr& cloud,

apps/src/openni_feature_persistence.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -69,11 +69,11 @@ using namespace std::chrono_literals;
6969
} while (false)
7070
// clang-format on
7171

72-
const float default_subsampling_leaf_size = 0.02f;
73-
const float default_normal_search_radius = 0.041f;
72+
constexpr float default_subsampling_leaf_size = 0.02f;
73+
constexpr float default_normal_search_radius = 0.041f;
7474
const double aux[] = {0.21, 0.32};
7575
const std::vector<double> default_scales_vector(aux, aux + 2);
76-
const float default_alpha = 1.2f;
76+
constexpr float default_alpha = 1.2f;
7777

7878
template <typename PointType>
7979
class OpenNIFeaturePersistence {

apps/src/openni_mobile_server.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ CopyPointCloudToBuffers(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& clou
7979
point.x > bounds_max.x || point.y > bounds_max.y || point.z > bounds_max.z)
8080
continue;
8181

82-
const int conversion_factor = 500;
82+
constexpr int conversion_factor = 500;
8383

8484
cloud_buffers.points[j * 3 + 0] = static_cast<short>(point.x * conversion_factor);
8585
cloud_buffers.points[j * 3 + 1] = static_cast<short>(point.y * conversion_factor);

apps/src/openni_organized_edge_detection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ class OpenNIOrganizedEdgeDetection {
6868
*this);
6969
viewer->resetCameraViewpoint("cloud");
7070

71-
const int point_size = 2;
71+
constexpr int point_size = 2;
7272
viewer->addPointCloud<PointT>(cloud, "nan boundary edges");
7373
viewer->setPointCloudRenderingProperties(
7474
pcl::visualization::PCL_VISUALIZER_POINT_SIZE,

apps/src/openni_shift_to_depth_conversion.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ class SimpleOpenNIViewer {
164164
int centerY = static_cast<int>(height_arg / 2);
165165

166166
const float fl_const = 1.0f / focalLength_arg;
167-
static const float bad_point = std::numeric_limits<float>::quiet_NaN();
167+
constexpr float bad_point = std::numeric_limits<float>::quiet_NaN();
168168

169169
std::size_t i = 0;
170170
for (int y = -centerY; y < +centerY; ++y)

apps/src/pcd_organized_edge_detection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,7 @@ compute(const pcl::PCLPointCloud2::ConstPtr& input,
227227
pcl::copyPointCloud(*cloud, label_indices[3].indices, *high_curvature_edges);
228228
pcl::copyPointCloud(*cloud, label_indices[4].indices, *rgb_edges);
229229

230-
const int point_size = 2;
230+
constexpr int point_size = 2;
231231
viewer.addPointCloud<pcl::PointXYZRGBA>(nan_boundary_edges, "nan boundary edges");
232232
viewer.setPointCloudRenderingProperties(
233233
pcl::visualization::PCL_VISUALIZER_POINT_SIZE, point_size, "nan boundary edges");

apps/src/ppf_object_recognition.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ using namespace pcl;
1515
using namespace std::chrono_literals;
1616

1717
const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f);
18-
const float normal_estimation_search_radius = 0.05f;
18+
constexpr float normal_estimation_search_radius = 0.05f;
1919

2020
PointCloud<PointNormal>::Ptr
2121
subsampleAndCalculateNormals(const PointCloud<PointXYZ>::Ptr& cloud)

apps/src/pyramid_surface_matching.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ using namespace pcl;
99
#include <iostream>
1010

1111
const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f);
12-
const float normal_estimation_search_radius = 0.05f;
12+
constexpr float normal_estimation_search_radius = 0.05f;
1313

1414
void
1515
subsampleAndCalculateNormals(PointCloud<PointXYZ>::Ptr& cloud,

apps/src/statistical_multiscale_interest_region_extraction_example.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@
4242

4343
using namespace pcl;
4444

45-
const float subsampling_leaf_size = 0.003f;
46-
const float base_scale = 0.005f;
45+
constexpr float subsampling_leaf_size = 0.003f;
46+
constexpr float base_scale = 0.005f;
4747

4848
int
4949
main(int, char** argv)

common/include/pcl/common/impl/copy_point.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -118,10 +118,10 @@ struct CopyPointHelper<PointInT, PointOutT,
118118
using FieldListInT = typename pcl::traits::fieldList<PointInT>::type;
119119
using FieldListOutT = typename pcl::traits::fieldList<PointOutT>::type;
120120
using FieldList = typename pcl::intersect<FieldListInT, FieldListOutT>::type;
121-
const std::uint32_t offset_in = boost::mpl::if_<pcl::traits::has_field<PointInT, pcl::fields::rgb>,
121+
constexpr std::uint32_t offset_in = boost::mpl::if_<pcl::traits::has_field<PointInT, pcl::fields::rgb>,
122122
pcl::traits::offset<PointInT, pcl::fields::rgb>,
123123
pcl::traits::offset<PointInT, pcl::fields::rgba> >::type::value;
124-
const std::uint32_t offset_out = boost::mpl::if_<pcl::traits::has_field<PointOutT, pcl::fields::rgb>,
124+
constexpr std::uint32_t offset_out = boost::mpl::if_<pcl::traits::has_field<PointOutT, pcl::fields::rgb>,
125125
pcl::traits::offset<PointOutT, pcl::fields::rgb>,
126126
pcl::traits::offset<PointOutT, pcl::fields::rgba> >::type::value;
127127
pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (point_in, point_out));

common/include/pcl/common/impl/eigen.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ computeRoots (const Matrix& m, Roots& roots)
8989
computeRoots2 (c2, c1, roots);
9090
else
9191
{
92-
const Scalar s_inv3 = Scalar (1.0 / 3.0);
92+
constexpr Scalar s_inv3 = Scalar(1.0 / 3.0);
9393
const Scalar s_sqrt3 = std::sqrt (Scalar (3.0));
9494
// Construct the parameters used in classifying the roots of the equation
9595
// and in solving the equation for the roots in closed form.

common/include/pcl/point_representation.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -250,7 +250,7 @@ namespace pcl
250250
template<typename Key> inline void operator() ()
251251
{
252252
using FieldT = typename pcl::traits::datatype<PointDefault, Key>::type;
253-
const int NrDims = pcl::traits::datatype<PointDefault, Key>::size;
253+
constexpr int NrDims = pcl::traits::datatype<PointDefault, Key>::size;
254254
Helper<Key, FieldT, NrDims>::copyPoint (p1_, p2_, f_idx_);
255255
}
256256

common/include/pcl/register_point_struct.h

+7-7
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ namespace pcl
100100
plus (std::remove_const_t<T> &l, const T &r)
101101
{
102102
using type = std::remove_all_extents_t<T>;
103-
static const std::uint32_t count = sizeof (T) / sizeof (type);
103+
constexpr std::uint32_t count = sizeof(T) / sizeof(type);
104104
for (std::uint32_t i = 0; i < count; ++i)
105105
l[i] += r[i];
106106
}
@@ -117,7 +117,7 @@ namespace pcl
117117
plusscalar (T1 &p, const T2 &scalar)
118118
{
119119
using type = std::remove_all_extents_t<T1>;
120-
static const std::uint32_t count = sizeof (T1) / sizeof (type);
120+
constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
121121
for (std::uint32_t i = 0; i < count; ++i)
122122
p[i] += scalar;
123123
}
@@ -134,7 +134,7 @@ namespace pcl
134134
minus (std::remove_const_t<T> &l, const T &r)
135135
{
136136
using type = std::remove_all_extents_t<T>;
137-
static const std::uint32_t count = sizeof (T) / sizeof (type);
137+
constexpr std::uint32_t count = sizeof(T) / sizeof(type);
138138
for (std::uint32_t i = 0; i < count; ++i)
139139
l[i] -= r[i];
140140
}
@@ -151,7 +151,7 @@ namespace pcl
151151
minusscalar (T1 &p, const T2 &scalar)
152152
{
153153
using type = std::remove_all_extents_t<T1>;
154-
static const std::uint32_t count = sizeof (T1) / sizeof (type);
154+
constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
155155
for (std::uint32_t i = 0; i < count; ++i)
156156
p[i] -= scalar;
157157
}
@@ -168,7 +168,7 @@ namespace pcl
168168
mulscalar (T1 &p, const T2 &scalar)
169169
{
170170
using type = std::remove_all_extents_t<T1>;
171-
static const std::uint32_t count = sizeof (T1) / sizeof (type);
171+
constexpr std::uint32_t count = sizeof(T1) / sizeof(type);
172172
for (std::uint32_t i = 0; i < count; ++i)
173173
p[i] *= scalar;
174174
}
@@ -185,7 +185,7 @@ namespace pcl
185185
divscalar (T1 &p, const T2 &scalar)
186186
{
187187
using type = std::remove_all_extents_t<T1>;
188-
static const std::uint32_t count = sizeof (T1) / sizeof (type);
188+
constexpr std::uint32_t count = sizeof (T1) / sizeof (type);
189189
for (std::uint32_t i = 0; i < count; ++i)
190190
p[i] /= scalar;
191191
}
@@ -202,7 +202,7 @@ namespace pcl
202202
divscalar2 (ArrayT &p, const ScalarT &scalar)
203203
{
204204
using type = std::remove_all_extents_t<ArrayT>;
205-
static const std::uint32_t count = sizeof (ArrayT) / sizeof (type);
205+
constexpr std::uint32_t count = sizeof (ArrayT) / sizeof (type);
206206
for (std::uint32_t i = 0; i < count; ++i)
207207
p[i] = scalar / p[i];
208208
}

examples/features/example_difference_of_normals.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ int main (int argc, char *argv[])
9999

100100
// Create downsampled point cloud for DoN NN search with large scale
101101
large_cloud_downsampled = PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
102-
const float largedownsample = float (scale2/decimation);
102+
constexpr float largedownsample = float(scale2 / decimation);
103103
sor.setLeafSize (largedownsample, largedownsample, largedownsample);
104104
sor.filter (*large_cloud_downsampled);
105105
std::cout << "Using leaf size of " << largedownsample << " for large scale, " << large_cloud_downsampled->size() << " points" << std::endl;

examples/keypoints/example_sift_keypoint_estimation.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -57,10 +57,10 @@ main(int, char** argv)
5757
std::cout << "points: " << cloud->size () <<std::endl;
5858

5959
// Parameters for sift computation
60-
const float min_scale = 0.1f;
61-
const int n_octaves = 6;
62-
const int n_scales_per_octave = 10;
63-
const float min_contrast = 0.5f;
60+
constexpr float min_scale = 0.1f;
61+
constexpr int n_octaves = 6;
62+
constexpr int n_scales_per_octave = 10;
63+
constexpr float min_contrast = 0.5f;
6464

6565

6666
// Estimate the sift interest points using Intensity values from RGB values

examples/keypoints/example_sift_normal_keypoint_estimation.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -63,10 +63,10 @@ main(int, char** argv)
6363
std::cout << "points: " << cloud_xyz->size () <<std::endl;
6464

6565
// Parameters for sift computation
66-
const float min_scale = 0.01f;
67-
const int n_octaves = 3;
68-
const int n_scales_per_octave = 4;
69-
const float min_contrast = 0.001f;
66+
constexpr float min_scale = 0.01f;
67+
constexpr int n_octaves = 3;
68+
constexpr int n_scales_per_octave = 4;
69+
constexpr float min_contrast = 0.001f;
7070

7171
// Estimate the normals of the cloud_xyz
7272
pcl::NormalEstimation<pcl::PointXYZ, pcl::PointNormal> ne;

examples/keypoints/example_sift_z_keypoint_estimation.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,10 @@ main(int, char** argv)
7575
std::cout << "points: " << cloud_xyz->size () <<std::endl;
7676

7777
// Parameters for sift computation
78-
const float min_scale = 0.005f;
79-
const int n_octaves = 6;
80-
const int n_scales_per_octave = 4;
81-
const float min_contrast = 0.005f;
78+
constexpr float min_scale = 0.005f;
79+
constexpr int n_octaves = 6;
80+
constexpr int n_scales_per_octave = 4;
81+
constexpr float min_contrast = 0.005f;
8282

8383
// Estimate the sift interest points using z values from xyz as the Intensity variants
8484
pcl::SIFTKeypoint<pcl::PointXYZ, pcl::PointWithScale> sift;

examples/segmentation/example_extract_clusters_normals.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -79,9 +79,9 @@ main (int argc, char **argv)
7979

8080
// Extracting Euclidean clusters using cloud and its normals
8181
std::vector<pcl::PointIndices> cluster_indices;
82-
const float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system
83-
const double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals
84-
const unsigned int min_cluster_size = 50;
82+
constexpr float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system
83+
constexpr double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals
84+
constexpr unsigned int min_cluster_size = 50;
8585

8686
pcl::extractEuclideanClusters (*cloud_ptr, *cloud_normals, tolerance, tree_ec, cluster_indices, eps_angle, min_cluster_size);
8787

features/include/pcl/features/impl/brisk_2d.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
124124
scale_list_ = new float[scales_];
125125
size_list_ = new unsigned int[scales_];
126126

127-
const float sigma_scale = 1.3f;
127+
constexpr float sigma_scale = 1.3f;
128128

129129
for (unsigned int scale = 0; scale < scales_; ++scale)
130130
{

gpu/kinfu/tools/kinfu_app.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -732,7 +732,7 @@ struct KinFuApp
732732
{
733733
if(registration_)
734734
{
735-
const int max_color_integration_weight = 2;
735+
constexpr int max_color_integration_weight = 2;
736736
kinfu_.initColorIntegration(max_color_integration_weight);
737737
integrate_colors_ = true;
738738
}

gpu/kinfu/tools/record_tsdfvolume.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -138,8 +138,8 @@ DeviceVolume::createFromDepth (const pcl::device::PtrStepSz<const unsigned short
138138

139139
using Matrix3frm = Eigen::Matrix<float, 3, 3, Eigen::RowMajor>;
140140

141-
const int rows = 480;
142-
const int cols = 640;
141+
constexpr int rows = 480;
142+
constexpr int cols = 640;
143143

144144
// scale depth values
145145
gpu::DeviceArray2D<float> device_depth_scaled;
@@ -197,7 +197,7 @@ DeviceVolume::getVolume (pcl::TSDFVolume<VoxelT, WeightT>::Ptr &volume)
197197
bool
198198
DeviceVolume::getCloud (pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud)
199199
{
200-
const int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000;
200+
constexpr int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000;
201201

202202
// point buffer on the device
203203
pcl::gpu::DeviceArray<pcl::PointXYZ> device_cloud_buffer (DEFAULT_VOLUME_CLOUD_BUFFER_SIZE);

gpu/kinfu_large_scale/tools/kinfuLS_app.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -790,7 +790,7 @@ struct KinFuLSApp
790790
{
791791
if(registration_)
792792
{
793-
const int max_color_integration_weight = 2;
793+
constexpr int max_color_integration_weight = 2;
794794
kinfu_->initColorIntegration(max_color_integration_weight);
795795
integrate_colors_ = true;
796796
}

0 commit comments

Comments
 (0)