ompl_planning.yaml 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196
  1. planner_configs:
  2. AnytimePathShortening:
  3. type: geometric::AnytimePathShortening
  4. shortcut: true # Attempt to shortcut all new solution paths
  5. hybridize: true # Compute hybrid solution trajectories
  6. max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
  7. num_planners: 4 # The number of default planners to use for planning
  8. planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
  9. SBL:
  10. type: geometric::SBL
  11. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  12. EST:
  13. type: geometric::EST
  14. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
  15. goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
  16. LBKPIECE:
  17. type: geometric::LBKPIECE
  18. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  19. border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
  20. min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
  21. BKPIECE:
  22. type: geometric::BKPIECE
  23. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  24. border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
  25. failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
  26. min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
  27. KPIECE:
  28. type: geometric::KPIECE
  29. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  30. goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
  31. border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
  32. failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
  33. min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
  34. RRT:
  35. type: geometric::RRT
  36. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  37. goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
  38. RRTConnect:
  39. type: geometric::RRTConnect
  40. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  41. RRTstar:
  42. type: geometric::RRTstar
  43. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  44. goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
  45. delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
  46. TRRT:
  47. type: geometric::TRRT
  48. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  49. goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
  50. max_states_failed: 10 # when to start increasing temp. default: 10
  51. temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
  52. min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
  53. init_temperature: 10e-6 # initial temperature. default: 10e-6
  54. frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
  55. frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
  56. k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
  57. PRM:
  58. type: geometric::PRM
  59. max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
  60. PRMstar:
  61. type: geometric::PRMstar
  62. FMT:
  63. type: geometric::FMT
  64. num_samples: 1000 # number of states that the planner should sample. default: 1000
  65. radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
  66. nearest_k: 1 # use Knearest strategy. default: 1
  67. cache_cc: 1 # use collision checking cache. default: 1
  68. heuristics: 0 # activate cost to go heuristics. default: 0
  69. extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
  70. BFMT:
  71. type: geometric::BFMT
  72. num_samples: 1000 # number of states that the planner should sample. default: 1000
  73. radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
  74. nearest_k: 1 # use the Knearest strategy. default: 1
  75. balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
  76. optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
  77. heuristics: 1 # activates cost to go heuristics. default: 1
  78. cache_cc: 1 # use the collision checking cache. default: 1
  79. extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
  80. PDST:
  81. type: geometric::PDST
  82. STRIDE:
  83. type: geometric::STRIDE
  84. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  85. goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
  86. use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
  87. degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
  88. max_degree: 18 # max degree of a node in the GNAT. default: 12
  89. min_degree: 12 # min degree of a node in the GNAT. default: 12
  90. max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
  91. estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
  92. min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
  93. BiTRRT:
  94. type: geometric::BiTRRT
  95. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  96. temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
  97. init_temperature: 100 # initial temperature. default: 100
  98. frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
  99. frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
  100. cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
  101. LBTRRT:
  102. type: geometric::LBTRRT
  103. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  104. goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
  105. epsilon: 0.4 # optimality approximation factor. default: 0.4
  106. BiEST:
  107. type: geometric::BiEST
  108. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  109. ProjEST:
  110. type: geometric::ProjEST
  111. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  112. goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
  113. LazyPRM:
  114. type: geometric::LazyPRM
  115. range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
  116. LazyPRMstar:
  117. type: geometric::LazyPRMstar
  118. SPARS:
  119. type: geometric::SPARS
  120. stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
  121. sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
  122. dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
  123. max_failures: 1000 # maximum consecutive failure limit. default: 1000
  124. SPARStwo:
  125. type: geometric::SPARStwo
  126. stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
  127. sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
  128. dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
  129. max_failures: 5000 # maximum consecutive failure limit. default: 5000
  130. AITstar:
  131. type: geometric::AITstar
  132. use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
  133. rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
  134. samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
  135. use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
  136. find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
  137. set_max_num_goals: 1 # maximum number of goals sampled from sampleable goal regions. Valid values: [1:1:1000]. Default: 1
  138. ABITstar:
  139. type: geometric::ABITstar
  140. use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
  141. rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
  142. samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
  143. use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
  144. prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
  145. delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0
  146. use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
  147. drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
  148. stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
  149. use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
  150. find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
  151. initial_inflation_factor: 1000000 # inflation factor for the initial search. Valid values: [1.0:0.01:1000000.0]. Default: 1000000
  152. inflation_scaling_parameter: 10 # scaling parameter for the inflation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
  153. truncation_scaling_parameter: 5.0 # scaling parameter for the truncation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
  154. BITstar:
  155. type: geometric::BITstar
  156. use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
  157. rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
  158. samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
  159. use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
  160. prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
  161. delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0
  162. use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
  163. drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
  164. stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
  165. use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
  166. find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
  167. manipulator:
  168. default_planner_config: RRTConnect
  169. planner_configs:
  170. - AnytimePathShortening
  171. - SBL
  172. - EST
  173. - LBKPIECE
  174. - BKPIECE
  175. - KPIECE
  176. - RRT
  177. - RRTConnect
  178. - RRTstar
  179. - TRRT
  180. - PRM
  181. - PRMstar
  182. - FMT
  183. - BFMT
  184. - PDST
  185. - STRIDE
  186. - BiTRRT
  187. - LBTRRT
  188. - BiEST
  189. - ProjEST
  190. - LazyPRM
  191. - LazyPRMstar
  192. - SPARS
  193. - SPARStwo
  194. - AITstar
  195. - ABITstar
  196. - BITstar