15
15
#include " ndt_scan_matcher/map_update_module.hpp"
16
16
17
17
MapUpdateModule::MapUpdateModule (
18
- rclcpp::Node * node, std::mutex * ndt_ptr_mutex,
19
- std::shared_ptr<NormalDistributionsTransform> ndt_ptr, HyperParameters::DynamicMapLoading param)
20
- : ndt_ptr_(std::move( ndt_ptr) ),
18
+ rclcpp::Node * node, std::mutex * ndt_ptr_mutex, NdtPtrType & ndt_ptr,
19
+ HyperParameters::DynamicMapLoading param)
20
+ : ndt_ptr_(ndt_ptr),
21
21
ndt_ptr_mutex_(ndt_ptr_mutex),
22
22
logger_(node->get_logger ()),
23
23
clock_(node->get_clock ()),
@@ -28,29 +28,90 @@ MapUpdateModule::MapUpdateModule(
28
28
29
29
pcd_loader_client_ =
30
30
node->create_client <autoware_map_msgs::srv::GetDifferentialPointCloudMap>(" pcd_loader_service" );
31
+
32
+ secondary_ndt_ptr_.reset (new NdtType);
33
+
34
+ if (ndt_ptr_) {
35
+ *secondary_ndt_ptr_ = *ndt_ptr_;
36
+ } else {
37
+ RCLCPP_ERROR_STREAM_THROTTLE (logger_, *clock_, 1000 , " Attempt to update a null NDT pointer." );
38
+ }
39
+
40
+ // Initially, a direct map update on ndt_ptr_ is needed.
41
+ // ndt_ptr_'s mutex is locked until it is fully rebuilt.
42
+ // From the second update, the update is done on secondary_ndt_ptr_,
43
+ // and ndt_ptr_ is only locked when swapping its pointer with
44
+ // secondary_ndt_ptr_.
45
+ need_rebuild_ = true ;
31
46
}
32
47
33
- bool MapUpdateModule::should_update_map (const geometry_msgs::msg::Point & position) const
48
+ bool MapUpdateModule::should_update_map (const geometry_msgs::msg::Point & position)
34
49
{
35
50
if (last_update_position_ == std::nullopt) {
36
51
return false ;
37
52
}
53
+
38
54
const double dx = position.x - last_update_position_.value ().x ;
39
55
const double dy = position.y - last_update_position_.value ().y ;
40
56
const double distance = std::hypot (dx, dy);
41
57
if (distance + param_.lidar_radius > param_.map_radius ) {
42
58
RCLCPP_ERROR_STREAM_THROTTLE (logger_, *clock_, 1000 , " Dynamic map loading is not keeping up." );
59
+ // If the map does not keep up with the current position,
60
+ // lock ndt_ptr_ entirely until it is fully rebuilt.
61
+ need_rebuild_ = true ;
43
62
}
63
+
44
64
return distance > param_.update_distance ;
45
65
}
46
66
47
67
void MapUpdateModule::update_map (const geometry_msgs::msg::Point & position)
68
+ {
69
+ // If the current position is super far from the previous loading position,
70
+ // lock and rebuild ndt_ptr_
71
+ if (need_rebuild_) {
72
+ ndt_ptr_mutex_->lock ();
73
+ auto param = ndt_ptr_->getParams ();
74
+
75
+ ndt_ptr_.reset (new NdtType);
76
+
77
+ ndt_ptr_->setParams (param);
78
+
79
+ update_ndt (position, *ndt_ptr_);
80
+ ndt_ptr_mutex_->unlock ();
81
+ need_rebuild_ = false ;
82
+ } else {
83
+ // Load map to the secondary_ndt_ptr, which does not require a mutex lock
84
+ // Since the update of the secondary ndt ptr and the NDT align (done on
85
+ // the main ndt_ptr_) overlap, the latency of updating/alignment reduces partly.
86
+ // If the updating is done the main ndt_ptr_, either the update or the NDT
87
+ // align will be blocked by the other.
88
+ update_ndt (position, *secondary_ndt_ptr_);
89
+
90
+ ndt_ptr_mutex_->lock ();
91
+ auto input_source = ndt_ptr_->getInputSource ();
92
+ ndt_ptr_ = secondary_ndt_ptr_;
93
+ ndt_ptr_->setInputSource (input_source);
94
+ ndt_ptr_mutex_->unlock ();
95
+ }
96
+
97
+ secondary_ndt_ptr_.reset (new NdtType);
98
+ *secondary_ndt_ptr_ = *ndt_ptr_;
99
+
100
+ // Memorize the position of the last update
101
+ last_update_position_ = position;
102
+
103
+ // Publish the new ndt maps
104
+ publish_partial_pcd_map ();
105
+ }
106
+
107
+ void MapUpdateModule::update_ndt (const geometry_msgs::msg::Point & position, NdtType & ndt)
48
108
{
49
109
auto request = std::make_shared<autoware_map_msgs::srv::GetDifferentialPointCloudMap::Request>();
110
+
50
111
request->area .center_x = static_cast <float >(position.x );
51
112
request->area .center_y = static_cast <float >(position.y );
52
113
request->area .radius = static_cast <float >(param_.map_radius );
53
- request->cached_ids = ndt_ptr_-> getCurrentMapIDs ();
114
+ request->cached_ids = ndt. getCurrentMapIDs ();
54
115
55
116
while (!pcd_loader_client_->wait_for_service (std::chrono::seconds (1 )) && rclcpp::ok ()) {
56
117
RCLCPP_INFO (logger_, " Waiting for pcd loader service. Check the pointcloud_map_loader." );
@@ -69,60 +130,49 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position)
69
130
}
70
131
status = result.wait_for (std::chrono::seconds (1 ));
71
132
}
72
- update_ndt (result.get ()->new_pointcloud_with_ids , result.get ()->ids_to_remove );
73
- last_update_position_ = position;
74
- }
75
133
76
- void MapUpdateModule::update_ndt (
77
- const std::vector<autoware_map_msgs::msg::PointCloudMapCellWithID> & maps_to_add,
78
- const std::vector<std::string> & map_ids_to_remove)
79
- {
134
+ auto & maps_to_add = result.get ()->new_pointcloud_with_ids ;
135
+ auto & map_ids_to_remove = result.get ()->ids_to_remove ;
136
+
80
137
RCLCPP_INFO (
81
138
logger_, " Update map (Add: %lu, Remove: %lu)" , maps_to_add.size (), map_ids_to_remove.size ());
82
139
if (maps_to_add.empty () && map_ids_to_remove.empty ()) {
83
140
RCLCPP_INFO (logger_, " Skip map update" );
84
141
return ;
85
142
}
86
- const auto exe_start_time = std::chrono::system_clock::now ();
87
143
144
+ const auto exe_start_time = std::chrono::system_clock::now ();
88
145
const size_t add_size = maps_to_add.size ();
89
-
90
146
// Perform heavy processing outside of the lock scope
91
147
std::vector<pcl::shared_ptr<pcl::PointCloud<PointTarget>>> points_pcl (add_size);
148
+
92
149
for (size_t i = 0 ; i < add_size; i++) {
93
150
points_pcl[i] = pcl::make_shared<pcl::PointCloud<PointTarget>>();
94
151
pcl::fromROSMsg (maps_to_add[i].pointcloud , *points_pcl[i]);
95
152
}
96
153
97
- (*ndt_ptr_mutex_).lock ();
98
-
99
154
// Add pcd
100
155
for (size_t i = 0 ; i < add_size; i++) {
101
- ndt_ptr_-> addTarget (points_pcl[i], maps_to_add[i].cell_id );
156
+ ndt. addTarget (points_pcl[i], maps_to_add[i].cell_id );
102
157
}
103
158
104
159
// Remove pcd
105
160
for (const std::string & map_id_to_remove : map_ids_to_remove) {
106
- ndt_ptr_-> removeTarget (map_id_to_remove);
161
+ ndt. removeTarget (map_id_to_remove);
107
162
}
108
163
109
- ndt_ptr_->createVoxelKdtree ();
110
-
111
- (*ndt_ptr_mutex_).unlock ();
164
+ ndt.createVoxelKdtree ();
112
165
113
166
const auto exe_end_time = std::chrono::system_clock::now ();
114
167
const auto duration_micro_sec =
115
168
std::chrono::duration_cast<std::chrono::microseconds>(exe_end_time - exe_start_time).count ();
116
169
const auto exe_time = static_cast <double >(duration_micro_sec) / 1000.0 ;
117
170
RCLCPP_INFO (logger_, " Time duration for creating new ndt_ptr: %lf [ms]" , exe_time);
118
-
119
- publish_partial_pcd_map ();
120
171
}
121
172
122
173
void MapUpdateModule::publish_partial_pcd_map ()
123
174
{
124
175
pcl::PointCloud<PointTarget> map_pcl = ndt_ptr_->getVoxelPCD ();
125
-
126
176
sensor_msgs::msg::PointCloud2 map_msg;
127
177
pcl::toROSMsg (map_pcl, map_msg);
128
178
map_msg.header .frame_id = " map" ;
0 commit comments