ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

how to change default planner for moveit

asked 2014-06-19 15:31:46 -0600

airplanesrule gravatar image

I am attempting to change the default planner for moveit from LBKPIECE1 to ESTkConfigDefault. I have tried appending:

  default_planner_config: ESTkConfigDefault

to the end of my ompl_planning.yaml with no success. I have yet to find any other way to accomplish this from either the command line or through configuration files. My full ompl_planning.yaml file is copied below in case it is relevant.

planner_configs:
  SBLkConfigDefault:
    type: geometric::SBL
  ESTkConfigDefault:
    type: geometric::EST
  LBKPIECEkConfigDefault:
    type: geometric::LBKPIECE
  BKPIECEkConfigDefault:
    type: geometric::BKPIECE
  KPIECEkConfigDefault:
    type: geometric::KPIECE
  RRTkConfigDefault:
    type: geometric::RRT
  RRTConnectkConfigDefault:
    type: geometric::RRTConnect
  RRTstarkConfigDefault:
    type: geometric::RRTstar
  TRRTkConfigDefault:
    type: geometric::TRRT
  PRMkConfigDefault:
    type: geometric::PRM
  PRMstarkConfigDefault:
    type: geometric::PRMstar

manipulator:
  planner_configs:
    - SBLkConfigDefault
    - ESTkConfigDefault
    - LBKPIECEkConfigDefault
    - BKPIECEkConfigDefault
    - KPIECEkConfigDefault
    - RRTkConfigDefault
    - RRTConnectkConfigDefault
    - RRTstarkConfigDefault
    - TRRTkConfigDefault
    - PRMkConfigDefault
    - PRMstarkConfigDefault

  projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)
  longest_valid_segment_fraction: 0.05
  default_planner_config: ESTkConfigDefault
edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
2

answered 2016-02-08 21:26:07 -0600

Kei Okada gravatar image

you can set default planner with configuration file on latest moveit@indigo -> https://github.com/ros-planning/movei...

edit flag offensive delete link more
8

answered 2014-12-17 06:34:47 -0600

VictorLamoine gravatar image

You can choose your solver by using the setPlannerId member of your MoveGroup:

  move_group_interface::MoveGroup group("manipulator");
  // See ompl_planning.yaml for a complete list
  group.setPlannerId("SBLkConfigDefault");
edit flag offensive delete link more

Comments

which planner is used when no planner Id is specified ?

psfa_fz gravatar image psfa_fz  ( 2015-01-30 10:18:13 -0600 )edit

If you remove the line:

projection_evaluator: joints(shoulder_pan_joint,shoulder_lift_joint)

the default will be RRTConnect, else LBKPIECE1.

I am also interested in a deterministic way to set the default planner.

marcoesposito1988 gravatar image marcoesposito1988  ( 2015-04-15 11:43:22 -0600 )edit

For the people who end up here looking up how to switch planners: you may need to set setPlanningPipelineId too.

fvd gravatar image fvd  ( 2021-04-26 10:54:42 -0600 )edit
0

answered 2023-05-08 16:32:19 -0600

130s gravatar image

updated 2023-05-08 16:33:18 -0600

Years passed I still hit this post but not much other newer posts.

In ROS2 from launch, you can set default_planner_config in ompl_planning.yaml in each move-group (NOT for the entire yaml) e.g.:

arm_x:
  default_planner_config: PRMkConfigDefault
  planner_configs:
    - SBLkConfigDefault
    - ESTkConfigDefault
    - LBKPIECEkConfigDefault
    - BKPIECEkConfigDefault
    - KPIECEkConfigDefault
    - RRTkConfigDefault
    - RRTConnectkConfigDefault
    - RRTstarkConfigDefault
    - TRRTkConfigDefault
    - PRMkConfigDefault
    - PRMstarkConfigDefault
  longest_valid_segment_fraction: 0.01

I think this feature was added a while ago in moveit_ros!625 (same PR the answer above refers to) but might have slipped from documentation.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2014-06-19 15:31:46 -0600

Seen: 10,596 times

Last updated: May 08 '23