]> defiant.homedns.org Git - wt_open_manipulator.git/commitdiff
added realsense.launch
authorErik Andresen <erik@vontaene.de>
Sat, 18 Jan 2020 17:53:37 +0000 (18:53 +0100)
committerErik Andresen <erik@vontaene.de>
Sat, 18 Jan 2020 17:53:37 +0000 (18:53 +0100)
launch/open_manipulator.launch
launch/realsense.launch [new file with mode: 0644]

index f6ccaf59dabd44fbcd94841159d5e7d6ff65de13..0cca044b718ed7d42d1cb7cfd898626d726521ab 100644 (file)
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <launch>
-       <param name="robot_description" command="$(find xacro)/xacro.py $(find wt_open_manipulator)/urdf/wild_thumper_with_manipulator.urdf.xacro"/>
+       <param name="robot_description" command="$(find xacro)/xacro.py $(find wt_open_manipulator)/urdf/wild_thumper_with_manipulator.urdf.xacro use_nominal_extrinsics:=false"/>
 
        <!-- Load controller configurations from YAML file to parameter server -->
        <rosparam file="$(find wt_open_manipulator)/config/control.yaml" command="load" />
diff --git a/launch/realsense.launch b/launch/realsense.launch
new file mode 100644 (file)
index 0000000..99a696c
--- /dev/null
@@ -0,0 +1,48 @@
+<?xml version="1.0"?>
+
+<!--
+v4l2-ctl -d /dev/video3 \-\-list-formats-ext
+ioctl: VIDIOC_ENUM_FMT
+        Index       : 0
+        Type        : Video Capture
+        Pixel Format: 'YUYV'
+        Name        : YUYV 4:2:2
+                Size: Discrete 424x240
+                        Interval: Discrete 0.017s (60.000 fps)
+                        Interval: Discrete 0.033s (30.000 fps)
+                        Interval: Discrete 0.067s (15.000 fps)
+                        Interval: Discrete 0.167s (6.000 fps)
+                Size: Discrete 640x480
+                        Interval: Discrete 0.033s (30.000 fps)
+                        Interval: Discrete 0.067s (15.000 fps)
+                        Interval: Discrete 0.167s (6.000 fps)
+                Size: Discrete 1280x720
+                        Interval: Discrete 0.167s (6.000 fps)
+-->
+
+<launch>
+       <!--
+       <node pkg="usb_cam" type="usb_cam_node" name="usb_cam" output="screen" required="true">
+               <param name="video_device" value="/dev/video3"/>
+               <param name="pixel_format" value="yuyv"/>
+               <param name="framerate" value="15"/>
+       </node>
+       -->
+       <include file="$(find realsense2_camera)/launch/rs_camera.launch">
+               <arg name="depth_fps"           default="15"/>
+               <arg name="infra_fps"           default="15"/>
+               <arg name="color_fps"           default="15"/>
+               <arg name="enable_fisheye"      default="false"/>
+               <arg name="enable_infra2"       default="false"/>
+               <arg name="enable_gyro"         default="false"/>
+               <arg name="enable_accel"        default="false"/>
+               <arg name="publish_tf"          default="true"/>
+               <arg name="publish_odom_tf"     default="false"/>
+               <arg name="enable_pointcloud"   default="false"/>
+               <!--
+               <arg name="filters"             default="pointcloud"/>
+               -->
+       </include>
+
+       <node pkg="web_video_server" type="web_video_server" name="web_video_server" output="screen"/>
+</launch>