Browse Source

Made camera topics parameters

pull/65/head
Hongyu Li 2 years ago
parent
commit
c452ee309c
2 changed files with 9 additions and 3 deletions
  1. +3
    -1
      vz_human_state_estimation/launch/human_state_estimation.launch
  2. +6
    -2
      vz_human_state_estimation/scripts/ros_interface.py

+ 3
- 1
vz_human_state_estimation/launch/human_state_estimation.launch View File

@ -1,5 +1,7 @@
<launch>
<node pkg="vz_human_state_estimation" type="ros_interface.py" name="human_state_estimation" />
<!-- flip images before passing onto human state estimation module -->
<param name="flip_images_human_state_est" type="bool" value="true" />
<param name="flip_images_human_state_est" type="bool" value="true" />
<param name="rgbd_topic" type="string" value="/D435i/image_raw" />
<param name="thermal_topic" type="string" value="/Lepton/image_raw" />
</launch>

+ 6
- 2
vz_human_state_estimation/scripts/ros_interface.py View File

@ -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)

Loading…
Cancel
Save