Skip to content

Commit aa864db

Browse files
authored
Added modernize-return-braced-init-list to clang-tidy checks (#5593)
* Added modernize-return-braced-init-list clang-tidy Added modernize-return-braced-init-list clang-tidy check Fixed issues flagged by clang-tidy Fixed clang-tidy complaints from CI Worked around clang bug with explicit constructor Fixed unrelated unused typedef error Fixed formatting issue * Reverted formatting changes per review * Restored braced-init-list return * *Really* revert formatting this time * Commented NOLINT instances more clearly
1 parent 3a8af8e commit aa864db

File tree

32 files changed

+104
-121
lines changed

32 files changed

+104
-121
lines changed

.clang-tidy

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ Checks: >
77
modernize-deprecated-headers,
88
modernize-redundant-void-arg,
99
modernize-replace-random-shuffle,
10+
modernize-return-braced-init-list,
1011
modernize-use-auto,
1112
modernize-use-equals-default,
1213
modernize-use-equals-delete,

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

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -285,8 +285,7 @@ getLargest3x3Eigenvector (const Matrix scaledMatrix)
285285

286286
Index index;
287287
const Scalar length = len.maxCoeff (&index); // <- first evaluation
288-
return EigenVector<Vector, Scalar> {crossProduct.row (index) / length,
289-
length};
288+
return {crossProduct.row (index) / length, length};
290289
}
291290

292291
} // namespace detail

common/include/pcl/range_image/impl/range_image.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -682,7 +682,7 @@ RangeImage::getAcutenessValue (int x1, int y1, int x2, int y2) const
682682
const Eigen::Vector3f
683683
RangeImage::getSensorPos () const
684684
{
685-
return Eigen::Vector3f (to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3));
685+
return {to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3)};
686686
}
687687

688688
/////////////////////////////////////////////////////////////////////////
@@ -801,7 +801,7 @@ RangeImage::getMaxAngleSize (const Eigen::Affine3f& viewer_pose, const Eigen::Ve
801801
Eigen::Vector3f
802802
RangeImage::getEigenVector3f (const PointWithRange& point)
803803
{
804-
return Eigen::Vector3f (point.x, point.y, point.z);
804+
return {point.x, point.y, point.z};
805805
}
806806

807807
/////////////////////////////////////////////////////////////////////////

filters/include/pcl/filters/normal_refinement.h

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,11 @@ namespace pcl
6464
PCL_ERROR("[pcl::assignNormalWeights] inequal size of neighbor indices and distances!\n");
6565

6666
// TODO: For now we use uniform weights
67-
return (std::vector<float> (k_indices.size (), 1.0f));
67+
// Disable check for braced-initialization,
68+
// since the compiler doesn't seem to recognize that
69+
// {k_indices.size (), 1.0f} is selecting the vector(size_type count, const T&) constructor
70+
// NOLINTNEXTLINE(modernize-return-braced-init-list)
71+
return std::vector<float> (k_indices.size (), 1.0f);
6872
}
6973

7074
/** \brief Refine an indexed point based on its neighbors, this function only writes to the normal_* fields

filters/include/pcl/filters/voxel_grid.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -362,9 +362,9 @@ namespace pcl
362362
inline Eigen::Vector3i
363363
getGridCoordinates (float x, float y, float z) const
364364
{
365-
return (Eigen::Vector3i (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
365+
return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
366366
static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
367-
static_cast<int> (std::floor (z * inverse_leaf_size_[2]))));
367+
static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
368368
}
369369

370370
/** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.
@@ -710,9 +710,9 @@ namespace pcl
710710
inline Eigen::Vector3i
711711
getGridCoordinates (float x, float y, float z) const
712712
{
713-
return (Eigen::Vector3i (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
713+
return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
714714
static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
715-
static_cast<int> (std::floor (z * inverse_leaf_size_[2]))));
715+
static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
716716
}
717717

718718
/** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.

filters/include/pcl/filters/voxel_grid_occlusion_estimation.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -227,9 +227,9 @@ namespace pcl
227227
inline Eigen::Vector3i
228228
getGridCoordinatesRound (float x, float y, float z)
229229
{
230-
return Eigen::Vector3i (static_cast<int> (round (x * inverse_leaf_size_[0])),
231-
static_cast<int> (round (y * inverse_leaf_size_[1])),
232-
static_cast<int> (round (z * inverse_leaf_size_[2])));
230+
return {static_cast<int> (round (x * inverse_leaf_size_[0])),
231+
static_cast<int> (round (y * inverse_leaf_size_[1])),
232+
static_cast<int> (round (z * inverse_leaf_size_[2]))};
233233
}
234234

235235
// initialization flag

geometry/include/pcl/geometry/mesh_base.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1091,7 +1091,7 @@ class MeshBase {
10911091
&vertex_data <= &vertex_data_cloud_.back());
10921092
return (VertexIndex(std::distance(&vertex_data_cloud_.front(), &vertex_data)));
10931093
}
1094-
return (VertexIndex());
1094+
return {};
10951095
}
10961096

10971097
/** \brief Get the index associated to the given half-edge data. */
@@ -1104,7 +1104,7 @@ class MeshBase {
11041104
return (HalfEdgeIndex(
11051105
std::distance(&half_edge_data_cloud_.front(), &half_edge_data)));
11061106
}
1107-
return (HalfEdgeIndex());
1107+
return {};
11081108
}
11091109

11101110
/** \brief Get the index associated to the given edge data. */
@@ -1116,7 +1116,7 @@ class MeshBase {
11161116
&edge_data <= &edge_data_cloud_.back());
11171117
return (EdgeIndex(std::distance(&edge_data_cloud_.front(), &edge_data)));
11181118
}
1119-
return (EdgeIndex());
1119+
return {};
11201120
}
11211121

11221122
/** \brief Get the index associated to the given face data. */
@@ -1128,7 +1128,7 @@ class MeshBase {
11281128
&face_data <= &face_data_cloud_.back());
11291129
return (FaceIndex(std::distance(&face_data_cloud_.front(), &face_data)));
11301130
}
1131-
return (FaceIndex());
1131+
return {};
11321132
}
11331133

11341134
protected:
@@ -1162,7 +1162,7 @@ class MeshBase {
11621162
{
11631163
const int n = static_cast<int>(vertices.size());
11641164
if (n < 3)
1165-
return (FaceIndex());
1165+
return {};
11661166

11671167
// Check for topological errors
11681168
inner_he_.resize(n);
@@ -1175,7 +1175,7 @@ class MeshBase {
11751175
inner_he_[i],
11761176
is_new_[i],
11771177
IsManifold())) {
1178-
return (FaceIndex());
1178+
return {};
11791179
}
11801180
}
11811181
for (int i = 0; i < n; ++i) {
@@ -1188,7 +1188,7 @@ class MeshBase {
11881188
make_adjacent_[i],
11891189
free_he_[i],
11901190
IsManifold())) {
1191-
return (FaceIndex());
1191+
return {};
11921192
}
11931193
}
11941194

io/include/pcl/io/dinast_grabber.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ namespace pcl
8181
*/
8282
std::string
8383
getName () const override
84-
{ return (std::string ("DinastGrabber")); }
84+
{ return {"DinastGrabber"}; }
8585

8686
/** \brief Start the data acquisition process.
8787
*/

io/include/pcl/io/real_sense_2_grabber.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,8 @@ namespace pcl
101101

102102
/** \brief defined grabber name*/
103103
std::string
104-
getName () const override { return std::string ( "RealSense2Grabber" ); }
104+
getName () const override {
105+
return {"RealSense2Grabber"}; }
105106

106107
//define callback signature typedefs
107108
using signal_librealsense_PointXYZ = void( const pcl::PointCloud<pcl::PointXYZ>::ConstPtr& );

io/src/dinast_grabber.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,7 @@ pcl::DinastGrabber::getDeviceVersion ()
204204
PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::getDeviceVersion] Error trying to get device version");
205205

206206
//data[21] = 0;
207-
return (std::string (reinterpret_cast<const char*> (data)));
207+
return {reinterpret_cast<const char*>(data)};
208208
}
209209

210210
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////

0 commit comments

Comments
 (0)