From cf6868786530b40de0347b7f5c3eb5adbe0aa137 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 20 May 2024 20:35:35 +0900 Subject: [PATCH] chore(velodyne_scan_decoder.hpp): explicitly initialize some fields for clarity --- .../decoders/velodyne_scan_decoder.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index 1d8cb9255..02209c5b2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -134,9 +134,9 @@ enum RETURN_TYPE { class VelodyneScanDecoder { private: - size_t processed_packets_; - uint32_t prev_packet_first_azm_phased_; - bool has_scanned_; + size_t processed_packets_{0}; + uint32_t prev_packet_first_azm_phased_{0}; + bool has_scanned_{false}; protected: /// @brief Checks if the current packet completes the ongoing scan. @@ -204,7 +204,7 @@ class VelodyneScanDecoder /// @brief Virtual function for getting the flag indicating whether one cycle is ready /// @return Readied - virtual bool hasScanned() { + bool hasScanned() { return has_scanned_; }