Skip to content

Commit 860f6a0

Browse files
committed
refactor: simplify if condition
1 parent 59a5c22 commit 860f6a0

File tree

3 files changed

+33
-15
lines changed

3 files changed

+33
-15
lines changed

nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp

+11-5
Original file line numberDiff line numberDiff line change
@@ -237,14 +237,20 @@ void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa
237237

238238
// Condition added to avoid calculating points which are not in the interesting
239239
// defined area (min_angle < area < max_angle).
240-
if (
241-
((azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 &&
240+
const bool is_within_min_max_angle =
241+
(azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 &&
242242
azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 &&
243-
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) ||
243+
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle);
244+
245+
const bool is_outside_max_min_angle =
244246
(sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle &&
245247
(azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 ||
246-
azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100))) &&
247-
!check_excluded_point(corrections.laser_ring, azimuth_corrected)) {
248+
azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100));
249+
250+
const bool is_not_excluded_point =
251+
!check_excluded_point(corrections.laser_ring, azimuth_corrected);
252+
253+
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
248254
// Convert polar coordinates to Euclidean XYZ.
249255
const float cos_vert_angle = corrections.cos_vert_correction;
250256
const float sin_vert_angle = corrections.sin_vert_correction;

nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp

+11-5
Original file line numberDiff line numberDiff line change
@@ -194,14 +194,20 @@ void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa
194194
distance < sensor_configuration_->max_range) {
195195
/*condition added to avoid calculating points which are not
196196
in the interesting defined area (min_angle < area < max_angle)*/
197-
if (
198-
((block.rotation >= sensor_configuration_->cloud_min_angle * 100 &&
197+
const bool is_within_min_max_angle =
198+
(block.rotation >= sensor_configuration_->cloud_min_angle * 100 &&
199199
block.rotation <= sensor_configuration_->cloud_max_angle * 100 &&
200-
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) ||
200+
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle);
201+
202+
const bool is_outside_max_min_angle =
201203
(sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle &&
202204
(raw->blocks[i].rotation <= sensor_configuration_->cloud_max_angle * 100 ||
203-
raw->blocks[i].rotation >= sensor_configuration_->cloud_min_angle * 100))) &&
204-
!check_excluded_point(corrections.laser_ring, block.rotation)) {
205+
raw->blocks[i].rotation >= sensor_configuration_->cloud_min_angle * 100));
206+
207+
const bool is_not_excluded_point =
208+
!check_excluded_point(corrections.laser_ring, block.rotation);
209+
210+
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
205211
const float cos_vert_angle = corrections.cos_vert_correction;
206212
const float sin_vert_angle = corrections.sin_vert_correction;
207213
const float cos_rot_correction = corrections.cos_rot_correction;

nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp

+11-5
Original file line numberDiff line numberDiff line change
@@ -258,14 +258,20 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p
258258
distance < sensor_configuration_->max_range) {
259259
// Condition added to avoid calculating points which are not in the interesting defined
260260
// area (cloud_min_angle < area < cloud_max_angle).
261-
if (
262-
((azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 &&
261+
const bool is_within_min_max_angle =
262+
(azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 &&
263263
azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 &&
264-
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) ||
264+
sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle);
265+
266+
const bool is_outside_max_min_angle =
265267
(sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle &&
266268
(azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 ||
267-
azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100))) &&
268-
!check_excluded_point(corrections.laser_ring, azimuth_corrected)) {
269+
azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100));
270+
271+
const bool is_not_excluded_point =
272+
!check_excluded_point(corrections.laser_ring, azimuth_corrected);
273+
274+
if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) {
269275
// convert polar coordinates to Euclidean XYZ.
270276
const float cos_vert_angle = corrections.cos_vert_correction;
271277
const float sin_vert_angle = corrections.sin_vert_correction;

0 commit comments

Comments
 (0)