Skip to content
Snippets Groups Projects
Commit 7ef44fd3 authored by EtienneAr's avatar EtienneAr
Browse files

Move camera bringup arguments to singleview_loop.launch

parent 8055e6f4
No related branches found
No related tags found
No related merge requests found
......@@ -10,19 +10,24 @@
<arg name="allow_tracking" default="false"/>
<!-- Start service and camera -->
<!-- Start camera -->
<group if="$(arg bringup_camera)">
<include file="$(find ros_cosypose)/launch/cameras_bringup.launch">
<arg name="usbcam_ids" value="$(arg camera_id)"/>
</include>
<!-- Rectify image -->
<node name="$(anon image_proc)" pkg="image_proc" type="image_proc" ns="$(arg camera_name)"/>
</group>
<!-- Start service -->
<include file="$(find ros_cosypose)/launch/singleview_service.launch">
<arg name="dataset" value="$(arg dataset)"/>
<arg name="detection_threshold" value="$(arg detection_threshold)"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="debug_models" value="$(arg debug_models)"/>
<arg name="camera_id" value="$(arg camera_id)"/>
<arg name="camera_name" value="$(arg camera_name)"/>
<arg name="bringup_camera" value="$(arg bringup_camera)"/>
</include>
<!-- call ros_cosypose in loop and publish on topics -->
<!-- call service in loop and publish on topics -->
<node name="pose_estimation_loop" pkg="ros_cosypose" type="pose_estimation_loop.py">
<param name="camera_name" value="$(arg camera_name)"/>
<param name="allow_tracking" value="$(arg allow_tracking)"/>
......
......@@ -4,20 +4,6 @@
<arg name="debug" default="false"/>
<arg name="debug_models" default="bop_datasets/$(arg dataset)/models/"/> <!-- Relative path from cosypose local_data directory -->
<arg name="camera_id" default="0" />
<arg name="camera_name" default="usb_cam_$(arg camera_id)"/>
<arg name="bringup_camera" default="true"/>
<!-- Start camera -->
<group if="$(arg bringup_camera)">
<include file="$(find ros_cosypose)/launch/cameras_bringup.launch">
<arg name="usbcam_ids" value="$(arg camera_id)"/>
</include>
<!-- Rectify image -->
<node name="$(anon image_proc)" pkg="image_proc" type="image_proc" ns="$(arg camera_name)"/>
</group>
<!-- ros_cosypose service -->
<node name="pose_estimation" pkg="ros_cosypose" type="pose_estimation.py">
<param name="dataset" value="$(arg dataset)"/>
......
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