Tuning Parameters OMPL (ompl_planning.yaml)

2,656 views
Skip to first unread message

Carlos Suarez Zapico

unread,
May 25, 2015, 10:02:03 PM5/25/15
to moveit...@googlegroups.com
Hi to all.

I have been using MoveIt for an application of Motion Planning. It is about a robot arm  (ABB IRB120) that has to move along some obstacles and respect the position and orientation constraints. The robot uses IKfast for its inverse kinematics and the planning time is set to 3 seconds. The result of this experiment is in: https://www.youtube.com/watch?v=LYBm4PwQyrY

The problem is that because of all the obstacles in the scene and the constraints, the robot usually finds a feasible plan in one of three times approximately. So I decided to try to have more success in the planning proccess by tuning the parameters in the ompl_planning.yaml. I have found very little documentation and tutorials so I am not sure about what I am doing.
Coming up I show you my conclusions of how parameters can be tuned in the ompl_planning.yaml so that someone can help me if I am wrong in it.

planner_configs:
  SBLkConfigDefault:
    type: geometric::SBL
    longest_valid_segment_fraction: 0.001
    projection_evaluator: joints(joint_1,joint_2)
    range: 10
  ESTkConfigDefault:
    type: geometric::EST
    longest_valid_segment_fraction: 0.001
    projection_evaluator: joints(joint_1,joint_2)
    range: 10
    goal_bias: 0.05
  LBKPIECEkConfigDefault:
    type: geometric::LBKPIECE
    projection_evaluator: joints(joint_1,joint_2)
    longest_valid_segment_fraction: 0.001
    range: 10
  BKPIECEkConfigDefault:
    type: geometric::BKPIECE
    projection_evaluator: joints(joint_1,joint_2)
    longest_valid_segment_fraction: 0.001
    range: 10
  KPIECEkConfigDefault:
    type: geometric::KPIECE
    projection_evaluator: joints(joint_1,joint_2)
    longest_valid_segment_fraction: 0.001
    range: 10
    goal_bias: 0.05
  RRTkConfigDefault:
    type: geometric::RRT
    longest_valid_segment_fraction: 0.001
    range: 10
    goal_bias: 0.05
  RRTConnectkConfigDefault:
    type: geometric::RRTConnect
    longest_valid_segment_fraction: 0.001
    range: 10
  RRTstarkConfigDefault:
    type: geometric::RRTstar
    longest_valid_segment_fraction: 0.001
    range: 10
    goal_bias: 0.05
  TRRTkConfigDefault:
    type: geometric::TRRT
    longest_valid_segment_fraction: 0.01
    range: 10
    goal_bias: 0.05
    (More  available parameters)
  PRMkConfigDefault:
    type: geometric::PRM
    longest_valid_segment_fraction: 0.001
    max_nearest_neighbors: 100
  PRMstarkConfigDefault:
    type: geometric::PRMstar
    longest_valid_segment_fraction: 0.001
  
Description of Parameters
-------------------------Parameters Used in all Planners------------------------------------------
 longest_valid_segment_fraction =the resolution at which collisions are checked  Posible values-  From 0.001 to 1 in 0.001 step
-------------------------Parameters Used in Tree-Based Planners------------------------------------------
 Range: Represents the maximum length of a motion to be added to the tree of motions. Posible values- From 0  to 10000 in 1 step
-------------------------Parameters Used in Tree-Based Planners which needs a proyection to work ------------------------------------------
projection_evaluator: Defines the orientation of the projection  A good projection in robot arms is the one formed by the shoulder and elbow joints.
-------------------------Parameters Used in Tree-Based Planners with just one tree------------------------------------------
goal_bias: The process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0 with a 0.01 step
-------------------------Parameters Used in Probabilistic Roadmap Planners PRM------------------------------------------
max_nearest_neighbors: represents the maximum number of nodes at which each vertex of the tree can be connected. Posible values- From 8 to 1000 in 1 step

Daniel Solomon

unread,
May 29, 2015, 9:02:52 PM5/29/15
to moveit...@googlegroups.com
Firstly, when you are planning under constraints, you will most likely have to give a longer time to plan, as fewer of the sampled states will be valid.

What planner are you actually using during the planning process?

The most likely OMPL parameter to attempt to improve this process is 'range'. If range is too small, the graph will expand too slowly (although successful plans are often smoother). If this value is too large, there may be many edges drawn between nodes that are inappropriate to the problem. In this problem, range is a measure of joint difference between two robot states, so you could conceivably calculate an appropriate range to match how you intuitively feel how closely states should be sampled.

-Dan

Carlos Suarez Zapico

unread,
May 29, 2015, 10:07:13 PM5/29/15
to moveit...@googlegroups.com
Thanks for your help.
In this application I used most of the planners that MoveIt has by default (KPIECE, PRM, RRT, RRTConnect, LBKPIECE, EST). I have seen benchmarking graphics that indicates that for scenes with obstacles and constrainst the best planners to use might be the KPIECE or BKPIECE ones. Am I right? 
At first I tried to change planning time because of all the constraints and obstacles the scene has, but I noticed that if the planner doesn´t find a solution in less than 2-3 seconds the planner fails to find a feasible trayectory. Several times I put times of 30 or even 60 seconds and it never worked. That was not logical so I thought the planners look for a maximum number of states and then when they reach it they stop the itertation.
 I thought that because Sampling-Based planners are said to be probabilistic completeness which means that if the number of nodes increases the probability to find a solution goes to 1. And when you can see in the simulation that a solution exists you don´t understand why the planner is not able to find a solution in 60 seconds.

I supposed you are right and the problem is the small value of the range parameter that makes the planner can´t expand around the free state space.
I will do some testing and I will tell you the results.
Reply all
Reply to author
Forward
0 new messages