Skip to content

Commit 73ac31b

Browse files
style(pre-commit): autofix
1 parent 61a1e0b commit 73ac31b

File tree

1 file changed

+4
-5
lines changed

1 file changed

+4
-5
lines changed

localization/ndt_scan_matcher/src/map_update_module.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -153,16 +153,15 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
153153

154154
const auto exe_start_time = std::chrono::system_clock::now();
155155
// Perform heavy processing outside of the lock scope
156-
156+
157157
// Add pcd
158-
for (auto& map : maps_to_add)
159-
{
158+
for (auto & map : maps_to_add) {
160159
auto cloud = pcl::make_shared<pcl::PointCloud<PointTarget>>();
161-
160+
162161
pcl::fromROSMsg(map.pointcloud, *cloud);
163162
ndt.addTarget(cloud, map.cell_id);
164163
}
165-
164+
166165
// Remove pcd
167166
for (const std::string & map_id_to_remove : map_ids_to_remove) {
168167
ndt.removeTarget(map_id_to_remove);

0 commit comments

Comments
 (0)