forked from aschulz90/gunther
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathar_pose_single.launch
29 lines (26 loc) · 1.51 KB
/
ar_pose_single.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
<launch>
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find ar_pose)/launch/live_single.vcg"/>
<node pkg="tf" type="static_transform_publisher" name="world_to_cam"
args="0 0 0.5 -1.57 0 -1.57 world usb_cam 10" />
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" respawn="false" output="log">
<param name="video_device" type="string" value="/dev/video0"/>
<param name="camera_frame_id" type="string" value="usb_cam"/>
<param name="io_method" type="string" value="mmap"/>
<param name="image_width" type="int" value="640"/>
<param name="image_height" type="int" value="480"/>
<param name="pixel_format" type="string" value="yuyv"/>
<rosparam param="D">[0.144078, -0.601696, -0.001497, 0.001406, 0.0]</rosparam>
<rosparam param="K">[661.643138, 0.0, 332.01896, 0.0, 664.293114, 251.657219, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="R">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="P">[660.756803, 0.0, 333.022615, 0.0, 0.0, 668.703254, 250.807703, 0.0, 0.0, 0.0, 1.0, 0.0]</rosparam>
</node>
<node name="ar_pose" pkg="ar_pose" type="ar_single" respawn="false" output="screen">
<param name="marker_pattern" type="string" value="$(find ar_pose)/data/hiro.pat"/>
<param name="marker_width" type="double" value="210.0"/>
<param name="marker_center_x" type="double" value="0.0"/>
<param name="marker_center_y" type="double" value="0.0"/>
<param name="threshold" type="int" value="100"/>
<param name="use_history" type="bool" value="true"/>
</node>
</launch>