Skip to content

Commit 71a1f1b

Browse files
KYabuuchiautoware
authored and
autoware
committedMay 13, 2024
perf(pointcloud_preprocessor): prevent excessive log and speed up a bit (autowarefoundation#6843)
* provide only one warning Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * associate only one time Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * Revert "associate only one time" This reverts commit 984d028. * remove redundant for loop and rclcpp::Time instantiation Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> --------- Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>
1 parent 1f6b87d commit 71a1f1b

File tree

1 file changed

+25
-15
lines changed

1 file changed

+25
-15
lines changed
 

‎sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+25-15
Original file line numberDiff line numberDiff line change
@@ -242,6 +242,16 @@ bool DistortionCorrectorComponent::undistortPointCloud(
242242
// For performance, avoid transform computation if unnecessary
243243
bool need_transform = points.header.frame_id != base_link_frame_;
244244

245+
// For performance, do not instantiate `rclcpp::Time` inside of the for-loop
246+
double imu_stamp{0.0};
247+
if (use_imu_ && !angular_velocity_queue_.empty()) {
248+
imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds();
249+
}
250+
251+
// If there is a point that cannot be associated, record it to issue a warning
252+
bool twist_time_stamp_is_too_late = false;
253+
bool imu_time_stamp_is_too_late = false;
254+
245255
for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_time_stamp) {
246256
while (twist_it != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) {
247257
++twist_it;
@@ -252,32 +262,19 @@ bool DistortionCorrectorComponent::undistortPointCloud(
252262
float w{static_cast<float>(twist_it->twist.angular.z)};
253263

254264
if (std::abs(*it_time_stamp - twist_stamp) > 0.1) {
255-
RCLCPP_WARN_STREAM_THROTTLE(
256-
get_logger(), *get_clock(), 10000 /* ms */,
257-
"twist time_stamp is too late. Could not interpolate.");
265+
twist_time_stamp_is_too_late = true;
258266
v = 0.0f;
259267
w = 0.0f;
260268
}
261269

262270
if (use_imu_ && !angular_velocity_queue_.empty()) {
263-
// For performance, do not instantiate `rclcpp::Time` inside of the for-loop
264-
double imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds();
265-
266-
for (;
267-
(imu_it != std::end(angular_velocity_queue_) - 1 &&
268-
*it_time_stamp > rclcpp::Time(imu_it->header.stamp).seconds());
269-
++imu_it) {
270-
}
271-
272271
while (imu_it != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) {
273272
++imu_it;
274273
imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds();
275274
}
276275

277276
if (std::abs(*it_time_stamp - imu_stamp) > 0.1) {
278-
RCLCPP_WARN_STREAM_THROTTLE(
279-
get_logger(), *get_clock(), 10000 /* ms */,
280-
"imu time_stamp is too late. Could not interpolate.");
277+
imu_time_stamp_is_too_late = true;
281278
} else {
282279
w = static_cast<float>(imu_it->vector.z);
283280
}
@@ -314,6 +311,19 @@ bool DistortionCorrectorComponent::undistortPointCloud(
314311

315312
prev_time_stamp_sec = *it_time_stamp;
316313
}
314+
315+
if (twist_time_stamp_is_too_late) {
316+
RCLCPP_WARN_STREAM_THROTTLE(
317+
get_logger(), *get_clock(), 10000 /* ms */,
318+
"twist time_stamp is too late. Could not interpolate.");
319+
}
320+
321+
if (imu_time_stamp_is_too_late) {
322+
RCLCPP_WARN_STREAM_THROTTLE(
323+
get_logger(), *get_clock(), 10000 /* ms */,
324+
"imu time_stamp is too late. Could not interpolate.");
325+
}
326+
317327
return true;
318328
}
319329

0 commit comments

Comments
 (0)
Failed to load comments.