@@ -11,8 +11,9 @@ move_base_flex:
11
11
planners : ['mesh_planner']
12
12
mesh_planner :
13
13
type : ' cvp_mesh_planner/CVPMeshPlanner'
14
- cost_limit : 0.8
14
+ cost_limit : 2.0 # inscribed radius has inf values. so they will be avoided independent on how we select this value
15
15
publish_vector_field : true
16
+
16
17
planner_patience : 10.0
17
18
planner_max_retries : 2
18
19
project_path_onto_mesh : false
@@ -31,38 +32,58 @@ move_base_flex:
31
32
32
33
mesh_map :
33
34
# input
34
- # mesh_file: '/home/amock/mesh_nav_ws/src/mesh_navigation_tutorials/mesh_navigation_tutorials/maps/parking_garage.ply'
35
+ # In this examples, `mesh_file` is set dynamically from the launch file.
36
+ # you can also set it statically:
37
+ # mesh_file: '.../parking_garage.ply'
35
38
mesh_part : ' /'
36
39
# storage
37
40
# mesh_working_file: 'parking_garage.h5'
38
41
mesh_working_part : ' mesh'
39
42
40
43
# half-edge-mesh implementation
41
- hem : pmp # pmp (default), lvr
44
+ # pmp (default), lvr
45
+ hem : pmp
42
46
47
+ # compute each layer's vertex costs in the following order
43
48
layers : ['border', 'height_diff', 'roughness', 'inflation']
49
+ # After computing the layers, a final combined vertex cost is determined by linearly combine all layers' vertex costs:
50
+ # -> vertex_cost = layer1.combination_weight * layer1.vertex_cost + layer2.combination_weight * layer2.vertex_cost + ...
51
+ # The lethal vertices are accumulated in a set along the layer list
44
52
45
53
height_diff :
46
54
type : ' mesh_layers/HeightDiffLayer'
47
- factor : 1 .0
55
+ combination_weight : 0 .0
48
56
threshold : 0.8
49
57
50
58
border :
51
59
type : ' mesh_layers/BorderLayer'
52
- factor : 1 .0
60
+ combination_weight : 0 .0
53
61
border_cost : 1.0
54
62
threshold : 0.2
55
63
56
64
roughness :
57
65
type : ' mesh_layers/RoughnessLayer'
58
- factor : 1 .0
66
+ combination_weight : 0 .0
59
67
threshold : 0.8
60
68
61
69
inflation :
62
70
type : ' mesh_layers/InflationLayer'
63
- factor : 1.0
64
- inflation_radius : 0.5
65
- inscribed_radius : 0.7
66
- lethal_value : 1.0
67
- inscribed_value : 0.6
71
+ combination_weight : 1.0
72
+ inflation_radius : 1.5 # outer ring
73
+ inscribed_radius : 0.4 # inner ring
74
+ lethal_value : 1.0 # is also inscribed value
75
+ inscribed_value : 1.0
68
76
repulsive_field : false
77
+ cost_scaling_factor : 2.0
78
+
79
+ # An edge cost equals the total costs that are collected along a
80
+ # triangle's edge by linearly interpolating the combined vertex costs
81
+ # This factor defines the factor that is used for the final edge weight
82
+ # -> edge_weight = edge_length + edge_cost_factor * edge_cost
83
+ # This edge_weight is then passed to the global planner to search for
84
+ # the best path
85
+ # Note: Set this to 0.0 if you need the shortest path
86
+ edge_cost_factor : 5.0
87
+
88
+ # debug function: enable this, for publishing text markers with edge costs
89
+ publish_edge_weights_text : false
0 commit comments