We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent f13503a commit 3153252Copy full SHA for 3153252
perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp
@@ -207,10 +207,13 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader
207
}
208
inline std::vector<std::string> getCurrentMapIDs()
209
{
210
- std::vector<std::string> current_map_ids{};
211
- std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
212
- for (auto & kv : current_voxel_grid_dict_) {
213
- current_map_ids.push_back(kv.first);
+ std::vector<std::string> current_map_ids;
+ {
+ std::lock_guard<std::mutex> lock(dynamic_map_loader_mutex_);
+ current_map_ids.reserve(current_voxel_grid_dict_.size());
214
+ for (const auto & kv : current_voxel_grid_dict_) {
215
+ current_map_ids.push_back(kv.first);
216
+ }
217
218
return current_map_ids;
219
0 commit comments