Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Feb 28, 2024
1 parent 61a1e0b commit 73ac31b
Showing 1 changed file with 4 additions and 5 deletions.
9 changes: 4 additions & 5 deletions localization/ndt_scan_matcher/src/map_update_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,16 +153,15 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt

const auto exe_start_time = std::chrono::system_clock::now();
// Perform heavy processing outside of the lock scope

// Add pcd
for (auto& map : maps_to_add)
{
for (auto & map : maps_to_add) {
auto cloud = pcl::make_shared<pcl::PointCloud<PointTarget>>();

pcl::fromROSMsg(map.pointcloud, *cloud);
ndt.addTarget(cloud, map.cell_id);

Check notice on line 162 in localization/ndt_scan_matcher/src/map_update_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

MapUpdateModule::update_ndt decreases in cyclomatic complexity from 10 to 9, 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.
}

// Remove pcd
for (const std::string & map_id_to_remove : map_ids_to_remove) {
ndt.removeTarget(map_id_to_remove);
Expand Down

0 comments on commit 73ac31b

Please sign in to comment.