Skip to content

Commit

Permalink
fix segmentation fault
Browse files Browse the repository at this point in the history
Signed-off-by: Yamato Ando <[email protected]>
  • Loading branch information
YamatoAndo committed Sep 24, 2024
1 parent aaf5f27 commit cf05e77
Showing 1 changed file with 5 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,11 @@ std::vector<landmark_manager::Landmark> LidarMarkerLocalizer::detect_landmarks(
// Check that the leaf size is not too small, given the size of the data
const int bin_num = static_cast<int>((max_x - min_x) / param_.resolution + 1);

if (bin_num < static_cast<int>(param_.intensity_pattern.size())) {
RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, "bin_num is too small!");
return std::vector<landmark_manager::Landmark>{};
}

Check warning on line 366 in localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

LidarMarkerLocalizer::detect_landmarks increases in cyclomatic complexity from 25 to 26, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
// initialize variables
std::vector<int> vote(bin_num, 0);
std::vector<float> min_y(bin_num, std::numeric_limits<float>::max());
Expand Down

0 comments on commit cf05e77

Please sign in to comment.