From c452ee309c2d6aa4be12afe6949fbbc6ade4660f Mon Sep 17 00:00:00 2001
From: Hongyu Li
Date: Tue, 29 Mar 2022 14:59:17 -0400
Subject: [PATCH] Made camera topics parameters
---
.../launch/human_state_estimation.launch | 4 +++-
vz_human_state_estimation/scripts/ros_interface.py | 8 ++++++--
2 files changed, 9 insertions(+), 3 deletions(-)
diff --git a/vz_human_state_estimation/launch/human_state_estimation.launch b/vz_human_state_estimation/launch/human_state_estimation.launch
index ef5cdb8..47f270a 100644
--- a/vz_human_state_estimation/launch/human_state_estimation.launch
+++ b/vz_human_state_estimation/launch/human_state_estimation.launch
@@ -1,5 +1,7 @@
-
+
+
+
\ No newline at end of file
diff --git a/vz_human_state_estimation/scripts/ros_interface.py b/vz_human_state_estimation/scripts/ros_interface.py
index 5ad12bd..20bde4d 100755
--- a/vz_human_state_estimation/scripts/ros_interface.py
+++ b/vz_human_state_estimation/scripts/ros_interface.py
@@ -33,9 +33,13 @@ class ROSInterface:
# set up CV Bridge
self.bridge = CvBridge()
+ # Get topic names
+ self.rgbd_topic = rospy.get_param("rgbd_topic")
+ self.thermal_topic = rospy.get_param("thermal_topic")
+
#Image subscribers
- rgbd_sub = message_filters.Subscriber("/D435i/image_raw",Image)
- thermal_sub = message_filters.Subscriber("/flir_3_5_near_realsense_raw",Image)
+ rgbd_sub = message_filters.Subscriber(self.rgbd_topic, Image)
+ thermal_sub = message_filters.Subscriber(self.thermal_topic, Image)
# todo: confirm the slop parameter with Paul Ghanem. 2 secs seems high
ats = message_filters.ApproximateTimeSynchronizer([rgbd_sub,thermal_sub],queue_size=10,slop=2.0)