-
Notifications
You must be signed in to change notification settings - Fork 40
/
airsim1.launch
52 lines (43 loc) · 2.05 KB
/
airsim1.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>
# Use simulation time for TFs
<param name="use_sim_time" value="true" />
# Bag file
<node name="bag_player" type="play" pkg="rosbag" args="airsim1.bag -s 0 -r 1.0 --clock " />
# Fake odometry. You better use a good odometry estrimator as LOAM
<node pkg="tf" type="static_transform_publisher" name="odom_tf" args="0 0 0 0 0 0 odom drone_1 10" />
# airsim map conf
<arg name="base_frame_id" default="drone_1"/>
<arg name="odom_frame_id" default="odom"/>
<arg name="global_frame_id" default="map"/>
<arg name="initial_x" default="12.2"/>
<arg name="initial_y" default="11.2"/>
<arg name="initial_z" default="6.9"/>
<arg name="initial_a" default="1.5"/>
<arg name="map" default="airsim.bt" />
<arg name="map_path" default="$(find dll)/maps/$(arg map)"/>
# Launch DLL
<node name="dll_node" type="dll_node" pkg="dll" output="screen">
<remap from="/dll_node/initial_pose" to="/initialpose"/>
<remap from="/imu" to="/airsim_node/drone_1/imu/Imu"/>
<param name="in_cloud" value="/airsim_node/drone_1/lidar/Lidar2" />
<param name="base_frame_id" value="$(arg base_frame_id)" />
<param name="odom_frame_id" value="$(arg odom_frame_id)" />
<param name="global_frame_id" value="$(arg global_frame_id)" />
<param name="rate" value="10.0" />
<param name="map_path" value="$(arg map_path)" />
<param name="sensor_dev" value="0.05" />
<param name="publish_point_cloud" value="true" />
<param name="update_min_d" value="0.01" />
<param name="update_min_a" value="0.01" />
<param name="update_min_time" value="0.1" />
<param name="initial_x" value="$(arg initial_x)"/>
<param name="initial_y" value="$(arg initial_y)"/>
<param name="initial_z" value="$(arg initial_z)"/>
<param name="initial_a" value="$(arg initial_a)"/>
<param name="use_imu" value="true" />
<param name="align_method" value="1" /> # 1: DLL, 2: NDT, 3: ICP
</node>
<node name="rviz" type="rviz" pkg="rviz" args="-d $(find dll)/launch/airsim.rviz" output="screen"/>
</launch>