Skip to content

Commit

Permalink
chore: fix the output order of the debug mode
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Oct 22, 2024
1 parent fcdb989 commit 460b467
Showing 1 changed file with 13 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -73,13 +73,8 @@ void CloudCollector::process_pointcloud(

void CloudCollector::concatenate_callback()
{
// All pointclouds are received or the timer has timed out, cancel the timer and concatenate the
// pointclouds in the collector.
auto time_until_trigger = timer_->time_until_trigger();
timer_->cancel();

auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_);
if (debug_mode_) {
auto time_until_trigger = timer_->time_until_trigger();
std::stringstream log_stream;
log_stream << std::fixed << std::setprecision(6);
log_stream << "Collector's concatenate callback time: "
Expand All @@ -91,18 +86,24 @@ void CloudCollector::concatenate_callback()
log_stream << "Time until trigger: " << (time_until_trigger.count() / 1e9) << " seconds\n";

log_stream << "Pointclouds: [";
for (auto it = concatenated_cloud_result.topic_to_original_stamp_map.begin();
it != concatenated_cloud_result.topic_to_original_stamp_map.end(); ++it) {
log_stream << "[" << it->first << ", " << it->second << "]";
if (std::next(it) != concatenated_cloud_result.topic_to_original_stamp_map.end()) {
log_stream << ", ";
}
std::string separator = "";
for (const auto & [topic, cloud] : topic_to_cloud_map_) {
log_stream << separator;
log_stream << "[" << topic << ", " << rclcpp::Time(cloud->header.stamp).seconds() << "]";
separator = ", ";
}

log_stream << "]\n";

RCLCPP_INFO(ros2_parent_node_->get_logger(), "%s", log_stream.str().c_str());
}

// All pointclouds are received or the timer has timed out, cancel the timer and concatenate the
// pointclouds in the collector.
timer_->cancel();

auto concatenated_cloud_result = concatenate_pointclouds(topic_to_cloud_map_);

ros2_parent_node_->publish_clouds(
std::move(concatenated_cloud_result), reference_timestamp_min_, reference_timestamp_max_);

Expand Down

0 comments on commit 460b467

Please sign in to comment.