From 555bce4e2862b5964a20f7fcf332d367d5291fb9 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Wed, 20 Dec 2023 15:07:45 +0300 Subject: [PATCH] succesfully spawn both predicted objs and pointcloud --- tools/reaction_analyzer/src/reaction_analyzer_node.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp index ae283c9b4330c..a28346e80ec4e 100644 --- a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp +++ b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp @@ -93,7 +93,9 @@ void ReactionAnalyzerNode::onTimer() node_params_.spawn_distance_threshold; if (!spawn) { // send empty + pcl::PointCloud pcl_empty; PointCloud2 empty_pointcloud; + pcl::toROSMsg(pcl_empty, empty_pointcloud); empty_pointcloud.header.frame_id = "base_link"; PredictedObjects empty_predicted_objects; empty_predicted_objects.header.frame_id = "map";