Skip to content

Commit 1696281

Browse files
committedNov 18, 2024··
chore(velodyne): fix compiler and clang-tidy errors after rebase
Signed-off-by: Max SCHMELLER <max.schmeller@tier4.jp>
1 parent 20a1e22 commit 1696281

File tree

9 files changed

+417
-334
lines changed

9 files changed

+417
-334
lines changed
 

‎nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp

+214-200
Large diffs are not rendered by default.
Original file line numberDiff line numberDiff line change
@@ -1,41 +1,51 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
115
#pragma once
216

317
#include <cstddef>
418
#include <cstdint>
519
#include <ctime>
620

7-
namespace nebula
8-
{
9-
namespace drivers
10-
{
11-
namespace velodyne_packet
21+
namespace nebula::drivers::velodyne_packet
1222
{
1323

1424
/**
1525
* Raw Velodyne packet constants and structures.
1626
*/
17-
static const int RAW_SCAN_SIZE = 3; // TODO: remove
18-
static const int SCANS_PER_BLOCK = 32; // TODO: remove
19-
static const int CHANNELS_PER_BLOCK = 32;
27+
static const int g_raw_scan_size = 3; // TODO(ike-kazu): remove
28+
static const int g_scans_per_block = 32; // TODO(ike-kazu): remove
29+
static const int g_channels_per_block = 32;
2030

21-
static const double ROTATION_RESOLUTION = 0.01; // [deg]
22-
static const uint16_t ROTATION_MAX_UNITS = 360 * 100u; // [deg/100]
31+
static const double g_rotation_resolution = 0.01; // [deg]
32+
static const uint16_t g_rotation_max_units = 360 * 100u; // [deg/100]
2333

24-
static const size_t RETURN_MODE_INDEX = 1204;
34+
static const size_t g_return_mode_index = 1204;
2535

2636
/** @todo make this work for both big and little-endian machines */
27-
static const uint16_t UPPER_BANK = 0xeeff;
28-
static const uint16_t LOWER_BANK = 0xddff;
37+
static const uint16_t g_upper_bank = 0xeeff;
38+
static const uint16_t g_lower_bank = 0xddff;
2939

3040
/** Return Modes **/
31-
static const uint16_t RETURN_MODE_STRONGEST = 55;
32-
static const uint16_t RETURN_MODE_LAST = 56;
33-
static const uint16_t RETURN_MODE_DUAL = 57;
41+
static const uint16_t g_return_mode_strongest = 55;
42+
static const uint16_t g_return_mode_last = 56;
43+
static const uint16_t g_return_mode_dual = 57;
3444

35-
const int BLOCKS_PER_PACKET = 12;
36-
const int PACKET_STATUS_SIZE = 4;
37-
const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
38-
const int POINTS_PER_PACKET = (SCANS_PER_PACKET * RAW_SCAN_SIZE);
45+
const int g_blocks_per_packet = 12;
46+
const int g_packet_status_size = 4;
47+
const int g_scans_per_packet = (g_scans_per_block * g_blocks_per_packet);
48+
const int g_points_per_packet = (g_scans_per_packet * g_raw_scan_size);
3949

4050
#pragma pack(push, 1)
4151
/** \brief Raw Velodyne data block.
@@ -45,16 +55,17 @@ const int POINTS_PER_PACKET = (SCANS_PER_PACKET * RAW_SCAN_SIZE);
4555
*
4656
* use stdint.h types, so things work with both 64 and 32-bit machines
4757
*/
48-
struct raw_units{
58+
struct raw_units
59+
{
4960
uint16_t distance;
5061
uint8_t reflectivity;
5162
};
5263

5364
struct raw_block_t
5465
{
55-
uint16_t flag; ///< UPPER_BANK or LOWER_BANK
66+
uint16_t flag; ///< UPPER_BANK or LOWER_BANK
5667
uint16_t rotation; ///< 0-35999, divide by 100 to get degrees
57-
raw_units units[SCANS_PER_BLOCK];
68+
raw_units units[g_scans_per_block];
5869
};
5970

6071
/** \brief Raw Velodyne packet.
@@ -71,7 +82,7 @@ struct raw_block_t
7182
*/
7283
struct raw_packet_t
7384
{
74-
raw_block_t blocks[BLOCKS_PER_PACKET];
85+
raw_block_t blocks[g_blocks_per_packet];
7586
uint32_t timestamp;
7687
uint16_t factory;
7788
};
@@ -89,6 +100,4 @@ enum RETURN_TYPE {
89100
DUAL_ONLY = 7
90101
};
91102

92-
} // namespace hesai_packet
93-
} // namespace drivers
94-
} // namespace nebula
103+
} // namespace nebula::drivers::velodyne_packet

‎nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@
3232
#include <cmath>
3333
#include <cstdint>
3434
#include <memory>
35-
#include <string>
3635
#include <tuple>
3736
#include <vector>
3837

@@ -44,9 +43,13 @@ class VelodyneScanDecoder
4443
private:
4544
size_t processed_packets_{0};
4645
uint32_t prev_packet_first_azm_phased_{0};
47-
bool has_scanned_{false};
46+
47+
static const size_t g_offset_first_azimuth = 2;
48+
static const size_t g_offset_last_azimuth = 1102;
49+
static const uint32_t g_degree_subdivisions = 100;
4850

4951
protected:
52+
bool has_scanned_{false};
5053
/// @brief Checks if the current packet completes the ongoing scan.
5154
/// TODO: this has been moved from velodyne_hw_interface.cpp and is a temporary solution until
5255
/// the Velodyne decoder uses the same structure as Hesai/Robosense
@@ -115,7 +118,7 @@ class VelodyneScanDecoder
115118

116119
/// @brief Virtual function for getting the flag indicating whether one cycle is ready
117120
/// @return Readied
118-
virtual bool hasScanned() = 0;
121+
virtual bool has_scanned() = 0;
119122

120123
/// @brief Virtual function for getting the constructed point cloud
121124
/// @return tuple of Point cloud and timestamp
Original file line numberDiff line numberDiff line change
@@ -1,39 +1,60 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
115
#pragma once
2-
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp"
316

417
#include <cstdint>
518

6-
namespace nebula
7-
{
8-
namespace drivers
19+
namespace nebula::drivers
920
{
1021
class VelodyneSensor
1122
{
1223
public:
13-
/// @brief each VLP lidars packat structure in user manual. If you know details, see commens in each <vlp_list>.hpp file.
14-
/// To ignore an empty data blocks which is created by only VLS128 dual return mode case
15-
virtual int getNumPaddingBlocks(bool /* dual_return */) { return 0; }
16-
17-
/// @brief each VLP lidar laser timing in user manual. If you know details, see commens in each <vlp_list>.hpp file.
18-
/// calculate and stack the firing timing for each laser timeing used in getAzimuthCorrected to calculate the corrected azimuth
19-
virtual bool fillAzimuthCache() { return false; }
24+
VelodyneSensor() = default;
25+
VelodyneSensor(const VelodyneSensor &) = default;
26+
VelodyneSensor(VelodyneSensor &&) = default;
27+
VelodyneSensor & operator=(const VelodyneSensor &) = default;
28+
VelodyneSensor & operator=(VelodyneSensor &&) = default;
29+
virtual ~VelodyneSensor() = default;
30+
31+
/// @brief each VLP lidars packat structure in user manual. If you know details, see commens in
32+
/// each <vlp_list>.hpp file. To ignore an empty data blocks which is created by only VLS128 dual
33+
/// return mode case
34+
virtual int get_num_padding_blocks(bool /* dual_return */) { return 0; }
35+
36+
/// @brief each VLP lidar laser timing in user manual. If you know details, see commens in each
37+
/// <vlp_list>.hpp file. calculate and stack the firing timing for each laser timeing used in
38+
/// getAzimuthCorrected to calculate the corrected azimuth
39+
virtual bool fill_azimuth_cache() { return false; }
2040

2141
/// @brief VSL128User manual p. Packet structure
22-
virtual uint getBank(uint bank, uint /* header */) { return bank; }
42+
virtual uint32_t get_bank(uint32_t bank, uint32_t /* header */) { return bank; }
2343

24-
/// @brief each VLP calculating sample code and formula in user manual. If you know details, see commens in each <vlp_list>.hpp file.
25-
/// calculate the corrected azimuth from each firing timing.
26-
virtual uint16_t getAzimuthCorrected(
44+
/// @brief each VLP calculating sample code and formula in user manual. If you know details, see
45+
/// commens in each <vlp_list>.hpp file. calculate the corrected azimuth from each firing timing.
46+
virtual uint16_t get_azimuth_corrected(
2747
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) = 0;
2848

2949
/// @brief each VLP calculating sample code and formula in user manual. Check packet structure.
3050
/// Get a correct firing order
31-
virtual int getFiringOrder(int /* channels_per_block */, int /* scans_per_firing */) { return 0; }
51+
virtual int get_firing_order(int /* channels_per_block */, int /* scans_per_firing */)
52+
{
53+
return 0;
54+
}
3255

3356
/// @brief each VLP calculating sample code and formula in user manual. Check packet structure.
3457
/// Get a correct channel number
35-
virtual int getChannelNumber(int /* unit_idx */) { return 0; }
36-
58+
virtual int get_channel_number(int /* unit_idx */) { return 0; }
3759
};
38-
} // namespace drivers
39-
} // namespace nebula
60+
} // namespace nebula::drivers
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,24 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
115
#pragma once
16+
217
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp"
318

4-
namespace nebula
5-
{
6-
namespace drivers
19+
#include <cmath>
20+
21+
namespace nebula::drivers
722
{
823

924
class VLP16 : public VelodyneSensor
@@ -15,33 +30,31 @@ class VLP16 : public VelodyneSensor
1530
/// @param firing_sequence Firing sequence
1631
/// @param firing_order Firing order
1732
/// @return Corrected azimuth
18-
uint16_t getAzimuthCorrected(
19-
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order)
33+
uint16_t get_azimuth_corrected(
34+
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) override
2035
{
2136
float azimuth_corrected =
2237
azimuth + (azimuth_diff *
23-
((firing_order * VLP16_DSR_TOFFSET) + (firing_sequence * VLP16_FIRING_TOFFSET)) /
24-
VLP16_BLOCK_DURATION);
38+
((firing_order * vlp16_dsr_toffset) + (firing_sequence * vlp16_firing_toffset)) /
39+
vlp16_block_duration);
2540

2641
return static_cast<uint16_t>(round(azimuth_corrected)) % 36000;
2742
}
2843

2944
// Not succeed nebula_test on only VLP32 so add this function
3045
// Choose the correct azimuth from the 2 azimuths
31-
uint16_t getTrueRotation(uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
46+
static uint16_t get_true_rotation(
47+
uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
3248
{
3349
return azimuth_corrected;
3450
}
3551

36-
int getFiringOrder(int channels, int scans_per_firing)
52+
int get_firing_order(int channels, int scans_per_firing) override
3753
{
3854
return channels / scans_per_firing;
3955
}
4056

41-
int getChannelNumber(int unit_idx)
42-
{
43-
return unit_idx % channels_per_firing_sequence;
44-
}
57+
int get_channel_number(int unit_idx) override { return unit_idx % channels_per_firing_sequence; }
4558

4659
constexpr static int num_maintenance_periods = 0;
4760

@@ -60,11 +73,10 @@ class VLP16 : public VelodyneSensor
6073
constexpr static double offset_packet_time = 0;
6174

6275
/** Special Defines for VLP16 support **/
63-
constexpr static const int VLP16_FIRINGS_PER_BLOCK = 2;
64-
constexpr static const int VLP16_SCANS_PER_FIRING = 16;
65-
constexpr static const float VLP16_BLOCK_DURATION = 110.592f; // [µs]
66-
constexpr static const float VLP16_DSR_TOFFSET = 2.304f; // [µs]
67-
constexpr static const float VLP16_FIRING_TOFFSET = 55.296f; // [µs]
76+
constexpr static const int vlp16_firings_per_block = 2;
77+
constexpr static const int vlp16_scans_per_firing = 16;
78+
constexpr static const float vlp16_block_duration = 110.592f; // [µs]
79+
constexpr static const float vlp16_dsr_toffset = 2.304f; // [µs]
80+
constexpr static const float vlp16_firing_toffset = 55.296f; // [µs]
6881
};
69-
} // namespace drivers
70-
} // namespace nebula
82+
} // namespace nebula::drivers
Original file line numberDiff line numberDiff line change
@@ -1,20 +1,34 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
115
#pragma once
216

317
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp"
418

5-
namespace nebula
6-
{
7-
namespace drivers
19+
#include <cmath>
20+
21+
namespace nebula::drivers
822
{
923
class VLP32 : public VelodyneSensor
1024
{
1125
public:
12-
// calculate and stack the firing timing for each laser timeing
13-
/// @brief laser timing for VLP32 from VLP32 User manual in p.61
14-
bool fillAzimuthCache()
26+
// calculate and stack the firing timing for each laser timeing
27+
/// @brief laser timing for VLP32 from VLP32 User manual in p.61
28+
bool fill_azimuth_cache() override
1529
{
1630
for (uint8_t i = 0; i < 16; i++) {
17-
laser_azimuth_cache_[i] = (VLP32_CHANNEL_DURATION / VLP32_SEQ_DURATION) * (i + i / 2);
31+
laser_azimuth_cache_[i] = (vlp32_channel_duration / vlp32_seq_duration) * (i + i / 2);
1832
}
1933
return true;
2034
}
@@ -24,8 +38,8 @@ class VLP32 : public VelodyneSensor
2438
/// @param azimuth_diff Azimuth difference between a current azimuth and a next azimuth
2539
/// @param firing_order Firing order
2640
/// @return Corrected azimuth
27-
uint16_t getAzimuthCorrected(
28-
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order)
41+
uint16_t get_azimuth_corrected(
42+
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order) override
2943
{
3044
float azimuth_corrected = azimuth + (azimuth_diff * laser_azimuth_cache_[firing_order]);
3145

@@ -34,20 +48,17 @@ class VLP32 : public VelodyneSensor
3448

3549
// Not succeed nebula_test on only VLP32 so add this function
3650
// Choose the correct azimuth from the 2 azimuths
37-
uint16_t getTrueRotation(uint16_t /* azimuth_corrected */, uint16_t current_block_rotation)
51+
uint16_t get_true_rotation(uint16_t /* azimuth_corrected */, uint16_t current_block_rotation)
3852
{
3953
return current_block_rotation;
4054
}
4155

42-
int getFiringOrder(int channels, int scans_per_firing)
56+
int get_firing_order(int channels, int scans_per_firing) override
4357
{
4458
return channels / scans_per_firing;
4559
}
46-
47-
int getChannelNumber(int unit_idx)
48-
{
49-
return unit_idx % channels_per_firing_sequence;
50-
}
60+
61+
int get_channel_number(int unit_idx) override { return unit_idx % channels_per_firing_sequence; }
5162

5263
constexpr static int num_maintenance_periods = 0;
5364

@@ -66,14 +77,12 @@ class VLP32 : public VelodyneSensor
6677
constexpr static double offset_packet_time = 0;
6778

6879
/** Special Definitions for VLS32 support **/
69-
constexpr static const float VLP32_CHANNEL_DURATION =
80+
constexpr static const float vlp32_channel_duration =
7081
2.304f; // [µs] Channels corresponds to one laser firing
71-
constexpr static const float VLP32_SEQ_DURATION =
82+
constexpr static const float vlp32_seq_duration =
7283
55.296f; // [µs] Sequence is a set of laser firings including recharging
7384

74-
7585
private:
7686
float laser_azimuth_cache_[16];
7787
};
78-
} // namespace drivers
79-
} // namespace nebula
88+
} // namespace nebula::drivers
Original file line numberDiff line numberDiff line change
@@ -1,28 +1,46 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
115
#pragma once
16+
217
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp"
318

4-
namespace nebula
5-
{
6-
namespace drivers
19+
#include <rclcpp/logger.hpp>
20+
#include <rclcpp/logging.hpp>
21+
22+
#include <cmath>
23+
24+
namespace nebula::drivers
725
{
826

927
class VLS128 : public VelodyneSensor
1028
{
1129
public:
1230
// To ignore an empty data blocks in VLS128 case
1331
/// @brief VLS128 Dual return mode data structure in VLS128 User manual p.57
14-
int getNumPaddingBlocks(bool dual_return)
32+
int get_num_padding_blocks(bool dual_return) override
1533
{
1634
if (dual_return) return 4;
1735
return 0;
1836
}
1937

20-
// calculate and stack the firing timing for each laser timeing
21-
/// @brief laser timing for VLS128 from VLS128 User manual in p.61
22-
bool fillAzimuthCache()
38+
// calculate and stack the firing timing for each laser timeing
39+
/// @brief laser timing for VLS128 from VLS128 User manual in p.61
40+
bool fill_azimuth_cache() override
2341
{
2442
for (uint8_t i = 0; i < 16; i++) {
25-
laser_azimuth_cache_[i] = (VLS128_CHANNEL_DURATION / VLS128_SEQ_DURATION) * (i + i / 8);
43+
laser_azimuth_cache_[i] = (vls128_channel_duration / vls128_seq_duration) * (i + i / 8);
2644
}
2745
return true;
2846
}
@@ -32,8 +50,8 @@ class VLS128 : public VelodyneSensor
3250
/// @param azimuth_diff Azimuth difference
3351
/// @param firing_order Firing order
3452
/// @return Corrected azimuth
35-
uint16_t getAzimuthCorrected(
36-
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order)
53+
uint16_t get_azimuth_corrected(
54+
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order) override
3755
{
3856
float azimuth_corrected = azimuth + (azimuth_diff * laser_azimuth_cache_[firing_order]);
3957

@@ -42,24 +60,26 @@ class VLS128 : public VelodyneSensor
4260

4361
// Not succeed nebula_test on only VLP32 so add this function
4462
// Choose the correct azimuth from the 2 azimuths
45-
uint16_t getTrueRotation(uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
63+
static uint16_t get_true_rotation(
64+
uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
4665
{
4766
return azimuth_corrected;
4867
}
4968

50-
uint getBank(uint bank, uint header) {
69+
uint32_t get_bank(uint32_t bank, uint32_t header) override
70+
{
5171
// Used to detect which bank of 32 lasers is in this block.
5272
switch (header) {
53-
case BANK_1:
73+
case bank_1:
5474
bank = 0;
5575
break;
56-
case BANK_2:
76+
case bank_2:
5777
bank = 32;
5878
break;
59-
case BANK_3:
79+
case bank_3:
6080
bank = 64;
6181
break;
62-
case BANK_4:
82+
case bank_4:
6383
bank = 96;
6484
break;
6585
default:
@@ -71,15 +91,12 @@ class VLS128 : public VelodyneSensor
7191
return bank;
7292
}
7393

74-
int getFiringOrder(int channels, int scans_per_firing)
94+
int get_firing_order(int channels, int scans_per_firing) override
7595
{
7696
return channels / scans_per_firing;
7797
}
7898

79-
int getChannelNumber(int unit_idx)
80-
{
81-
return unit_idx % channels_per_firing_sequence;
82-
}
99+
int get_channel_number(int unit_idx) override { return unit_idx % channels_per_firing_sequence; }
83100

84101
constexpr static int num_maintenance_periods = 1;
85102

@@ -98,19 +115,20 @@ class VLS128 : public VelodyneSensor
98115
constexpr static double offset_packet_time = 8.7 * 1e-6;
99116

100117
/** Special Definitions for VLS128 support **/
101-
constexpr static const float VLP128_DISTANCE_RESOLUTION = 0.004f; // [m]
118+
constexpr static const float vls128_distance_resolution = 0.004f; // [m]
102119

103-
constexpr static const float VLS128_CHANNEL_DURATION = 2.665f; // [µs] Channels corresponds to one laser firing
120+
constexpr static const float vls128_channel_duration =
121+
2.665f; // [µs] Channels corresponds to one laser firing
104122

105-
constexpr static const float VLS128_SEQ_DURATION = 53.3f; // [µs] Sequence is a set of laser firings including recharging
123+
constexpr static const float vls128_seq_duration =
124+
53.3f; // [µs] Sequence is a set of laser firings including recharging
106125
// These are used to detect which bank of 32 lasers is in this block
107-
constexpr static const uint16_t BANK_1 = 0xeeff;
108-
constexpr static const uint16_t BANK_2 = 0xddff;
109-
constexpr static const uint16_t BANK_3 = 0xccff;
110-
constexpr static const uint16_t BANK_4 = 0xbbff;
126+
constexpr static const uint16_t bank_1 = 0xeeff;
127+
constexpr static const uint16_t bank_2 = 0xddff;
128+
constexpr static const uint16_t bank_3 = 0xccff;
129+
constexpr static const uint16_t bank_4 = 0xbbff;
111130

112131
private:
113-
float laser_azimuth_cache_[16];
132+
float laser_azimuth_cache_[16]{};
114133
};
115-
} // namespace drivers
116-
} // namespace nebula
134+
} // namespace nebula::drivers

‎nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp

+2-6
Original file line numberDiff line numberDiff line change
@@ -19,25 +19,21 @@
1919
#include "nebula_common/nebula_status.hpp"
2020
#include "nebula_common/point_types.hpp"
2121
#include "nebula_common/velodyne/velodyne_common.hpp"
22-
#include "nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp"
2322
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp"
2423

2524
#include <velodyne_msgs/msg/velodyne_packet.hpp>
2625
#include <velodyne_msgs/msg/velodyne_scan.hpp>
2726

2827
#include <pcl_conversions/pcl_conversions.h>
2928

30-
#include <iostream>
3129
#include <memory>
32-
#include <stdexcept>
33-
#include <string>
3430
#include <tuple>
3531
#include <vector>
3632

3733
namespace nebula::drivers
3834
{
3935
/// @brief Velodyne driver
40-
class VelodyneDriver : NebulaDriverBase
36+
class VelodyneDriver
4137
{
4238
private:
4339
/// @brief Current driver status
@@ -59,7 +55,7 @@ class VelodyneDriver : NebulaDriverBase
5955
/// @param calibration_configuration
6056
/// @return Resulting status
6157
Status set_calibration_configuration(
62-
const CalibrationConfigurationBase & calibration_configuration) override;
58+
const CalibrationConfigurationBase & calibration_configuration);
6359

6460
/// @brief Get current status of this driver
6561
/// @return Current status

‎nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
#include "nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp"
44

5+
#include "memory"
56
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp"
67
#include "nebula_decoders/nebula_decoders_velodyne/decoders/vlp_16.hpp"
78
#include "nebula_decoders/nebula_decoders_velodyne/decoders/vlp_32.hpp"
@@ -21,18 +22,18 @@ VelodyneDriver::VelodyneDriver(
2122
driver_status_ = nebula::Status::INVALID_SENSOR_MODEL;
2223
break;
2324
case SensorModel::VELODYNE_VLS128:
24-
scan_decoder_.reset(
25-
new VelodyneDecoder<VLS128>(sensor_configuration, calibration_configuration));
25+
scan_decoder_ =
26+
std::make_shared<VelodyneDecoder<VLS128>>(sensor_configuration, calibration_configuration);
2627
break;
2728
case SensorModel::VELODYNE_VLP32:
2829
case SensorModel::VELODYNE_HDL64:
2930
case SensorModel::VELODYNE_HDL32:
30-
scan_decoder_.reset(
31-
new VelodyneDecoder<VLP32>(sensor_configuration, calibration_configuration));
31+
scan_decoder_ =
32+
std::make_shared<VelodyneDecoder<VLP32>>(sensor_configuration, calibration_configuration);
3233
break;
3334
case SensorModel::VELODYNE_VLP16:
34-
scan_decoder_.reset(
35-
new VelodyneDecoder<VLP16>(sensor_configuration, calibration_configuration));
35+
scan_decoder_ =
36+
std::make_shared<VelodyneDecoder<VLP16>>(sensor_configuration, calibration_configuration);
3637
break;
3738
default:
3839
driver_status_ = nebula::Status::INVALID_SENSOR_MODEL;

0 commit comments

Comments
 (0)
Please sign in to comment.