|
| 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 | + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() |
| 55 | + frountierNodeRatio: 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 | + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() |
| 99 | + frountier_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 | +rusty_arm: |
| 131 | + planner_configs: |
| 132 | + - AnytimePathShortening |
| 133 | + - SBL |
| 134 | + - EST |
| 135 | + - LBKPIECE |
| 136 | + - BKPIECE |
| 137 | + - KPIECE |
| 138 | + - RRT |
| 139 | + - RRTConnect |
| 140 | + - RRTstar |
| 141 | + - TRRT |
| 142 | + - PRM |
| 143 | + - PRMstar |
| 144 | + - FMT |
| 145 | + - BFMT |
| 146 | + - PDST |
| 147 | + - STRIDE |
| 148 | + - BiTRRT |
| 149 | + - LBTRRT |
| 150 | + - BiEST |
| 151 | + - ProjEST |
| 152 | + - LazyPRM |
| 153 | + - LazyPRMstar |
| 154 | + - SPARS |
| 155 | + - SPARStwo |
| 156 | + projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) |
| 157 | + longest_valid_segment_fraction: 0.005 |
0 commit comments