Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update tutorials for planning pipeline refactoring #793

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 4 additions & 10 deletions doc/concepts/motion_planning.rst
Original file line number Diff line number Diff line change
Expand Up @@ -47,36 +47,30 @@ Pre-processing is useful in several situations, e.g. when a start state for the
Post-processing is needed for several other operations, e.g. to convert paths generated for a robot into time-parameterized trajectories.
MoveIt provides a set of default motion planning adapters that each perform a very specific function.

FixStartStateBounds
CheckStartStateBounds
^^^^^^^^^^^^^^^^^^^

The fix start state bounds adapter fixes the start state to be within the joint limits specified in the URDF.
The need for this adapter arises in situations where the joint limits for the physical robot are not properly configured.
The robot may then end up in a configuration where one or more of its joints is slightly outside its joint limits.
In this case, the motion planner is unable to plan since it will think that the starting state is outside joint limits.
The "FixStartStateBounds" planning request adapter will "fix" the start state by moving it to the joint limit.
The "CheckStartStateBounds" planning request adapter will "fix" the start state by moving it to the joint limit.
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.
A parameter for the adapter specifies how much the joint can be outside its limits for it to be "fixable".

FixWorkspaceBounds
ValidateWorkspaceBounds
^^^^^^^^^^^^^^^^^^

The fix workspace bounds adapter will specify a default workspace for planning: a cube of size 10 m x 10 m x 10 m.
This workspace will only be specified if the planning request to the planner does not have these fields filled in.

FixStartStateCollision
CheckStartStateCollision
^^^^^^^^^^^^^^^^^^^^^^
sjahr marked this conversation as resolved.
Show resolved Hide resolved

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.
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.
The other parameter for this adapter specifies how many random perturbations the adapter will sample before giving up.

FixStartStatePathConstraints
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

This adapter is applied when the start state for a motion plan does not obey the specified path constraints.
It will attempt to plan a path between the current configuration of the robot to a new location where the path constraint is obeyed.
The new location will serve as the start state for planning.

AddTimeParameterization
^^^^^^^^^^^^^^^^^^^^^^^
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,8 @@ int main(int argc, char** argv)
req.pipeline_id = "ompl";
req.planner_id = "RRTConnectkConfigDefault";
req.allowed_planning_time = 1.0;
req.max_velocity_scaling_factor = 1.0;
req.max_acceleration_scaling_factor = 1.0;
planning_interface::MotionPlanResponse res;
geometry_msgs::msg::PoseStamped pose;
pose.header.frame_id = "panda_link0";
Expand Down
4 changes: 2 additions & 2 deletions doc/examples/subframes/subframes_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -69,5 +69,5 @@ For older moveit_config packages that you have not generated yourself recently,
required for subframes might not be configured, and the subframe link might not be found. To fix this for your
moveit_config package, open the ``ompl_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch``
folder of your robot. For the Panda robot it is :panda_codedir:`this <launch/ompl_planning_pipeline.launch.xml>` file.
Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and insert ``default_planner_request_adapters/ResolveConstraintFrames`` after
the line ``default_planner_request_adapters/FixStartStatePathConstraints``.
Edit this launch file, find the lines where ``<arg name="planning_adapters">`` is mentioned and insert ``default_planning_request_adapters/ResolveConstraintFrames`` after
the line ``default_planning_request_adapters/FixStartStatePathConstraints``.
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ Finally, add the Ruckig smoothing algorithm to the list of planning request adap

.. code-block:: yaml

request_adapters: >-
default_planner_request_adapters/AddRuckigTrajectorySmoothing
default_planner_request_adapters/AddTimeOptimalParameterization
response_adapters:
- default_planning_request_adapters/AddRuckigTrajectorySmoothing
- default_planning_request_adapters/AddTimeOptimalParameterization
...
19 changes: 11 additions & 8 deletions doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,17 @@ def generate_launch_description():
ompl_planning_pipeline_config = {
"ompl_rrtc": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": """\
default_planner_request_adapters/AddTimeOptimalParameterization \
default_planner_request_adapters/FixWorkspaceBounds \
default_planner_request_adapters/FixStartStateBounds \
default_planner_request_adapters/FixStartStateCollision \
default_planner_request_adapters/FixStartStatePathConstraints \
""",
"start_state_max_bounds_error": 0.1,
"request_adapters": [
"default_planning_request_adapters/ResolveConstraintFrames",
"default_planning_request_adapters/ValidateWorkspaceBounds",
"default_planning_request_adapters/CheckStartStateBounds",
"default_planning_request_adapters/CheckStartStateCollision",
],
"response_adapters": [
"default_planning_response_adapters/AddTimeOptimalParameterization",
"default_planning_response_adapters/ValidateSolution",
"default_planning_response_adapters/DisplayMotionPath",
],
}
}
ompl_planning_yaml = load_yaml(
Expand Down
28 changes: 0 additions & 28 deletions doc/how_to_guides/chomp_planner/chomp_planner_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -98,31 +98,3 @@ OMPL is a open source library for sampling based / randomized motion planning al
CHOMP: While most high-dimensional motion planners separate trajectory generation into distinct planning and optimization stages, CHOMP capitalizes on covariant gradient and functional gradient approaches to the optimization stage to design a motion planning algorithm based entirely on trajectory optimization. Given an infeasible naive trajectory, CHOMP reacts to the surrounding environment to quickly pull the trajectory out of collision while simultaneously optimizing dynamic quantities such as joint velocities and accelerations. It rapidly converges to a smooth, collision-free trajectory that can be executed efficiently on the robot. A covariant update rule ensures that CHOMP quickly converges to a locally optimal trajectory.

For scenes containing obstacles, CHOMP often generates paths which do not prefer smooth trajectories by addition of some noise (*ridge_factor*) in the cost function for the dynamic quantities of the robot (like acceleration, velocity). CHOMP is able to avoid obstacles in most cases, but it can fail if it gets stuck in local minima due to a bad initial guess for the trajectory. OMPL can be used to generate collision-free seed trajectories for CHOMP to mitigate this issue.

Using CHOMP as a post-processor for OMPL
sjahr marked this conversation as resolved.
Show resolved Hide resolved
----------------------------------------
Here, we will demonstrate that CHOMP can also be used as a post-processing optimization technique for plans obtained by other planning algorithms. The intuition behind this is that some randomized planning algorithm produces an initial guess for CHOMP. CHOMP then takes this initial guess and further optimizes the trajectory.
To achieve this, use the following steps:

#. Edit ``ompl_planning.yaml`` in the ``<robot_moveit_config>/config`` folder of your robot. Add ``chomp/OptimizerAdapter`` to the bottom of the list of request_adapters: ::

request_adapters: >-
...
default_planner_request_adapters/FixStartStatePathConstraints
chomp/OptimizerAdapter

#. Change the ``trajectory_initialization_method`` parameter in ``chomp_planning.yaml`` to ``fillTrajectory`` so that OMPL can provide the input for the CHOMP algorithm: ::

trajectory_initialization_method: "fillTrajectory"

#. Add the CHOMP config file to the launch file of your robot, ``<robot_moveit_config>/launch/chomp_demo.launch.py``, if it is not there already: ::

.planning_pipelines(pipelines=["ompl", "chomp"])

#. Now you can launch the newly configured planning pipeline as follows: ::

ros2 launch moveit2_tutorials chomp_demo.launch.py rviz_tutorial:=True

This will launch RViz. Select OMPL in the Motion Planning panel under the Context tab. Set the desired start and goal states by moving the end-effector around in the same way as was done for CHOMP above. Finally click on the Plan button to start planning. The planner will now first run OMPL, then run CHOMP on OMPL's output to produce an optimized path. To make the planner's task more challenging, add obstacles to the scene using: ::

ros2 run moveit2_tutorials collision_scene_example
Original file line number Diff line number Diff line change
Expand Up @@ -58,14 +58,17 @@ def launch_setup(context, *args, **kwargs):
ompl_planning_pipeline_config = {
"ompl_2": {
"planning_plugin": "ompl_interface/OMPLPlanner",
"request_adapters": """\
default_planner_request_adapters/AddTimeOptimalParameterization \
default_planner_request_adapters/FixWorkspaceBounds \
default_planner_request_adapters/FixStartStateBounds \
default_planner_request_adapters/FixStartStateCollision \
default_planner_request_adapters/FixStartStatePathConstraints \
""",
"start_state_max_bounds_error": 0.1,
"request_adapters": [
"default_planning_request_adapters/ResolveConstraintFrames",
"default_planning_request_adapters/ValidateWorkspaceBounds",
"default_planning_request_adapters/CheckStartStateBounds",
"default_planning_request_adapters/CheckStartStateCollision",
],
"response_adapters": [
"default_planning_response_adapters/AddTimeOptimalParameterization",
"default_planning_response_adapters/ValidateSolution",
"default_planning_response_adapters/DisplayMotionPath",
],
}
}
ompl_planning_yaml = load_yaml(
Expand Down
33 changes: 9 additions & 24 deletions doc/how_to_guides/stomp_planner/stomp_planner.rst
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,15 @@ Using STOMP with Your Robot
#. Simply add the `stomp_planning.yaml <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/config/stomp_planning.yaml>`__ configuration file into the config directory of your MoveIt config package. It contains the plugin identifier, a planning pipeline adapter list, and the STOMP planning parameters. The config file should look like example below: ::

planning_plugin: stomp_moveit/StompPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
- default_planning_response_adapters/DisplayMotionPath

stomp_moveit:
num_timesteps: 60
Expand All @@ -51,24 +54,6 @@ Using STOMP with Your Robot

#. Configure MoveIt to load the STOMP planning pipeline by adding "stomp" to your MoveItConfiguration launch statement next to "ompl" and the other planners. You can find an example for this in the `demo.launch.py <https://github.com/ros-planning/moveit_resources/blob/ros2/panda_moveit_config/launch/demo.launch.py#L42>`_ of the Panda config.

Using STOMP's planner adapter
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

STOMP can also be used for smoothing and optimizing trajectories from other planner plugins using the ``StompSmoothingAdapter`` plugin.
The only step needed is to add the plugin name ``stomp_moveit/StompSmoothingAdapter`` to the ``request_adapters`` parameter list configured for the planning pipeline: ::

request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
stomp_moveit/StompSmoothingAdapter

In addition, STOMP parameters can be specified just like for the usual planning setup.
An important detail is that now the parameter ``num_iterations_after_valid`` is used for specifying the smoothing steps since the input trajectory is already valid.
It should therefore be larger than 0 to have an effect.

Running the Demo
----------------
If you have the ``panda_moveit_config`` from the `ros-planning/moveit_resources <https://github.com/ros-planning/moveit_resources>`_ repository you should be able to simply launch the demo setup and start planning with STOMP in RViZ ::
Expand Down
Loading