-
Notifications
You must be signed in to change notification settings - Fork 151
/
kimera_vio_ros_euroc.launch
73 lines (61 loc) · 3.08 KB
/
kimera_vio_ros_euroc.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
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
<launch>
<arg name="dataset_name" default="Euroc"/>
<arg name="verbosity" default="0" />
<arg name="do_coarse_temporal_sync" default="false"/>
<arg name="do_fine_temporal_sync" default="false"/>
<!-- Set online to true if you use rosbag play or sensor stream -->
<arg name="online" default="false" />
<!-- Set use_sim_time to true if you use rosbag with clock argument -->
<param name="use_sim_time" value="true"/>
<!-- Set log_output to true and KimeraVIO will log output of all modules to
the log_output_path location. -->
<arg name="log_output" default="false"/>
<arg name="log_output_path"
default="$(find kimera_vio_ros)/output_logs/$(arg dataset_name)"
if="$(arg log_output)"/>
<!-- Set to true and specify gt_topic if you want to log ground-truth data -->
<arg name="log_gt_data" default="false"/>
<arg name="gt_topic" default=""/>
<rosparam param="gt_gyro_bias"> [-0.002229, 0.0207, 0.07635] </rosparam>
<rosparam param="gt_accel_bias"> [-0.012492, 0.547666, 0.069073] </rosparam>
<arg name="use_lcd" default="false"/>
<arg name="use_external_odom" default="false"/>
<arg name="visualize" default="true"/>
<!-- Change rosbag path if online argument is false -->
<arg name="rosbag_path" default=""
unless="$(arg online)"/>
<!-- Frame IDs -->
<arg name="base_link_frame_id" value="base_link"/>
<arg name="left_cam_frame_id" value="cam0"/>
<arg name="right_cam_frame_id" value="cam1"/>
<arg name="left_cam_topic" default="/cam0/image_raw"/>
<arg name="right_cam_topic" default="/cam1/image_raw"/>
<arg name="imu_topic" default="/imu0"/>
<arg name="external_odom_topic" default=""/>
<!-- Perform stereo dense reconstruction? -->
<arg name="run_stereo_dense" default="false"/>
<group ns="stereo_gray" if="$(arg run_stereo_dense)">
<!-- StereoSGBM -->
<node name="dense_stereo" pkg="image_undistort" type="dense_stereo_node" >
<param name="input_camera_info_from_ros_params" value="true"/>
<param name="first_camera_namespace" value="cam0"/>
<param name="second_camera_namespace" value="cam1"/>
<param name="first_output_frame" value="cam0"/>
<param name="second_output_frame" value="cam1"/>
<param name="depth/use_sgbm" value="true"/>
<param name="depth/do_median_blur" value="false"/>
<param name="depth/use_mode_HH" value="true"/>
<param name="scale" value="1.0"/>
<param name="process_every_nth_frame" value="1"/>
<param name="publish_tf" value="false"/>
<rosparam file="$(find kimera_vio_ros)/cfg/calib/euroc_camchain.yaml"/>
<remap from="raw/first/image" to="/cam0/image_raw"/>
<remap from="raw/second/image" to="/cam1/image_raw"/>
<remap from="raw/first/camera_info" to="/cam0/camera_info"/>
<remap from="raw/second/camera_info" to="/cam1/camera_info"/>
</node>
</group>
<!-- Launch actual pipeline -->
<include file="$(find kimera_vio_ros)/launch/kimera_vio_ros.launch"
pass_all_args="true"/>
</launch>