From a47d4a738ff03c7690f734b5cc54dafaf919f56f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mehmet=20Emin=20BA=C5=9EO=C4=9ELU?= Date: Tue, 16 Apr 2024 18:32:02 +0300 Subject: [PATCH] refactor: simplify if condition --- .../decoders/vlp16_decoder.cpp | 16 +++++++++++----- .../decoders/vlp32_decoder.cpp | 16 +++++++++++----- .../decoders/vls128_decoder.cpp | 16 +++++++++++----- 3 files changed, 33 insertions(+), 15 deletions(-) diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp index 855cace4a..b1596fb50 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp @@ -237,14 +237,20 @@ void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa // Condition added to avoid calculating points which are not in the interesting // defined area (min_angle < area < max_angle). - if ( - ((azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 && + const bool is_within_min_max_angle = + (azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 && azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 && - sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) || + sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle); + + const bool is_outside_max_min_angle = (sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle && (azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 || - azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100))) && - !check_excluded_point(corrections.laser_ring, azimuth_corrected)) { + azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100)); + + const bool is_not_excluded_point = + !check_excluded_point(corrections.laser_ring, azimuth_corrected); + + if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) { // Convert polar coordinates to Euclidean XYZ. const float cos_vert_angle = corrections.cos_vert_correction; const float sin_vert_angle = corrections.sin_vert_correction; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp index 6dd4ebded..cfcaf88be 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp @@ -194,14 +194,20 @@ void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa distance < sensor_configuration_->max_range) { /*condition added to avoid calculating points which are not in the interesting defined area (min_angle < area < max_angle)*/ - if ( - ((block.rotation >= sensor_configuration_->cloud_min_angle * 100 && + const bool is_within_min_max_angle = + (block.rotation >= sensor_configuration_->cloud_min_angle * 100 && block.rotation <= sensor_configuration_->cloud_max_angle * 100 && - sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) || + sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle); + + const bool is_outside_max_min_angle = (sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle && (raw->blocks[i].rotation <= sensor_configuration_->cloud_max_angle * 100 || - raw->blocks[i].rotation >= sensor_configuration_->cloud_min_angle * 100))) && - !check_excluded_point(corrections.laser_ring, block.rotation)) { + raw->blocks[i].rotation >= sensor_configuration_->cloud_min_angle * 100)); + + const bool is_not_excluded_point = + !check_excluded_point(corrections.laser_ring, block.rotation); + + if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) { const float cos_vert_angle = corrections.cos_vert_correction; const float sin_vert_angle = corrections.sin_vert_correction; const float cos_rot_correction = corrections.cos_rot_correction; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp index 3ae9d29eb..10c598785 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -258,14 +258,20 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p distance < sensor_configuration_->max_range) { // Condition added to avoid calculating points which are not in the interesting defined // area (cloud_min_angle < area < cloud_max_angle). - if ( - ((azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 && + const bool is_within_min_max_angle = + (azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100 && azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 && - sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle) || + sensor_configuration_->cloud_min_angle < sensor_configuration_->cloud_max_angle); + + const bool is_outside_max_min_angle = (sensor_configuration_->cloud_min_angle > sensor_configuration_->cloud_max_angle && (azimuth_corrected <= sensor_configuration_->cloud_max_angle * 100 || - azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100))) && - !check_excluded_point(corrections.laser_ring, azimuth_corrected)) { + azimuth_corrected >= sensor_configuration_->cloud_min_angle * 100)); + + const bool is_not_excluded_point = + !check_excluded_point(corrections.laser_ring, azimuth_corrected); + + if ((is_within_min_max_angle || is_outside_max_min_angle) && is_not_excluded_point) { // convert polar coordinates to Euclidean XYZ. const float cos_vert_angle = corrections.cos_vert_correction; const float sin_vert_angle = corrections.sin_vert_correction;