Skip to content

Commit a181ab9

Browse files
committed
Keep timeout only
Signed-off-by: anhnv3991 <anh.nguyen.2@tier4.jp>
1 parent 6a6ac7d commit a181ab9

File tree

3 files changed

+3
-105
lines changed

3 files changed

+3
-105
lines changed

localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp

-5
Original file line numberDiff line numberDiff line change
@@ -60,11 +60,6 @@ class MapUpdateModule
6060
[[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position);
6161
void publish_partial_pcd_map();
6262

63-
// Looking for PCDs in the vicinity of the specified location
64-
void query_pcds(double px, double py, double radius, std::unordered_set<std::string>& maps_to_add, std::unordered_set<std::string>& maps_to_remove);
65-
// Compute distance between an origin and a pcd segment
66-
double dist(double px, double py, int idx, int idy);
67-
6863
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr loaded_pcd_pub_;
6964

7065
rclcpp::Client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>::SharedPtr

localization/ndt_scan_matcher/src/map_update_module.cpp

+3-80
Original file line numberDiff line numberDiff line change
@@ -146,13 +146,8 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt
146146
request,
147147
[](rclcpp::Client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>::SharedFuture) {})};
148148

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);
156151
auto start = std::chrono::system_clock::now();
157152

158153
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
177172
auto & maps_to_add = result.get()->new_pointcloud_with_ids;
178173
auto & map_ids_to_remove = result.get()->ids_to_remove;
179174

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
197176
RCLCPP_INFO(
198177
logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size());
199178
if (maps_to_add.empty() && map_ids_to_remove.empty()) {
@@ -236,59 +215,3 @@ void MapUpdateModule::publish_partial_pcd_map()
236215

237216
loaded_pcd_pub_->publish(map_msg);
238217
}
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-
}

map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp

-20
Original file line numberDiff line numberDiff line change
@@ -29,13 +29,6 @@ void DifferentialMapLoaderModule::differentialAreaLoad(
2929
const autoware_map_msgs::msg::AreaInfo & area, const std::vector<std::string> & cached_ids,
3030
GetDifferentialPointCloudMap::Response::SharedPtr & response) const
3131
{
32-
33-
// For debug
34-
std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app);
35-
36-
test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl;
37-
// End
38-
3932
// iterate over all the available pcd map grids
4033
std::vector<bool> should_remove(static_cast<int>(cached_ids.size()), true);
4134
for (const auto & ele : all_pcd_file_metadata_dict_) {
@@ -74,12 +67,6 @@ bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap(
7467
GetDifferentialPointCloudMap::Request::SharedPtr req,
7568
GetDifferentialPointCloudMap::Response::SharedPtr res)
7669
{
77-
// For debug
78-
std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app);
79-
80-
test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl;
81-
// End
82-
8370
auto area = req->area;
8471
std::vector<std::string> cached_ids = req->cached_ids;
8572
differentialAreaLoad(area, cached_ids, res);
@@ -91,13 +78,6 @@ autoware_map_msgs::msg::PointCloudMapCellWithID
9178
DifferentialMapLoaderModule::loadPointCloudMapCellWithID(
9279
const std::string & path, const std::string & map_id) const
9380
{
94-
95-
// For debug
96-
std::ofstream test("/home/anh/Work/autoware/test.txt", std::ios::app);
97-
98-
test << __FILE__ << "::" << __LINE__ << "::" << __func__ << std::endl;
99-
// End
100-
10181
sensor_msgs::msg::PointCloud2 pcd;
10282
if (pcl::io::loadPCDFile(path, pcd) == -1) {
10383
RCLCPP_ERROR_STREAM(logger_, "PCD load failed: " << path);

0 commit comments

Comments
 (0)