Skip to content

Commit

Permalink
Part H of transition to support modernize-use-default-member-init (Po…
Browse files Browse the repository at this point in the history
…intCloudLibrary#5899)

* Part H of transition to support modernize-use-default-member-init

* Updated per inspection

* Corrected formatting complaints

* Addressed CI clang-tidy issues

* Fixed another CI clang-tidy complaint

* Fixed yet more CI clang-tidy issues

* Made changes per review

* Fixed some typos

* Addressed more review changes

* Fixed new clang-tidy CI complaints

* Fixed clang-format CI complaint

* Fixed another piecemeal clang-format complaint

* Made more changes per review

* Fixed missed review comment
  • Loading branch information
gnawme committed Dec 21, 2023
1 parent eccdbe8 commit 4a389e1
Show file tree
Hide file tree
Showing 66 changed files with 352 additions and 536 deletions.
2 changes: 2 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ Checks: >
modernize-return-braced-init-list,
modernize-shrink-to-fit,
modernize-use-auto,
modernize-use-bool-literals,
modernize-use-default-member-init,
modernize-use-emplace,
modernize-use-equals-default,
modernize-use-equals-delete,
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/cvfh.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ namespace pcl
/** \brief Values describing the viewpoint ("pinhole" camera model assumed).
* By default, the viewpoint is set to 0,0,0.
*/
float vpx_{0}, vpy_{0}, vpz_{0};
float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};

/** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel
* size of the training data or the normalize_bins_ flag must be set to true.
Expand Down
24 changes: 12 additions & 12 deletions features/include/pcl/features/impl/esf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,18 +66,18 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
wt_d2.reserve (sample_size * 3);
wt_d3.reserve (sample_size);

float h_in[binsize] = {0};
float h_out[binsize] = {0};
float h_mix[binsize] = {0};
float h_mix_ratio[binsize] = {0};

float h_a3_in[binsize] = {0};
float h_a3_out[binsize] = {0};
float h_a3_mix[binsize] = {0};

float h_d3_in[binsize] = {0};
float h_d3_out[binsize] = {0};
float h_d3_mix[binsize] = {0};
float h_in[binsize] = {0.0f};
float h_out[binsize] = {0.0f};
float h_mix[binsize] = {0.0f};
float h_mix_ratio[binsize] = {0.0f};

float h_a3_in[binsize] = {0.0f};
float h_a3_out[binsize] = {0.0f};
float h_a3_mix[binsize] = {0.0f};

float h_d3_in[binsize] = {0.0f};
float h_d3_out[binsize] = {0.0f};
float h_d3_mix[binsize] = {0.0f};

float ratio=0.0;
float pih = static_cast<float>(M_PI) / 2.0f;
Expand Down
6 changes: 3 additions & 3 deletions io/include/pcl/io/ensenso_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -443,13 +443,13 @@ namespace pcl
boost::signals2::signal<sig_cb_ensenso_point_cloud_images>* point_cloud_images_signal_;

/** @brief Whether an Ensenso device is opened or not */
bool device_open_;
bool device_open_{false};

/** @brief Whether an TCP port is opened or not */
bool tcp_open_;
bool tcp_open_{false};

/** @brief Whether an Ensenso device is running or not */
bool running_;
bool running_{false};

/** @brief Point cloud capture/processing frequency */
pcl::EventFrequency frequency_;
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/openni2/openni2_device.h
Original file line number Diff line number Diff line change
Expand Up @@ -315,16 +315,16 @@ namespace pcl
mutable std::vector<OpenNI2VideoMode> color_video_modes_;
mutable std::vector<OpenNI2VideoMode> depth_video_modes_;

bool ir_video_started_;
bool color_video_started_;
bool depth_video_started_;
bool ir_video_started_{false};
bool color_video_started_{false};
bool depth_video_started_{false};

/** \brief distance between the projector and the IR camera in meters*/
float baseline_;
float baseline_{0.0f};
/** the value for shadow (occluded pixels) */
std::uint64_t shadow_value_;
std::uint64_t shadow_value_{0};
/** the value for pixels without a valid disparity measurement */
std::uint64_t no_sample_value_;
std::uint64_t no_sample_value_{0};
};

PCL_EXPORTS std::ostream& operator<< (std::ostream& stream, const OpenNI2Device& device);
Expand Down
57 changes: 28 additions & 29 deletions io/include/pcl/io/openni2_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -421,9 +421,9 @@ namespace pcl
convertToXYZIPointCloud (const pcl::io::openni2::IRImage::Ptr &image,
const pcl::io::openni2::DepthImage::Ptr &depth_image);

std::vector<std::uint8_t> color_resize_buffer_;
std::vector<std::uint16_t> depth_resize_buffer_;
std::vector<std::uint16_t> ir_resize_buffer_;
std::vector<std::uint8_t> color_resize_buffer_{};
std::vector<std::uint16_t> depth_resize_buffer_{};
std::vector<std::uint16_t> ir_resize_buffer_{};

// Stream callbacks /////////////////////////////////////////////////////
void
Expand All @@ -444,25 +444,25 @@ namespace pcl

std::string rgb_frame_id_;
std::string depth_frame_id_;
unsigned image_width_;
unsigned image_height_;
unsigned depth_width_;
unsigned depth_height_;

bool image_required_;
bool depth_required_;
bool ir_required_;
bool sync_required_;

boost::signals2::signal<sig_cb_openni_image>* image_signal_;
boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
unsigned image_width_{0};
unsigned image_height_{0};
unsigned depth_width_{0};
unsigned depth_height_{0};

bool image_required_{false};
bool depth_required_{false};
bool ir_required_{false};
bool sync_required_{false};

boost::signals2::signal<sig_cb_openni_image>* image_signal_{};
boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_{};
boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_{};
boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_{};
boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_{};
boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_{};
boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_{};
boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_{};
boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_{};

struct modeComp
{
Expand All @@ -483,14 +483,13 @@ namespace pcl
// Mapping from config (enum) modes to native OpenNI modes
std::map<int, pcl::io::openni2::OpenNI2VideoMode> config2oni_map_;

pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_;
pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_;
pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_;
bool running_;
pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_{};
pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_{};
pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_{};
bool running_{false};


CameraParameters rgb_parameters_;
CameraParameters depth_parameters_;
CameraParameters rgb_parameters_{std::numeric_limits<double>::quiet_NaN ()};
CameraParameters depth_parameters_{std::numeric_limits<double>::quiet_NaN ()};

public:
PCL_MAKE_ALIGNED_OPERATOR_NEW
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/real_sense_2_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -199,17 +199,17 @@ namespace pcl
/** \brief Repeat playback when reading from file */
bool repeat_playback_;
/** \brief controlling the state of the thread. */
bool quit_;
bool quit_{false};
/** \brief Is the grabber running. */
bool running_;
bool running_{false};
/** \brief Calculated FPS for the grabber. */
float fps_;
float fps_{0.0f};
/** \brief Width for the depth and color sensor. Default 424*/
std::uint32_t device_width_;
std::uint32_t device_width_{424};
/** \brief Height for the depth and color sensor. Default 240 */
std::uint32_t device_height_;
std::uint32_t device_height_{240};
/** \brief Target FPS for the device. Default 30. */
std::uint32_t target_fps_;
std::uint32_t target_fps_{30};
/** \brief Declare pointcloud object, for calculating pointclouds and texture mappings */
rs2::pointcloud pc_;
/** \brief Declare RealSense pipeline, encapsulating the actual device and sensors */
Expand Down
5 changes: 1 addition & 4 deletions io/src/ensenso_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,7 @@ ensensoExceptionHandling (const NxLibException& ex,
}

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
pcl::EnsensoGrabber::EnsensoGrabber () :
device_open_ (false),
tcp_open_ (false),
running_ (false)
pcl::EnsensoGrabber::EnsensoGrabber ()
{
point_cloud_signal_ = createSignal<sig_cb_ensenso_point_cloud> ();
images_signal_ = createSignal<sig_cb_ensenso_images> ();
Expand Down
5 changes: 1 addition & 4 deletions io/src/openni2/openni2_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,7 @@ using namespace pcl::io::openni2;
using openni::VideoMode;
using std::vector;

pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI) :
ir_video_started_(false),
color_video_started_(false),
depth_video_started_(false)
pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI)
{
openni::Status status = openni::OpenNI::initialize ();
if (status != openni::STATUS_OK)
Expand Down
18 changes: 0 additions & 18 deletions io/src/openni2_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,24 +73,6 @@ namespace

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
pcl::io::OpenNI2Grabber::OpenNI2Grabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
: color_resize_buffer_(0)
, depth_resize_buffer_(0)
, ir_resize_buffer_(0)
, image_width_ ()
, image_height_ ()
, depth_width_ ()
, depth_height_ ()
, image_required_ (false)
, depth_required_ (false)
, ir_required_ (false)
, sync_required_ (false)
, image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ ()
, ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ ()
, point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ ()
, depth_callback_handle_ (), image_callback_handle_ (), ir_callback_handle_ ()
, running_ (false)
, rgb_parameters_(std::numeric_limits<double>::quiet_NaN () )
, depth_parameters_(std::numeric_limits<double>::quiet_NaN () )
{
// initialize driver
updateModeMaps (); // registering mapping from PCL enum modes to openni::VideoMode and vice versa
Expand Down
6 changes: 0 additions & 6 deletions io/src/real_sense_2_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,12 +56,6 @@ namespace pcl
, signal_PointXYZRGBA ( createSignal<signal_librealsense_PointXYZRGBA> () )
, file_name_or_serial_number_ ( file_name_or_serial_number )
, repeat_playback_ ( repeat_playback )
, quit_ ( false )
, running_ ( false )
, fps_ ( 0 )
, device_width_ ( 424 )
, device_height_ ( 240 )
, target_fps_ ( 30 )
{
}

Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/impl/iss_3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,7 @@ pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut
}

#ifdef _OPENMP
Eigen::Vector3d *omp_mem = new Eigen::Vector3d[threads_];
auto *omp_mem = new Eigen::Vector3d[threads_];

for (std::size_t i = 0; i < threads_; i++)
omp_mem[i].setZero (3);
Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/keypoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -179,10 +179,10 @@ namespace pcl
KdTreePtr tree_;

/** \brief The actual search parameter (casted from either \a search_radius_ or \a k_). */
double search_parameter_{0};
double search_parameter_{0.0};

/** \brief The nearest neighbors search radius for each point. */
double search_radius_{0};
double search_radius_{0.0};

/** \brief The number of K nearest neighbors to use for each point. */
int k_{0};
Expand Down
2 changes: 1 addition & 1 deletion ml/include/pcl/ml/svm_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ struct SVMDataPoint {
/// It's the feature index. It has to be an integer number greater or equal to zero
int idx{-1};
/// The value assigned to the correspondent feature.
float value{0};
float value{0.0f};

SVMDataPoint() = default;
};
Expand Down
8 changes: 4 additions & 4 deletions octree/include/pcl/octree/octree_pointcloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -583,19 +583,19 @@ class OctreePointCloud : public OctreeT {
IndicesConstPtr indices_;

/** \brief Epsilon precision (error bound) for nearest neighbors searches. */
double epsilon_{0};
double epsilon_{0.0};

/** \brief Octree resolution. */
double resolution_;

// Octree bounding box coordinates
double min_x_{0.0f};
double min_x_{0.0};
double max_x_;

double min_y_{0.0f};
double min_y_{0.0};
double max_y_;

double min_z_{0.0f};
double min_z_{0.0};
double max_z_;

/** \brief Flag indicating if octree has defined bounding box. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#ifndef METS_ABSTRACT_SEARCH_HH_
#define METS_ABSTRACT_SEARCH_HH_

//NOLINTBEGIN
namespace mets {

/// @defgroup common Common components
Expand Down Expand Up @@ -346,5 +346,5 @@ mets::best_ever_solution::accept(const mets::feasible_solution& sol)
}
return false;
}

//NOLINTEND
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#ifndef METS_SIMULATED_ANNEALING_HH_
#define METS_SIMULATED_ANNEALING_HH_

//NOLINTBEGIN
namespace mets {

/// @defgroup simulated_annealing Simulated Annealing
Expand Down Expand Up @@ -271,4 +271,5 @@ mets::simulated_annealing<move_manager_t>::search()
cooling_schedule_m(current_temp_m, base_t::working_solution_m);
}
}
//NOLINTEND
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ class PCL_EXPORTS CorrespondenceRejectorMedianDistance : public CorrespondenceRe
/** \brief The median distance threshold between two correspondent points in source
* <-> target.
*/
double median_distance_{0};
double median_distance_{0.0};

/** \brief The factor for correspondence rejection. Points with distance greater than
* median times factor will be rejected
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ class PCL_EXPORTS CorrespondenceRejectorVarTrimmed : public CorrespondenceReject
/** \brief The inlier distance threshold (based on the computed trim factor) between
* two correspondent points in source <-> target.
*/
double trimmed_distance_{0};
double trimmed_distance_{0.0};

/** \brief The factor for correspondence rejection. Only factor times the total points
* sorted based on the correspondence distances will be considered as inliers.
Expand Down
2 changes: 1 addition & 1 deletion registration/include/pcl/registration/impl/ia_fpcs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
{
#ifdef _OPENMP
const unsigned int seed =
static_cast<unsigned int>(std::time(NULL)) ^ omp_get_thread_num();
static_cast<unsigned int>(std::time(nullptr)) ^ omp_get_thread_num();
std::srand(seed);
PCL_DEBUG("[%s::computeTransformation] Using seed=%u\n", reg_name_.c_str(), seed);
#pragma omp for schedule(dynamic)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ class LabeledEuclideanClusterExtraction : public PCLBase<PointT> {
KdTreePtr tree_{nullptr};

/** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */
double cluster_tolerance_{0};
double cluster_tolerance_{0.0};

/** \brief The minimum number of points that a cluster needs to contain in order to be
* considered valid (default = 1). */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ namespace pcl
double height_limit_max_{std::numeric_limits<float>::max()};

/** \brief Values describing the data acquisition viewpoint. Default: 0,0,0. */
float vpx_{0}, vpy_{0}, vpz_{0};
float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f};

/** \brief Class getName method. */
virtual std::string
Expand Down
Loading

0 comments on commit 4a389e1

Please sign in to comment.