-
Notifications
You must be signed in to change notification settings - Fork 98
/
mapping_server_relays.launch
67 lines (65 loc) · 2.12 KB
/
mapping_server_relays.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
<?xml version="1.0"?>
<launch>
<arg name="name"/>
<param name="use_sim_time" value="true"/>
<node pkg="subt_ros" type="cloud_downsampler" name="cloud_downsampler" output="screen"/>
<node
pkg="topic_tools"
type="throttle"
name="mapping_server_cloud_throttle"
args="messages /cloud 0.1 /cloud_throttled"
/>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_mapping_server_cloud"
args="/model/$(arg name)/cloud@sensor_msgs/PointCloud2]ignition.msgs.PointCloudPacked">
<remap from="/model/$(arg name)/cloud" to="/cloud_throttled_downsampled"/>
</node>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_mapping_server_cloud_size"
args="/model/$(arg name)/cloud_size@std_msgs/Int32]ignition.msgs.Int32">
<remap from="/model/$(arg name)/cloud_size" to="/cloud_throttled_size"/>
</node>
<node
pkg="topic_tools"
type="throttle"
name="mapping_server_grid_throttle"
args="messages /grid 0.1 /grid_throttled"
/>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_mapping_server_grid"
args="/model/$(arg name)/grid@nav_msgs/OccupancyGrid]ignition.msgs.OccupancyGrid">
<remap from="/model/$(arg name)/grid" to="/grid_throttled"/>
</node>
<node
pkg="topic_tools"
type="throttle"
name="mapping_server_poses_throttle"
args="messages /poses 1.0 /poses_throttled"
/>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_mapping_server_poses"
args="/model/$(arg name)/poses@geometry_msgs/PoseArray]ignition.msgs.Pose_V">
<remap from="/model/$(arg name)/poses" to="/poses_throttled"/>
</node>
<node
pkg="topic_tools"
type="throttle"
name="mapping_server_markers_throttle"
args="messages /markers 1.0 /markers_throttled"
/>
<node
pkg="ros_ign_bridge"
type="parameter_bridge"
name="ros_ign_bridge_mapping_server_markers"
args="/model/$(arg name)/markers@visualization_msgs/MarkerArray]ignition.msgs.Marker_V">
<remap from="/model/$(arg name)/markers" to="/markers_throttled"/>
</node>
</launch>