forked from carlosmccosta/dynamic_robot_localization
-
Notifications
You must be signed in to change notification settings - Fork 0
/
octo_map.launch
52 lines (51 loc) · 3.49 KB
/
octo_map.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
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="octomap_file" default="" />
<arg name="map_frame_id" default="map" />
<arg name="map_out_topic" default="/map" />
<arg name="cloud_out_topic" default="reference_pointcloud_update" />
<arg name="base_frame_id" default="base_footprint" />
<arg name="sensor_frame_id" default="laser" />
<arg name="override_sensor_z" default="false" />
<arg name="override_sensor_z_value" default="0.0" />
<arg name="cloud_in" default="aligned_pointcloud_outliers" /> <!-- ambient_pointcloud | aligned_pointcloud | aligned_pointcloud_outliers | aligned_pointcloud_inliers -->
<arg name="occupancy_grid_in" default="initial_2d_map" />
<arg name="resolution" default="0.025" />
<arg name="minimum_amount_of_time_between_ros_msg_publishing" default="5.0" />
<arg name="minimum_number_of_integrations_before_ros_msg_publishing" default="10" />
<arg name="nodes_respawn" default="true" />
<node pkg="octomap_server" type="octomap_server_node" name="$(anon octomap_server)" args="$(arg octomap_file)" output="screen" respawn="$(arg nodes_respawn)" clear_params="true" >
<param name="frame_id" type="str" value="$(arg map_frame_id)" />
<param name="resolution" type="double" value="$(arg resolution)" />
<param name="base_frame_id" type="str" value="$(arg base_frame_id" />
<param name="sensor_frame_id" type="str" value="$(arg sensor_frame_id)" />
<param name="override_sensor_z" type="bool" value="$(arg override_sensor_z)" />
<param name="override_sensor_z_value" type="double" value="$(arg override_sensor_z_value)" />
<param name="height_map" type="bool" value="true" />
<param name="sensor_model/max_range" type="double" value="200" />
<param name="sensor_model/hit" type="double" value="0.6" />
<param name="sensor_model/miss" type="double" value="0.45" /> <!-- 0.5 for static environments (will not decrease the occupied probability when ray tracing) -->
<param name="sensor_model/min" type="double" value="0.07" />
<param name="sensor_model/max" type="double" value="0.99" />
<param name="sensor_model/occupancy_treshold" type="double" value="0.7" />
<param name="latch" type="bool" value="true" />
<param name="filter_ground" type="bool" value="false" />
<param name="filter_speckles" type="bool" value="true" />
<param name="ground_filter/distance" type="double" value="0.02" />
<param name="ground_filter/angle" type="double" value="0.15" />
<param name="ground_filter/plane_distance" type="double" value="0.05" />
<param name="pointcloud_min_z" type="double" value="-1.0" />
<param name="pointcloud_max_z" type="double" value="2.5" />
<param name="occupancy_min_z" type="double" value="-1.0" />
<param name="occupancy_max_z" type="double" value="2.5" />
<param name="occupancy_grid_2d_min_z" type="double" value="-1.0" />
<param name="occupancy_grid_2d_max_z" type="double" value="2.5" />
<param name="occupancy_grid_2d_initialized_as_free" type="bool" value="false" />
<param name="occupancy_grid_in" type="str" value="$(arg occupancy_grid_in)" />
<param name="minimum_amount_of_time_between_ros_msg_publishing" type="double" value="$(arg minimum_amount_of_time_between_ros_msg_publishing)" />
<param name="minimum_number_of_integrations_before_ros_msg_publishing" type="double" value="$(arg minimum_number_of_integrations_before_ros_msg_publishing)" />
<remap from="cloud_in" to="$(arg cloud_in)" />
<remap from="projected_map" to="$(arg map_out_topic)" />
<remap from="octomap_point_cloud_centers" to="$(arg cloud_out_topic)" />
</node>
</launch>