-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathslam-navigation.launch
55 lines (47 loc) · 2.67 KB
/
slam-navigation.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
<launch>
<arg name="with_path_finding" default="true" />
<arg name="with_camera" default="true" />
<include if="$(arg with_camera)" file="$(find realsense_tools)/launch/rs_camera.launch"></include>
<!-- Set sim time if not using camera -->
<param name="/use_sim_time" value="true" unless="$(arg with_camera)" />
<param name="/use_sim_time" value="false" if="$(arg with_camera)" />
<node pkg="imu_filter_madgwick" type="imu_filter_node" name="ImuFilter">
<param name="use_mag" type="bool" value="false" />
<param name="publish_tf" type="bool" value="false" />
<param name="world_frame" type="string" value="enu" />
<remap from="/imu/data_raw" to="/camera/imu" />
</node>
<include file="$(find mapping)/launch/rtabmap.launch">
<arg name="args" value="--delete_db_on_start"/>
<arg name="rgb_topic" value="/camera/color/image_raw"/>
<arg name="depth_topic" value="/camera/aligned_depth_to_color/image_raw"/>
<arg name="camera_info_topic" value="/camera/color/camera_info"/>
<arg name="depth_camera_info_topic" value="/camera/depth/camera_info"/>
<arg name="rtabmapviz" value="false"/>
<arg name="rviz" value="true"/>
<arg name="queue_size" value="10" />
<arg name="cfg" value="$(find mapping)/launch/rtabmap/rtabmap.ini"/>
</include>
<include file="$(find robot_localization)/launch/ukf_template.launch" />
<param name="/ukf_se/frequency" value="30" />
<param name="/ukf_se/base_link_frame" value="camera_link" />
<param name="/ukf_se/odom0" value="rtabmap/odom" />
<rosparam param="/ukf_se/odom0_config">[true,true,true,
true,true,true,
true,true,true,
true,true,true,
false,false,false]
</rosparam>
<param name="/ukf_se/odom0_relative" value="true"/>
<param name="/ukf_se/odom0_differential" value="false"/>
<param name="/ukf_se/use_control" value="false"/>
<param name="/ukf_se/imu0" value="/imu/data"/>
<rosparam param="/ukf_se/imu0_config">[false, false, false,
true, true, true,
false, false, false,
true, true, true,
true, true, true]</rosparam>
<param name="/ukf_se/imu0_differential" value="true"/>
<param name="/ukf_se/imu0_relative" value="false"/>
<include if="$(arg with_path_finding)" file="$(find path_finding)/launch/path_finding.launch"></include>
</launch>