-
Notifications
You must be signed in to change notification settings - Fork 275
/
OctomapServer.cfg
executable file
·27 lines (23 loc) · 2.18 KB
/
OctomapServer.cfg
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
#!/usr/bin/env python
PACKAGE = "octomap_server"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("compress_map", bool_t, 0, "Compresses the map losslessly", True)
gen.add("incremental_2D_projection", bool_t, 0, "Incremental 2D projection", False)
gen.add("filter_speckles", bool_t, 0, "Filter speckle nodes (with no neighbors)", False)
gen.add("max_depth", int_t, 0, "Maximum depth when traversing the octree to send out markers. 16: full depth / max. resolution", 16, 1, 16)
gen.add("pointcloud_min_z", double_t, 0, "Minimum height of points to consider for insertion", -100, -100, 100)
gen.add("pointcloud_max_z", double_t, 0, "Maximum height of points to consider for insertion", 100, -100, 100)
gen.add("occupancy_min_z", double_t, 0, "Minimum height of occupied cells to consider in the final map", -100, -100, 100)
gen.add("occupancy_max_z", double_t, 0, "Maximum height of occupied cells to consider in the final map", 100, -100, 100)
gen.add("sensor_model_max_range", double_t, 0, "Sensor maximum range", -1.0, -1.0, 100)
gen.add("sensor_model_min_range", double_t, 0, "Sensor minimum range", -1.0, -1.0, 100)
gen.add("sensor_model_hit", double_t, 0, "Probabilities for hits in the sensor model when dynamically building a map", 0.7, 0.5, 1.0)
gen.add("sensor_model_miss", double_t, 0, "Probabilities for misses in the sensor model when dynamically building a map", 0.4, 0.0, 0.5)
gen.add("sensor_model_min", double_t, 0, "Minimum probability for clamping when dynamically building a map", 0.12, 0.0, 1.0)
gen.add("sensor_model_max", double_t, 0, "Maximum probability for clamping when dynamically building a map", 0.97, 0.0, 1.0)
gen.add("filter_ground", bool_t, 0, "Filter ground plane", False)
gen.add("ground_filter_distance", double_t, 0, "Distance threshold to consider a point as ground", 0.04, 0.001, 1)
gen.add("ground_filter_angle", double_t, 0, "Angular threshold of the detected plane from the horizontal plane to be detected as ground ", 0.15, 0.001, 15)
gen.add("ground_filter_plane_distance", double_t, 0, "Distance threshold from z=0 for a plane to be detected as ground", 0.07, 0.001, 1)
exit(gen.generate(PACKAGE, "octomap_server_node", "OctomapServer"))