You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: doc/concepts/motion_planning.rst
+4-10Lines changed: 4 additions & 10 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -47,36 +47,30 @@ Pre-processing is useful in several situations, e.g. when a start state for the
47
47
Post-processing is needed for several other operations, e.g. to convert paths generated for a robot into time-parameterized trajectories.
48
48
MoveIt provides a set of default motion planning adapters that each perform a very specific function.
49
49
50
-
FixStartStateBounds
50
+
CheckStartStateBounds
51
51
^^^^^^^^^^^^^^^^^^^
52
52
53
53
The fix start state bounds adapter fixes the start state to be within the joint limits specified in the URDF.
54
54
The need for this adapter arises in situations where the joint limits for the physical robot are not properly configured.
55
55
The robot may then end up in a configuration where one or more of its joints is slightly outside its joint limits.
56
56
In this case, the motion planner is unable to plan since it will think that the starting state is outside joint limits.
57
-
The "FixStartStateBounds" planning request adapter will "fix" the start state by moving it to the joint limit.
57
+
The "CheckStartStateBounds" planning request adapter will "fix" the start state by moving it to the joint limit.
58
58
However, this is obviously not the right solution every time - e.g. where the joint is really outside its joint limits by a large amount.
59
59
A parameter for the adapter specifies how much the joint can be outside its limits for it to be "fixable".
60
60
61
-
FixWorkspaceBounds
61
+
ValidateWorkspaceBounds
62
62
^^^^^^^^^^^^^^^^^^
63
63
64
64
The fix workspace bounds adapter will specify a default workspace for planning: a cube of size 10 m x 10 m x 10 m.
65
65
This workspace will only be specified if the planning request to the planner does not have these fields filled in.
66
66
67
-
FixStartStateCollision
67
+
CheckStartStateCollision
68
68
^^^^^^^^^^^^^^^^^^^^^^
69
69
70
70
The fix start state collision adapter will attempt to sample a new collision-free configuration near a specified configuration (in collision) by perturbing the joint values by a small amount.
71
71
The amount that it will perturb the values by is specified by the **jiggle_fraction** parameter that controls the perturbation as a percentage of the total range of motion for the joint.
72
72
The other parameter for this adapter specifies how many random perturbations the adapter will sample before giving up.
73
73
74
-
FixStartStatePathConstraints
75
-
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
76
-
77
-
This adapter is applied when the start state for a motion plan does not obey the specified path constraints.
78
-
It will attempt to plan a path between the current configuration of the robot to a new location where the path constraint is obeyed.
79
-
The new location will serve as the start state for planning.
Copy file name to clipboardExpand all lines: doc/examples/planning_adapters/planning_adapters_tutorial.rst
+13-16Lines changed: 13 additions & 16 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -6,7 +6,7 @@
6
6
Planning Adapter Tutorials
7
7
==========================
8
8
9
-
Planning Request Adapters is a concept in MoveIt which can be used to modify the trajectory (pre-processing and/or post-processing) for a motion planner. Some examples of existing planning adapters in MoveIt include AddTimeParameterization, FixWorkspaceBounds, FixStartBounds, FixStartStateCollision, FixStartStatePathConstraints, CHOMPOptimizerAdapter, etc. ! Using the concepts of Planning Adapters, multiple motion planning algorithms can be used in a pipeline to produce robust motion plans. For example, a sample pipeline of motion plans might include an initial plan produced by OMPL which can then be optimized by CHOMP to produce a motion plan which would likely be better than a path produced by OMPL or CHOMP alone. Similarly, using the concept of Planning Adapters, other motion planners can be mixed and matched depending on the environment the robot is operating in. This section provides a step by step tutorial on using a mix and match of different motion planners and also provides insights on when to use which particular motion planners.
9
+
Planning Request Adapters is a concept in MoveIt which can be used to modify the trajectory (pre-processing and/or post-processing) for a motion planner. Some examples of existing planning adapters in MoveIt include AddTimeParameterization, ValidateWorkspaceBounds, FixStartBounds, CheckStartStateCollision, CHOMPOptimizerAdapter, etc. ! Using the concepts of Planning Adapters, multiple motion planning algorithms can be used in a pipeline to produce robust motion plans. For example, a sample pipeline of motion plans might include an initial plan produced by OMPL which can then be optimized by CHOMP to produce a motion plan which would likely be better than a path produced by OMPL or CHOMP alone. Similarly, using the concept of Planning Adapters, other motion planners can be mixed and matched depending on the environment the robot is operating in. This section provides a step by step tutorial on using a mix and match of different motion planners and also provides insights on when to use which particular motion planners.
10
10
11
11
Getting Started
12
12
---------------
@@ -46,11 +46,10 @@ To achieve this, follow the steps:
46
46
#. Open the ``ompl_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch`` folder of your robot. For the Panda robot it is this `file <https://github.com/ros-planning/panda_moveit_config/blob/melodic-devel/launch/ompl_planning_pipeline.launch.xml>`_. Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and change it to: ::
#. The values of the ``planning_adapters`` is the order in which the mentioned adapters are called / invoked. Order here matters. Inside the CHOMP adapter, a call to OMPL is made before invoking the CHOMP optimization solver, so CHOMP takes the initial path computed by OMPL as the starting point to further optimize it.
@@ -81,11 +80,10 @@ To achieve this, follow the steps:
81
80
82
81
#. Open the ``stomp_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch`` folder of your robot. For the Panda robot it is `this <https://github.com/ros-planning/panda_moveit_config/blob/melodic-devel/launch/stomp_planning_pipeline.launch.xml>`_ file. Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and change it to: ::
#. The values of the ``planning_adapters`` is the order in which the mentioned adapters are called / invoked. Order here matters. Inside the CHOMP adapter, a call to STOMP is made before invoking the CHOMP optimization solver, so CHOMP takes the initial path computed by STOMP as the starting point to further optimize it.
@@ -118,11 +116,10 @@ To achieve this, follow the steps:
118
116
119
117
#. Open the ``ompl_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch`` folder of your robot. For the Panda robot it is this `file <https://github.com/ros-planning/panda_moveit_config/blob/melodic-devel/launch/ompl_planning_pipeline.launch.xml>`_. Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and change it to: ::
#. The values of the ``planning_adapters`` is the order in which the mentioned adapters are called / invoked. Order here matters. Inside the STOMP adapter, a call to OMPL is made before invoking the STOMP smoothing solver, so STOMP takes the initial path computed by OMPL as the starting point to further optimize it.
Copy file name to clipboardExpand all lines: doc/examples/subframes/subframes_tutorial.rst
+2-2Lines changed: 2 additions & 2 deletions
Display the source diff
Display the rich diff
Original file line number
Diff line number
Diff line change
@@ -69,5 +69,5 @@ For older moveit_config packages that you have not generated yourself recently,
69
69
required for subframes might not be configured, and the subframe link might not be found. To fix this for your
70
70
moveit_config package, open the ``ompl_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch``
71
71
folder of your robot. For the Panda robot it is :panda_codedir:`this <launch/ompl_planning_pipeline.launch.xml>` file.
72
-
Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and insert ``default_planner_request_adapters/ResolveConstraintFrames`` after
73
-
the line ``default_planner_request_adapters/FixStartStatePathConstraints``.
72
+
Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and insert ``default_planning_request_adapters/ResolveConstraintFrames`` after
73
+
the line ``default_planning_request_adapters/FixStartStatePathConstraints``.
0 commit comments