@@ -146,13 +146,8 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
146
146
request,
147
147
[](rclcpp::Client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>::SharedFuture) {})};
148
148
149
- // While waiting for the requested pcds, look for indices of the candidate pcds
150
- std::unordered_set<std::string> pcds_to_remove, pcds_to_add;
151
-
152
- query_pcds (position.x , position.y , param_.map_radius , pcds_to_add, pcds_to_remove);
153
-
154
- // Wait for maximum 20 milliseconds
155
- std::chrono::milliseconds timeout (20 );
149
+ // Wait for maximum 10 milliseconds
150
+ std::chrono::milliseconds timeout (10 );
156
151
auto start = std::chrono::system_clock::now ();
157
152
158
153
std::future_status status = result.wait_for (std::chrono::seconds (0 ));
@@ -177,23 +172,7 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
177
172
auto & maps_to_add = result.get ()->new_pointcloud_with_ids ;
178
173
auto & map_ids_to_remove = result.get ()->ids_to_remove ;
179
174
180
- // Check if there are any maps in the pcds_to_add not coming
181
- for (auto & name : pcds_to_add)
182
- {
183
- if (maps_to_add.find (name) == maps_to_add.end ())
184
- {
185
- RCLCPP_ERROR_STREAM_THROTTLE (logger_, *clock_, 1000 , " File %s not coming." , name.c_str ());
186
- }
187
- }
188
-
189
- for (auto & name : pcds_to_remove)
190
- {
191
- if (map_ids_to_remove.find (name) == map_ids_to_remove.end ())
192
- {
193
- RCLCPP_ERROR_STREAM_THROTTLE (logger_, *clock_, 1000 , " File %s should be removed but it was not." , name.c_str ());
194
- }
195
- }
196
-
175
+ // Check
197
176
RCLCPP_INFO (
198
177
logger_, " Update map (Add: %lu, Remove: %lu)" , maps_to_add.size (), map_ids_to_remove.size ());
199
178
if (maps_to_add.empty () && map_ids_to_remove.empty ()) {
@@ -236,59 +215,3 @@ void MapUpdateModule::publish_partial_pcd_map()
236
215
237
216
loaded_pcd_pub_->publish (map_msg);
238
217
}
239
-
240
- void MapUpdateModuble::query_pcds (double px, double py, double radius, std::unordered_set<std::string>& maps_to_add, std::unordered_set<std::string>& maps_to_remove)
241
- {
242
- int lower_x = static_cast <int >(floor ((px - radius) / pcd_res_x_));
243
- int lower_y = static_cast <int >(floor ((py - radius) / pcd_res_y_));
244
- int upper_x = static_cast <int >(floor ((px + radius) / pcd_res_x_));
245
- int upper_y = static_cast <int >(floor ((py + radius) / pcd_res_y_));
246
- double rel_px = px - pcd_lower_x_, rel_py = py - pcd_lower_y_;
247
- std::unordered_set<std::string> nn_pcds;
248
-
249
- for (int idx = lower_x; idx < upper_x; ++idx)
250
- {
251
- for (int idy = lower_y; idy < upper_y; ++idy)
252
- {
253
- // Skip if the pcd file is not within the query radius
254
- if (dist (rel_px, rel_py, idx, idy) > radius)
255
- {
256
- continue ;
257
- }
258
-
259
- // Generate name of the PCD file
260
- std::string name = pcd_tag_ + " _" + std::to_string (x) + " _" + std::to_string (y) + " .pcd" ;
261
-
262
- if (cur_pcds_.find (name) == cur_pcds_.end ())
263
- {
264
- maps_to_add.insert (name);
265
- }
266
- else
267
- {
268
- nn_pcds.insert (name);
269
- }
270
- }
271
- }
272
-
273
- // Compare with @cur_pcds_ to find out which pcds to remove
274
- for (auto & name : cur_pcds_)
275
- {
276
- if (nn_pcds.find (name) == nn_pcds.end ())
277
- {
278
- map_ids_to_remove.insert (name);
279
- }
280
- }
281
- }
282
-
283
- double MapUpdateModule::dist (double px, double py, int idx, int idy)
284
- {
285
- double lx = idx * pcd_res_x_;
286
- double ly = idy * pcd_res_y_;
287
- double ux = lx + pcd_res_x_;
288
- double uy = ly + pcd_res_y_;
289
-
290
- double dx = (px < lx) ? lx - px : ((px >= ux) ? px - ux : 0 );
291
- double dy = (py < ly) ? ly - py : ((py >= uy) ? py - uy : 0 );
292
-
293
- return std::hypot (dx, dy);
294
- }
0 commit comments