-
Notifications
You must be signed in to change notification settings - Fork 22
/
example.launch
74 lines (68 loc) · 3.41 KB
/
example.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
74
<?xml version="1.0" ?>
<launch>
<param name="/use_sim_time" value="true"/>
<arg name="bag_root" value="$(find cslibs_mapping)/bag"/>
<arg name="bag_file" value="example.bag" />
<arg name="bag_args" value="--clock --rate 1.0 -k --pause -q" />
<group ns="cslibs_mapping">
<param name="node_rate" value="0.0" />
<!-- data providers -->
<group ns="laser">
<param name="class" value="cslibs_plugins_data::LaserProvider"/>
<param name="base_class" value="cslibs_plugins_data::DataProvider"/>
<param name="topic" value="/scan/front/filtered"/>
<param name="queue_size" value="10"/>
<param name="rate" value="0.0"/>
</group>
<group ns="velodyne">
<param name="class" value="cslibs_plugins_data::Pointcloud3dProvider"/>
<param name="base_class" value="cslibs_plugins_data::DataProvider"/>
<param name="topic" value="/velodyne_points"/>
<param name="queue_size" value="10"/>
<param name="rate" value="0.0"/>
</group>
<!-- mappers -->
<group ns="ondt_2d">
<param name="class" value="cslibs_mapping::mapper::OccupancyNDTGridMapper2D"/>
<param name="base_class" value="cslibs_mapping::mapper::Mapper"/>
<rosparam param="data_providers">
["laser"]
</rosparam>
<rosparam param="map_publishers">
["ondt_2d_map"]
</rosparam>
<param name="map_frame" value="/odom"/>
<param name="resolution" value="1.0"/>
</group>
<group ns="ondt_3d">
<param name="class" value="cslibs_mapping::mapper::OccupancyNDTGridMapper3D"/>
<param name="base_class" value="cslibs_mapping::mapper::Mapper"/>
<rosparam param="data_providers">
["velodyne"]
</rosparam>
<rosparam param="map_publishers">
["ondt_3d_pointcloud"]
</rosparam>
<param name="map_frame" value="/odom"/>
<param name="resolution" value="1.0"/>
</group>
<!-- publishers -->
<group ns="ondt_2d_map">
<param name="class" value="cslibs_mapping::publisher::OccupancyGridPublisher"/>
<param name="base_class" value="cslibs_mapping::publisher::Publisher"/>
<param name="rate" value="10.0"/>
<param name="topic" value="/cslibs_mapping/ondt_2d"/>
<param name="occupancy" value="true"/>
</group>
<group ns="ondt_3d_pointcloud">
<param name="class" value="cslibs_mapping::publisher::PointcloudPublisher"/>
<param name="base_class" value="cslibs_mapping::publisher::Publisher"/>
<param name="rate" value="10.0"/>
<param name="topic" value="/cslibs_mapping/ondt_3d"/>
<param name="occupancy_ndt" value="true"/>
</group>
</group>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find cslibs_mapping)/config/example.rviz" required="true"/>
<node pkg="rosbag" type="play" name="rosbag" args="$(arg bag_args) $(arg bag_root)/$(arg bag_file)" required="true" output="screen"/>
<node name="cslibs_mapping" pkg="cslibs_mapping" type="cslibs_mapping_node" output="screen" required="true" clear_params="true"/>
</launch>