From 16d1a9447e7cbdbd2358e5d204f871cfed97f23a Mon Sep 17 00:00:00 2001 From: Johannes Mey <johannes.mey@tu-dresden.de> Date: Wed, 13 Jul 2022 16:00:27 +0200 Subject: [PATCH] restructure launch files --- config/settings.yaml | 2 +- launch/object_locator.launch | 27 +--------------- .../robot-cell_ceti-table-1-emptyworld.launch | 21 ++++++++++++ launch/tag_detection.launch | 32 +++++++++++++++++++ 4 files changed, 55 insertions(+), 27 deletions(-) create mode 100644 launch/robot-cell_ceti-table-1-emptyworld.launch create mode 100644 launch/tag_detection.launch diff --git a/config/settings.yaml b/config/settings.yaml index c72f7f1..518e071 100644 --- a/config/settings.yaml +++ b/config/settings.yaml @@ -9,5 +9,5 @@ tag_refine_edges: 1 # default: 1 tag_debug: 1 # default: 0 max_hamming_dist: 2 # default: 2 (Tunable parameter with 2 being a good choice - values >=3 consume large amounts of memory. Choose the largest value possible.) # Other parameters -publish_tf: true # default: false +publish_tf: false # default: false transport_hint: "raw" # default: raw, see http://wiki.ros.org/image_transport#Known_Transport_Packages for options diff --git a/launch/object_locator.launch b/launch/object_locator.launch index 6ef056b..ccf1725 100644 --- a/launch/object_locator.launch +++ b/launch/object_locator.launch @@ -1,28 +1,3 @@ <launch> - <arg name="launch_prefix" default="" /> <!-- set to value="gdbserver localhost:10000" for remote debugging --> - <arg name="node_namespace" default="apriltag_ros_continuous_node" /> - <arg name="camera_name" default="/usb_cam" /> - <arg name="image_topic" default="image_rect" /> - - <!-- Set parameters --> - <rosparam command="load" file="$(find ccf_immersive_sorting)/config/settings.yaml" ns="$(arg node_namespace)" /> - <rosparam command="load" file="$(find ccf_immersive_sorting)/config/tags.yaml" ns="$(arg node_namespace)" /> - - <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="log"> - <param name="video_device" value="/dev/video2" /> - <param name="image_width" value="2560" /> - <param name="image_height" value="1440" /> - <param name="autofocus" value="0" /> - </node> - - - <node name="image_proc" pkg="image_proc" type="image_proc" ns="usb_cam"/> - - <node pkg="apriltag_ros" type="apriltag_ros_continuous_node" name="$(arg node_namespace)" clear_params="true" output="screen" launch-prefix="$(arg launch_prefix)" > - <!-- Remap topics from those used in code to those on the ROS network --> - <remap from="image_rect" to="$(arg camera_name)/$(arg image_topic)" /> - <remap from="camera_info" to="$(arg camera_name)/camera_info" /> - - <param name="publish_tag_detections_image" type="bool" value="true" /> <!-- default: false --> - </node> + <node pkg="ccf_immersive_sorting" type="object_locator" name="object_locator"/> </launch> diff --git a/launch/robot-cell_ceti-table-1-emptyworld.launch b/launch/robot-cell_ceti-table-1-emptyworld.launch new file mode 100644 index 0000000..4d855d2 --- /dev/null +++ b/launch/robot-cell_ceti-table-1-emptyworld.launch @@ -0,0 +1,21 @@ +<launch> + + <!-- MQTT server for communication with client cells --> + <arg name="mqtt_server" default="tcp://localhost:1883" doc="address of the mqtt server for the connection to the controller"/> + + <!-- robot IP used by the robot controller --> + <arg name="robot_ip" default="172.31.1.13" doc="ip address if the robot"/> + + <include file="$(find ccf)/launch/robot_setup.launch"> + <arg name="robot_ip" value="$(arg robot_ip)"/> + <arg name="load_gripper" value="true"/> + </include> + + <node pkg="ccf_immersive_sorting" type="moveit_sorting_controller" name="ceti_cell_empty" output="screen"> + <param name="arm" type="string" value="arm"/> + <param name="scene_observer" type="string" value="object_locator/scene/update"/> + <param name="mqtt_server" type="yaml" value="$(arg mqtt_server)"/> + <param name="scene" type="string" value="$(find ccf_immersive_sorting)/config/config_scene_ceti-table-1-empty.json"/> + </node> + +</launch> diff --git a/launch/tag_detection.launch b/launch/tag_detection.launch new file mode 100644 index 0000000..c573ef9 --- /dev/null +++ b/launch/tag_detection.launch @@ -0,0 +1,32 @@ +<launch> + <arg name="launch_prefix" default="" /> <!-- set to value="gdbserver localhost:10000" for remote debugging --> + <arg name="node_namespace" default="apriltag_ros_continuous_node" /> + <arg name="camera_name" default="/usb_cam" /> + <arg name="image_topic" default="image_rect" /> + + <!-- Set parameters --> + <rosparam command="load" file="$(find ccf_immersive_sorting)/config/settings.yaml" ns="$(arg node_namespace)" /> + <rosparam command="load" file="$(find ccf_immersive_sorting)/config/tags.yaml" ns="$(arg node_namespace)" /> + + <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="log"> + <param name="video_device" value="/dev/video2" /> + <param name="image_width" value="2560" /> + <param name="image_height" value="1440" /> + <param name="autofocus" value="1" /> + <param name="pixel_format" value="mjpeg"/> + <param name="framerate" value="4"/> + </node> + + + <node name="image_proc" pkg="image_proc" type="image_proc" ns="usb_cam"/> + + <node pkg="apriltag_ros" type="apriltag_ros_continuous_node" name="$(arg node_namespace)" clear_params="true" output="screen" launch-prefix="$(arg launch_prefix)" > + <!-- Remap topics from those used in code to those on the ROS network --> + <remap from="image_rect" to="$(arg camera_name)/$(arg image_topic)" /> + <remap from="camera_info" to="$(arg camera_name)/camera_info" /> + + <param name="publish_tag_detections_image" type="bool" value="true" /> <!-- default: false --> + </node> + +<!-- <node pkg="ccf_immersive_sorting" type="object_locator" name="object_locator"/>--> +</launch> -- GitLab