-
Notifications
You must be signed in to change notification settings - Fork 137
/
Copy pathkitti.launch
52 lines (40 loc) · 2.49 KB
/
kitti.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
<launch>
<!-- Set use_sim_time true for datasets-->
<param name="use_sim_time" value="true" />
<!-- static_transform_publisher x y z yaw pitch roll frame_id child_frame_id -->
<!-- This transform was used set only to test if everything works
when using something different than the camera as a reference frame.
If enabled, take care to also fix the transform below. -->
<!--node pkg="tf2_ros" type="static_transform_publisher" name="camera_broadcaster" args="1 0 0.5 -1.57 0 -1.57 base_link left_camera" /-->
<!-- 'start' frame is the starting pose of the camera
When 'base_link' is set as the reference frame,
take care to set this transformation to the same as the previous one -->
<node pkg="tf2_ros" type="static_transform_publisher" name="start_broadcaster" args="0 0 0 0 0 0 start map" />
<!-- S-PTAM pose path publisher. Used for visualization. -->
<node pkg="ros_utils" type="pose_to_path" name="sptam_path">
<remap from="pose" to="sptam/robot/pose" />
<remap from="path" to="sptam/robot/path" />
</node>
<!-- Nodelet Manager -->
<!--<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen" clear_params="true"/>-->
<!-- Choose between Nodelet and Node S-PTAM -->
<node pkg="sptam" type="sptam_node" name="sptam" output="screen" >
<!-- <node pkg="nodelet" type="nodelet" name="sptam" args="load sptam/sptam_nodelet nodelet_manager" output="screen" clear_params="true" >-->
<!-- Read S-PTAM parameters file -->
<rosparam command="load" file="$(find sptam)/configurationFiles/kitti.yaml" />
<param name="LoopDetectorVocabulary" value="$(find sptam)/bow_voc/DBoW2/brief_mit_malaga_vocabulary.yml.gz" />
<param name="use_prediction" value="false" />
<param name="approximate_sync" value="false" />
<param name="publish_transform" value="true" />
<param name="publish_on_fail" value="true" />
<!--param name="prediction_frame" value="odom" /-->
<param name="base_frame" value="left_camera" />
<param name="camera_frame" value="left_camera" />
<!--param name="map_frame" value="map" /-->
<param name="reference_frame" value="left_camera" />
<remap from="/stereo/left/image_rect" to="/kitti_stereo/left/image_rect" />
<remap from="/stereo/right/image_rect" to="/kitti_stereo/right/image_rect" />
<remap from="/stereo/left/camera_info" to="/kitti_stereo/left/camera_info" />
<remap from="/stereo/right/camera_info" to="/kitti_stereo/right/camera_info" />
</node>
</launch>