Skip to content

Commit

Permalink
Use OMPL config for both arm groups, panda_arm + manipulator
Browse files Browse the repository at this point in the history
  • Loading branch information
gollth authored and rhaschke committed Mar 15, 2022
1 parent e2d7353 commit e60dc0b
Showing 1 changed file with 2 additions and 29 deletions.
31 changes: 2 additions & 29 deletions config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ planner_configs:
sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
max_failures: 5000 # maximum consecutive failure limit. default: 5000
panda_arm:
panda_arm: &arm_config
planner_configs:
- AnytimePathShortening
- SBL
Expand Down Expand Up @@ -155,6 +155,7 @@ panda_arm:
- SPARStwo
projection_evaluator: joints(panda_joint1,panda_joint2)
longest_valid_segment_fraction: 0.005
manipulator: *arm_config
hand:
planner_configs:
- AnytimePathShortening
Expand All @@ -181,31 +182,3 @@ hand:
- LazyPRMstar
- SPARS
- SPARStwo
panda_arm_hand:
planner_configs:
- AnytimePathShortening
- SBL
- EST
- LBKPIECE
- BKPIECE
- KPIECE
- RRT
- RRTConnect
- RRTstar
- TRRT
- PRM
- PRMstar
- FMT
- BFMT
- PDST
- STRIDE
- BiTRRT
- LBTRRT
- BiEST
- ProjEST
- LazyPRM
- LazyPRMstar
- SPARS
- SPARStwo
projection_evaluator: joints(panda_joint1,panda_joint2)
longest_valid_segment_fraction: 0.005

0 comments on commit e60dc0b

Please sign in to comment.