-
Notifications
You must be signed in to change notification settings - Fork 358
/
kitti_dataset.launch
48 lines (42 loc) · 2.48 KB
/
kitti_dataset.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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
<?xml version="1.0" encoding="ISO-8859-15"?>
<launch>
<arg name="play_bag" default="true" />
<!-- <arg name="bag_file" default="/path/to/drive35.bag"/> -->
<arg name="process_every_nth_frame" default="1" />
<arg name="voxel_size" default="0.25" />
<arg name="scale" default="0.25" />
<!-- whether to use laser (true) or stereo (false) for the map. -->
<arg name="use_laser" default="true" />
<!-- These datasets can be created with the KITTI raw datasets: http://www.cvlibs.net/datasets/kitti/raw_data.php and kitti_to_rosbag: https://github.com/ethz-asl/kitti_to_rosbag -->
<node name="player" pkg="rosbag" type="play" output="screen" args=" -r 0.2 --clock $(arg bag_file)" if="$(arg play_bag)"/>
<!-- Run stereo_dense_reconstruction_node-->
<node ns="stereo_gray" name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc" clear_params="true" output="screen">
<remap from="left/image_raw" to="/cam02/image_raw" />
<remap from="left/camera_info" to="/cam02/camera_info" />
<remap from="right/image_raw" to="/cam03/image_raw" />
<remap from="right/camera_info" to="/cam03/camera_info" />
<param name="approximate_sync" value="true" />
<param name="approximate_sync" value="true" />
<rosparam file="$(find voxblox_ros)/cfg/stereo/kitti_stereo_jager.yaml"/>
</node>
<node name="voxblox_node" pkg="voxblox_ros" type="tsdf_server" output="screen" args="-alsologtostderr" clear_params="true">
<remap from="pointcloud" to="/velodyne_points" if="$(arg use_laser)" />
<remap from="pointcloud" to="/stereo_gray/points2" unless="$(arg use_laser)" />
<param name="tsdf_voxel_size" value="$(arg voxel_size)" />
<param name="tsdf_voxels_per_side" value="16" />
<param name="voxel_carving_enabled" value="true" />
<param name="color_mode" value="color" unless="$(arg use_laser)" />
<param name="color_mode" value="normals" if="$(arg use_laser)" />
<param name="use_tf_transforms" value="true" />
<param name="enable_icp" value="true" />
<param name="icp_iterations" value="10" />
<param name="verbose" value="true" />
<param name="update_mesh_every_n_sec" value="0.2" />
<param name="max_ray_length_m" value="25.0" />
<param name="min_time_between_msgs_sec" value="0.2" />
<param name="slice_level" value="1.0" />
<param name="method" value="fast" />
<param name="use_const_weight" value="true" />
<param name="mesh_filename" value="$(find voxblox_ros)/mesh_results/$(anon kitti).ply" />
</node>
</launch>