-
Notifications
You must be signed in to change notification settings - Fork 22
/
demo.launch
25 lines (20 loc) · 965 Bytes
/
demo.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
<launch>
<node name="image_sim_node" pkg="yak_ros" type="yak_ros_image_simulator">
<param name="base_frame" value="world"/>
<param name="mesh" value="$(find yak_ros)/demo/bun_on_table.ply"/>
<param name="orbit_speed" value="1.0"/>
<param name="framerate" value="30"/>
</node>
<node name="tsdf_node" pkg="yak_ros" type="yak_ros_node">
<remap from="~input_depth_image" to="/image"/>
<param name="tsdf_frame" value="tsdf_origin"/>
<rosparam param="camera_matrix">[550.0, 0.0, 320.0, 0.0, 550.0, 240.0, 0.0, 0.0, 1.0]</rosparam>
<param name="cols" value="640"/>
<param name="rows" value="480"/>
<param name="volume_resolution" value="0.001"/>
<param name="volume_x" value="640"/>
<param name="volume_y" value="640"/>
<param name="volume_z" value="192"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="-0.3 -0.3 -0.01 0 0 0 1 world tsdf_origin 100" />
</launch>