Skip to content
Snippets Groups Projects
Commit 91b91cc9 authored by EtienneAr's avatar EtienneAr
Browse files

Update launchfiles

parent 248cfcb4
No related branches found
No related tags found
No related merge requests found
<launch>
<arg name="camera_id" default="0" />
<arg name="dataset" default="ycbv"/>
<arg name="allow_tracking" default="false"/>
<arg name="camera_name" default="usb_cam_$(arg camera_id)"/>
<!-- Start camera -->
<include file="$(find ros_cosypose)/launch/cameras_bringup.launch">
<arg name="usbcam_ids" value="$(arg camera_id)"/>
</include>
<node name="$(anon image_proc)" pkg="image_proc" type="image_proc" ns="$(arg camera_name)"/>
<!-- ros_cosypose -->
<node name="$(anon object_pose_estimation.py)" pkg="ros_cosypose" type="object_pose_estimation.py">
<param name="dataset" value="$(arg dataset)"/>
<param name="allow_tracking" value="$(arg allow_tracking)"/>
<param name="camera_name" value="$(arg camera_name)"/>
</node>
<!-- some basic frames -->
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 map world 100" />
<node pkg="tf" type="static_transform_publisher" name="link2_broadcaster" args="1 0 0 0 0 0 1 world $(arg camera_name) 100" />
<!-- RViz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ros_cosypose)/launch/config.rviz"/>
<node name="$(anon rviz_translator.py)" pkg="ros_cosypose" type="rviz_translator.py">
<param name="in_object_topic" value="cosyobject_list"/>
<param name="out_poses_topic" value="cosyobject_poses"/>
<param name="out_marker_topic" value="cosyobject_markers"/>
<param name="models_relative_path" value="bop_datasets/$(arg dataset)/models/"/> <!-- Relative to cosypose local_data directory -->
</node>
</launch>
<launch>
<arg name="camera_id" default="0" />
<arg name="dataset" default="ycbv"/>
<arg name="camera_name" default="usb_cam_$(arg camera_id)"/>
<arg name="allow_tracking" default="false"/>
<!-- Start camera -->
<include file="$(find ros_cosypose)/launch/singleview_service.launch">
<arg name="camera_id" value="$(arg camera_id)"/>
<arg name="dataset" value="$(arg dataset)"/>
<arg name="camera_name" value="$(arg camera_name)"/>
</include>
<!-- call ros_cosypose in loop and publish on topics -->
<node name="$(anon pose_estimation_loop.py)" pkg="ros_cosypose" type="pose_estimation_loop.py">
<param name="camera_name" value="$(arg camera_name)"/>
<param name="allow_tracking" value="$(arg allow_tracking)"/>
</node>
</launch>
<launch>
<arg name="camera_id" default="0" />
<arg name="dataset" default="ycbv"/>
<arg name="camera_name" default="usb_cam_$(arg camera_id)"/>
<arg name="allow_tracking" default="false"/>
<!-- Start camera -->
<include file="$(find ros_cosypose)/launch/singleview_service.launch">
<arg name="camera_id" value="$(arg camera_id)"/>
<arg name="dataset" value="$(arg dataset)"/>
<arg name="camera_name" value="$(arg camera_name)"/>
</include>
<!-- call ros_cosypose in loop and publish on topics -->
<node name="$(anon pose_estimation_loop.py)" pkg="ros_cosypose" type="pose_estimation_loop.py">
<param name="camera_name" value="$(arg camera_name)"/>
<param name="allow_tracking" value="$(arg allow_tracking)"/>
</node>
<!-- some basic frames -->
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 map world 100" />
<node pkg="tf" type="static_transform_publisher" name="link2_broadcaster" args="1 0 0 0 0 0 1 world $(arg camera_name) 100" />
<!-- RViz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ros_cosypose)/launch/config.rviz"/>
<node name="$(anon rviz_translator.py)" pkg="ros_cosypose" type="rviz_translator.py">
<param name="in_object_topic" value="cosyobject_list"/>
<param name="out_poses_topic" value="cosyobject_poses"/>
<param name="out_marker_topic" value="cosyobject_markers"/>
<param name="models_relative_path" value="bop_datasets/$(arg dataset)/models/"/> <!-- Relative to cosypose local_data directory -->
</node>
</launch>
<launch>
<arg name="camera_id" default="0" />
<arg name="dataset" default="ycbv"/>
<arg name="allow_tracking" default="false"/>
<arg name="camera_name" default="usb_cam_$(arg camera_id)"/>
<!-- Start camera -->
......@@ -16,23 +14,4 @@
<node name="$(anon pose_estimation.py)" pkg="ros_cosypose" type="pose_estimation.py">
<param name="dataset" value="$(arg dataset)"/>
</node>
<!-- call ros_cosypose in loop and publish on topics -->
<node name="$(anon pose_estimation_loop.py)" pkg="ros_cosypose" type="pose_estimation_loop.py">
<param name="camera_name" value="$(arg camera_name)"/>
</node>
<!-- some basic frames -->
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="1 0 0 0 0 0 1 map world 100" />
<node pkg="tf" type="static_transform_publisher" name="link2_broadcaster" args="1 0 0 0 0 0 1 world $(arg camera_name) 100" />
<!-- RViz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ros_cosypose)/launch/config.rviz"/>
<node name="$(anon rviz_translator.py)" pkg="ros_cosypose" type="rviz_translator.py">
<param name="in_object_topic" value="cosyobject_list"/>
<param name="out_poses_topic" value="cosyobject_poses"/>
<param name="out_marker_topic" value="cosyobject_markers"/>
<param name="models_relative_path" value="bop_datasets/$(arg dataset)/models/"/> <!-- Relative to cosypose local_data directory -->
</node>
</launch>
......@@ -80,7 +80,6 @@ class PredictionService:
# Predict poses using cosypose
self.predictor([image, ], cameras, pose_estimation_prior=pose_estimation_prior, detector_kwargs=self.detector_kwargs)
pose_predictions = self.predictor.pose_predictions
rospy.logwarn(pose_predictions)
# transform cosypose objects to ros msg
objects_array = CosyObjectArray()
......
......@@ -5,13 +5,14 @@ from ros_cosypose.msg import CosyObjectArray, CosyObject
from ros_cosypose.srv import GetPrediction, GetPredictionResponse
class PoseEstimationLoop:
def __init__(self, camera_name):
def __init__(self, camera_name, allow_tracking):
self._latest_img = None
self.camera_name = camera_name
self._sub = rospy.Subscriber(f'/{self.camera_name}/image_rect_color', Image, self.imgmsg_cb, queue_size=1, buff_size=2**24)
rospy.wait_for_service('pose_estimation')
self._srv = rospy.ServiceProxy('pose_estimation', GetPrediction)
self._pub = rospy.Publisher('cosyobject_list', CosyObjectArray, queue_size=1)
self.allow_tracking = allow_tracking
self.prediction = None
def imgmsg_cb(self, msg):
......@@ -22,7 +23,7 @@ class PoseEstimationLoop:
while not rospy.is_shutdown() :
if self._latest_img != None:
prior = []
if self.prediction != None:
if self.allow_tracking and self.prediction != None:
prior = self.prediction.objects
response = self._srv(cam_info.K, self._latest_img, prior)
self._pub.publish(response.prediction)
......@@ -33,4 +34,5 @@ class PoseEstimationLoop:
if __name__ == '__main__':
rospy.init_node('object_pose_estimation', anonymous=True)
camera_name = rospy.get_param('~camera_name', "usb_cam_0")
PoseEstimationLoop(camera_name).main()
allow_tracking = rospy.get_param('~allow_tracking', "false")
PoseEstimationLoop(camera_name, allow_tracking).main()
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment