@@ -71,15 +71,13 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode(
71
71
const double map_resolution = this ->declare_parameter <double >(" map_resolution" );
72
72
73
73
/* Subscriber and publisher */
74
- obstacle_pointcloud_sub_.subscribe (
75
- this , " ~/input/obstacle_pointcloud" ,
76
- rclcpp::SensorDataQoS{}.keep_last (1 ).get_rmw_qos_profile ());
77
- raw_pointcloud_sub_.subscribe (
78
- this , " ~/input/raw_pointcloud" , rclcpp::SensorDataQoS{}.keep_last (1 ).get_rmw_qos_profile ());
79
- sync_ptr_ = std::make_shared<Sync>(SyncPolicy (5 ), obstacle_pointcloud_sub_, raw_pointcloud_sub_);
80
-
81
- sync_ptr_->registerCallback (
82
- std::bind (&PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw, this , _1, _2));
74
+ obstacle_pointcloud_sub_ptr_ = this ->create_subscription <PointCloud2>(
75
+ " ~/input/obstacle_pointcloud" , rclcpp::SensorDataQoS{}.keep_last (1 ),
76
+ std::bind (&PointcloudBasedOccupancyGridMapNode::obstaclePointcloudCallback, this , _1));
77
+ raw_pointcloud_sub_ptr_ = this ->create_subscription <PointCloud2>(
78
+ " ~/input/raw_pointcloud" , rclcpp::SensorDataQoS{}.keep_last (1 ),
79
+ std::bind (&PointcloudBasedOccupancyGridMapNode::rawPointcloudCallback, this , _1));
80
+
83
81
occupancy_grid_map_pub_ = create_publisher<OccupancyGrid>(" ~/output/occupancy_grid_map" , 1 );
84
82
85
83
const std::string updater_type = this ->declare_parameter <std::string>(" updater_type" );
@@ -94,7 +92,6 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode(
94
92
occupancy_grid_map_updater_ptr_ = std::make_unique<OccupancyGridMapBBFUpdater>(
95
93
true , map_length / map_resolution, map_length / map_resolution, map_resolution);
96
94
}
97
- occupancy_grid_map_updater_ptr_->initRosParam (*this );
98
95
99
96
const std::string grid_map_type = this ->declare_parameter <std::string>(" grid_map_type" );
100
97
@@ -118,7 +115,15 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode(
118
115
occupancy_grid_map_updater_ptr_->getSizeInCellsY (),
119
116
occupancy_grid_map_updater_ptr_->getResolution ());
120
117
}
118
+
119
+ cudaStreamCreateWithFlags (&stream_, cudaStreamNonBlocking);
120
+ raw_pointcloud_.stream = stream_;
121
+ obstacle_pointcloud_.stream = stream_;
122
+ occupancy_grid_map_ptr_->setCudaStream (stream_);
123
+ occupancy_grid_map_updater_ptr_->setCudaStream (stream_);
124
+
121
125
occupancy_grid_map_ptr_->initRosParam (*this );
126
+ occupancy_grid_map_updater_ptr_->initRosParam (*this );
122
127
123
128
// initialize debug tool
124
129
{
@@ -140,14 +145,29 @@ PointcloudBasedOccupancyGridMapNode::PointcloudBasedOccupancyGridMapNode(
140
145
time_keeper_ = std::make_shared<autoware::universe_utils::TimeKeeper>(time_keeper);
141
146
}
142
147
}
148
+ }
149
+
150
+ void PointcloudBasedOccupancyGridMapNode::obstaclePointcloudCallback (
151
+ const PointCloud2::ConstSharedPtr & input_obstacle_msg)
152
+ {
153
+ obstacle_pointcloud_.fromROSMsgAsync (input_obstacle_msg);
143
154
144
- cudaStreamCreate (&raw_pointcloud_.stream );
145
- cudaStreamCreate (&obstacle_pointcloud_.stream );
155
+ if (obstacle_pointcloud_.header .stamp == raw_pointcloud_.header .stamp ) {
156
+ onPointcloudWithObstacleAndRaw ();
157
+ }
146
158
}
147
159
148
- void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw (
149
- const PointCloud2::ConstSharedPtr & input_obstacle_msg,
160
+ void PointcloudBasedOccupancyGridMapNode::rawPointcloudCallback (
150
161
const PointCloud2::ConstSharedPtr & input_raw_msg)
162
+ {
163
+ raw_pointcloud_.fromROSMsgAsync (input_raw_msg);
164
+
165
+ if (obstacle_pointcloud_.header .stamp == raw_pointcloud_.header .stamp ) {
166
+ onPointcloudWithObstacleAndRaw ();
167
+ }
168
+ }
169
+
170
+ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw ()
151
171
{
152
172
std::unique_ptr<ScopedTimeTrack> st_ptr;
153
173
if (time_keeper_) st_ptr = std::make_unique<ScopedTimeTrack>(__func__, *time_keeper_);
@@ -156,9 +176,6 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
156
176
stop_watch_ptr_->toc (" processing_time" , true );
157
177
}
158
178
159
- raw_pointcloud_.fromROSMsgAsync (*input_raw_msg);
160
- obstacle_pointcloud_.fromROSMsgAsync (*input_obstacle_msg);
161
-
162
179
// if scan_origin_frame_ is "", replace it with raw_pointcloud_.header.frame_id
163
180
if (scan_origin_frame_.empty ()) {
164
181
scan_origin_frame_ = raw_pointcloud_.header .frame_id ;
@@ -172,7 +189,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
172
189
return ;
173
190
}
174
191
}
175
- if (input_obstacle_msg-> header .frame_id != base_link_frame_) {
192
+ if (obstacle_pointcloud_. header .frame_id != base_link_frame_) {
176
193
if (!utils::transformPointcloudAsync (obstacle_pointcloud_, *tf2_, base_link_frame_)) {
177
194
return ;
178
195
}
@@ -221,7 +238,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
221
238
222
239
// publish
223
240
occupancy_grid_map_pub_->publish (OccupancyGridMapToMsgPtr (
224
- map_frame_, input_raw_msg-> header .stamp , robot_pose.position .z ,
241
+ map_frame_, raw_pointcloud_. header .stamp , robot_pose.position .z ,
225
242
*occupancy_grid_map_ptr_)); // (todo) robot_pose may be altered with gridmap_origin
226
243
} else {
227
244
std::unique_ptr<ScopedTimeTrack> inner_st_ptr;
@@ -231,10 +248,11 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
231
248
232
249
// Update with bayes filter
233
250
occupancy_grid_map_updater_ptr_->update (*occupancy_grid_map_ptr_);
251
+ occupancy_grid_map_updater_ptr_->copyDeviceCostmapToHost ();
234
252
235
253
// publish
236
254
occupancy_grid_map_pub_->publish (OccupancyGridMapToMsgPtr (
237
- map_frame_, input_raw_msg-> header .stamp , robot_pose.position .z ,
255
+ map_frame_, raw_pointcloud_. header .stamp , robot_pose.position .z ,
238
256
*occupancy_grid_map_updater_ptr_));
239
257
}
240
258
@@ -244,7 +262,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
244
262
const double pipeline_latency_ms =
245
263
std::chrono::duration<double , std::milli>(
246
264
std::chrono::nanoseconds (
247
- (this ->get_clock ()->now () - input_raw_msg-> header .stamp ).nanoseconds ()))
265
+ (this ->get_clock ()->now () - raw_pointcloud_. header .stamp ).nanoseconds ()))
248
266
.count ();
249
267
debug_publisher_ptr_->publish <autoware_internal_debug_msgs::msg::Float64Stamped>(
250
268
" debug/cyclic_time_ms" , cyclic_time_ms);
0 commit comments