|
| 1 | +planner_configs: |
| 2 | + SBLkConfigDefault: |
| 3 | + type: geometric::SBL |
| 4 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 5 | + ESTkConfigDefault: |
| 6 | + type: geometric::EST |
| 7 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() |
| 8 | + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 |
| 9 | + LBKPIECEkConfigDefault: |
| 10 | + type: geometric::LBKPIECE |
| 11 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 12 | + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 |
| 13 | + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 |
| 14 | + BKPIECEkConfigDefault: |
| 15 | + type: geometric::BKPIECE |
| 16 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 17 | + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 |
| 18 | + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 |
| 19 | + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 |
| 20 | + KPIECEkConfigDefault: |
| 21 | + type: geometric::KPIECE |
| 22 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 23 | + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 |
| 24 | + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] |
| 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 | + RRTkConfigDefault: |
| 28 | + type: geometric::RRT |
| 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 | + RRTConnectkConfigDefault: |
| 32 | + type: geometric::RRTConnect |
| 33 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 34 | + RRTstarkConfigDefault: |
| 35 | + type: geometric::RRTstar |
| 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 | + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 |
| 39 | + TRRTkConfigDefault: |
| 40 | + type: geometric::TRRT |
| 41 | + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() |
| 42 | + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 |
| 43 | + max_states_failed: 10 # when to start increasing temp. default: 10 |
| 44 | + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 |
| 45 | + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 |
| 46 | + init_temperature: 10e-6 # initial temperature. default: 10e-6 |
| 47 | + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() |
| 48 | + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 |
| 49 | + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() |
| 50 | + PRMkConfigDefault: |
| 51 | + type: geometric::PRM |
| 52 | + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 |
| 53 | + PRMstarkConfigDefault: |
| 54 | + type: geometric::PRMstar |
| 55 | +manipulator: |
| 56 | + default_planner_config: RRTConnectkConfigDefault |
| 57 | + planner_configs: |
| 58 | + - SBLkConfigDefault |
| 59 | + - ESTkConfigDefault |
| 60 | + - LBKPIECEkConfigDefault |
| 61 | + - BKPIECEkConfigDefault |
| 62 | + - KPIECEkConfigDefault |
| 63 | + - RRTkConfigDefault |
| 64 | + - RRTConnectkConfigDefault |
| 65 | + - RRTstarkConfigDefault |
| 66 | + - TRRTkConfigDefault |
| 67 | + - PRMkConfigDefault |
| 68 | + - PRMstarkConfigDefault |
| 69 | + ##Note: commenting the following line lets moveit chose RRTConnect as default planner rather than LBKPIECE |
| 70 | + #projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint) |
| 71 | + longest_valid_segment_fraction: 0.01 |
| 72 | +endeffector: |
| 73 | + planner_configs: |
| 74 | + - SBLkConfigDefault |
| 75 | + - ESTkConfigDefault |
| 76 | + - LBKPIECEkConfigDefault |
| 77 | + - BKPIECEkConfigDefault |
| 78 | + - KPIECEkConfigDefault |
| 79 | + - RRTkConfigDefault |
| 80 | + - RRTConnectkConfigDefault |
| 81 | + - RRTstarkConfigDefault |
| 82 | + - TRRTkConfigDefault |
| 83 | + - PRMkConfigDefault |
| 84 | + - PRMstarkConfigDefault |
0 commit comments