Skip to content
Snippets Groups Projects
Commit 5d0ea453 authored by Marco Esposito's avatar Marco Esposito
Browse files

Use RRTConnect by default for UR5

Fixes bug #193 about slow planning on Indigo

LBKPIECE1 (the previous default) looks to be the wrong planning algorithm for the robot
See https://groups.google.com/forum/#!topic/moveit-users/M71T-GaUNgg
parent 93fa8d5b
Branches
Tags
No related merge requests found
...@@ -34,7 +34,6 @@ manipulator: ...@@ -34,7 +34,6 @@ manipulator:
- TRRTkConfigDefault - TRRTkConfigDefault
- PRMkConfigDefault - PRMkConfigDefault
- PRMstarkConfigDefault - PRMstarkConfigDefault
projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
longest_valid_segment_fraction: 0.05 longest_valid_segment_fraction: 0.05
endeffector: endeffector:
planner_configs: planner_configs:
...@@ -48,4 +47,4 @@ endeffector: ...@@ -48,4 +47,4 @@ endeffector:
- RRTstarkConfigDefault - RRTstarkConfigDefault
- TRRTkConfigDefault - TRRTkConfigDefault
- PRMkConfigDefault - PRMkConfigDefault
- PRMstarkConfigDefault - PRMstarkConfigDefault
\ No newline at end of file
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment