Skip to content

Commit 06fcaf6

Browse files
committed
Update tutorials
Name planning pipeline correctly Update tutorial Update motion planning API tutorial Apply suggestions from code review Address review comment Remove config
1 parent 92a8a7b commit 06fcaf6

File tree

13 files changed

+94
-117
lines changed

13 files changed

+94
-117
lines changed

doc/concepts/motion_planning.rst

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -47,36 +47,30 @@ Pre-processing is useful in several situations, e.g. when a start state for the
4747
Post-processing is needed for several other operations, e.g. to convert paths generated for a robot into time-parameterized trajectories.
4848
MoveIt provides a set of default motion planning adapters that each perform a very specific function.
4949

50-
FixStartStateBounds
50+
CheckStartStateBounds
5151
^^^^^^^^^^^^^^^^^^^
5252

5353
The fix start state bounds adapter fixes the start state to be within the joint limits specified in the URDF.
5454
The need for this adapter arises in situations where the joint limits for the physical robot are not properly configured.
5555
The robot may then end up in a configuration where one or more of its joints is slightly outside its joint limits.
5656
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.
5858
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.
5959
A parameter for the adapter specifies how much the joint can be outside its limits for it to be "fixable".
6060

61-
FixWorkspaceBounds
61+
ValidateWorkspaceBounds
6262
^^^^^^^^^^^^^^^^^^
6363

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

67-
FixStartStateCollision
67+
CheckStartStateCollision
6868
^^^^^^^^^^^^^^^^^^^^^^
6969

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

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.
8074

8175
AddTimeParameterization
8276
^^^^^^^^^^^^^^^^^^^^^^^

doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp

Lines changed: 27 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -94,13 +94,13 @@ int main(int argc, char** argv)
9494
// Note that we are using the ROS pluginlib library here.
9595
std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager>> planner_plugin_loader;
9696
planning_interface::PlannerManagerPtr planner_instance;
97-
std::string planner_plugin_name;
97+
std::vector<std::string> planner_plugin_names;
9898

9999
// We will get the name of planning plugin we want to load
100100
// from the ROS parameter server, and then load the planner
101101
// making sure to catch all exceptions.
102-
if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugin", planner_plugin_name))
103-
RCLCPP_FATAL(LOGGER, "Could not find planner plugin name");
102+
if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugins", planner_plugin_names))
103+
RCLCPP_FATAL(LOGGER, "Could not find planner plugin names");
104104
try
105105
{
106106
planner_plugin_loader.reset(new pluginlib::ClassLoader<planning_interface::PlannerManager>(
@@ -110,9 +110,11 @@ int main(int argc, char** argv)
110110
{
111111
RCLCPP_FATAL(LOGGER, "Exception while creating planning plugin loader %s", ex.what());
112112
}
113+
114+
const auto& planner_name = planner_plugin_names.at(0);
113115
try
114116
{
115-
planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name));
117+
planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_name));
116118
if (!planner_instance->initialize(robot_model, motion_planning_api_tutorial_node,
117119
motion_planning_api_tutorial_node->get_namespace()))
118120
RCLCPP_FATAL(LOGGER, "Could not initialize planner instance");
@@ -124,7 +126,7 @@ int main(int argc, char** argv)
124126
std::stringstream ss;
125127
for (const auto& cls : classes)
126128
ss << cls << " ";
127-
RCLCPP_ERROR(LOGGER, "Exception while loading planner '%s': %s\nAvailable plugins: %s", planner_plugin_name.c_str(),
129+
RCLCPP_ERROR(LOGGER, "Exception while loading planner '%s': %s\nAvailable plugins: %s", planner_name.c_str(),
128130
ex.what(), ss.str().c_str());
129131
}
130132

@@ -166,14 +168,14 @@ int main(int argc, char** argv)
166168
geometry_msgs::msg::PoseStamped pose;
167169
pose.header.frame_id = "panda_link0";
168170
pose.pose.position.x = 0.3;
169-
pose.pose.position.y = 0.4;
171+
pose.pose.position.y = 0.0;
170172
pose.pose.position.z = 0.75;
171-
pose.pose.orientation.w = 1.0;
173+
pose.pose.orientation.z = 1.0;
172174

173-
// A tolerance of 0.01 m is specified in position
174-
// and 0.01 radians in orientation
175-
std::vector<double> tolerance_pose(3, 0.01);
176-
std::vector<double> tolerance_angle(3, 0.01);
175+
// A tolerance of 0.1 m is specified in position
176+
// and 0.1 radians in orientation
177+
std::vector<double> tolerance_pose(3, 0.1);
178+
std::vector<double> tolerance_angle(3, 0.1);
177179

178180
// We will create the request as a constraint using a helper function available
179181
// from the
@@ -185,16 +187,28 @@ int main(int argc, char** argv)
185187
req.group_name = PLANNING_GROUP;
186188
req.goal_constraints.push_back(pose_goal);
187189

190+
// Define workspace bounds
191+
req.workspace_parameters.min_corner.x = req.workspace_parameters.min_corner.y =
192+
req.workspace_parameters.min_corner.z = -5.0;
193+
req.workspace_parameters.max_corner.x = req.workspace_parameters.max_corner.y =
194+
req.workspace_parameters.max_corner.z = 5.0;
195+
188196
// We now construct a planning context that encapsulate the scene,
189197
// the request and the response. We call the planner using this
190198
// planning context
191199
planning_interface::PlanningContextPtr context =
192200
planner_instance->getPlanningContext(planning_scene, req, res.error_code);
201+
202+
if (!context)
203+
{
204+
RCLCPP_ERROR(LOGGER, "Failed to create planning context");
205+
return -1;
206+
}
193207
context->solve(res);
194208
if (res.error_code.val != res.error_code.SUCCESS)
195209
{
196210
RCLCPP_ERROR(LOGGER, "Could not compute plan successfully");
197-
return 0;
211+
return -1;
198212
}
199213

200214
// Visualize the result
@@ -246,7 +260,7 @@ int main(int argc, char** argv)
246260
if (res.error_code.val != res.error_code.SUCCESS)
247261
{
248262
RCLCPP_ERROR(LOGGER, "Could not compute plan successfully");
249-
return 0;
263+
return -1;
250264
}
251265
/* Visualize the trajectory */
252266
res.getMessage(response);

doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,8 @@ int main(int argc, char** argv)
141141
req.pipeline_id = "ompl";
142142
req.planner_id = "RRTConnectkConfigDefault";
143143
req.allowed_planning_time = 1.0;
144+
req.max_velocity_scaling_factor = 1.0;
145+
req.max_acceleration_scaling_factor = 1.0;
144146
planning_interface::MotionPlanResponse res;
145147
geometry_msgs::msg::PoseStamped pose;
146148
pose.header.frame_id = "panda_link0";

doc/examples/moveit_cpp/config/moveit_cpp.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,5 +14,6 @@ planning_pipelines:
1414
plan_request_params:
1515
planning_attempts: 1
1616
planning_pipeline: ompl
17+
planner_id: "RRTConnectkConfigDefault"
1718
max_velocity_scaling_factor: 1.0
1819
max_acceleration_scaling_factor: 1.0

doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ def generate_launch_description():
1111
MoveItConfigsBuilder("moveit_resources_panda")
1212
.robot_description(file_path="config/panda.urdf.xacro")
1313
.trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
14+
.planning_pipelines("ompl", ["ompl"])
1415
.moveit_cpp(
1516
file_path=get_package_share_directory("moveit2_tutorials")
1617
+ "/config/moveit_cpp.yaml"

doc/examples/planning_adapters/planning_adapters_tutorial.rst

Lines changed: 13 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
Planning Adapter Tutorials
77
==========================
88

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.
1010

1111
Getting Started
1212
---------------
@@ -46,11 +46,10 @@ To achieve this, follow the steps:
4646
#. 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: ::
4747

4848
<arg name="planning_adapters"
49-
value="default_planner_request_adapters/AddTimeParameterization
50-
default_planner_request_adapters/FixWorkspaceBounds
51-
default_planner_request_adapters/FixStartStateBounds
52-
default_planner_request_adapters/FixStartStateCollision
53-
default_planner_request_adapters/FixStartStatePathConstraints
49+
value="default_planning_request_adapters/AddTimeParameterization
50+
default_planning_request_adapters/ValidateWorkspaceBounds
51+
default_planning_request_adapters/CheckStartStateBounds
52+
default_planning_request_adapters/CheckStartStateCollision
5453
chomp/OptimizerAdapter" />
5554

5655
#. 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:
8180

8281
#. 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: ::
8382

84-
<arg name="planning_adapters" value="default_planner_request_adapters/AddTimeParameterization
85-
default_planner_request_adapters/FixWorkspaceBounds
86-
default_planner_request_adapters/FixStartStateBounds
87-
default_planner_request_adapters/FixStartStateCollision
88-
default_planner_request_adapters/FixStartStatePathConstraints
83+
<arg name="planning_adapters" value="default_planning_request_adapters/AddTimeParameterization
84+
default_planning_request_adapters/ValidateWorkspaceBounds
85+
default_planning_request_adapters/CheckStartStateBounds
86+
default_planning_request_adapters/CheckStartStateCollision
8987
chomp/OptimizerAdapter" />
9088

9189
#. 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:
118116

119117
#. 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: ::
120118

121-
<arg name="planning_adapters" value="default_planner_request_adapters/AddTimeParameterization
122-
default_planner_request_adapters/FixWorkspaceBounds
123-
default_planner_request_adapters/FixStartStateBounds
124-
default_planner_request_adapters/FixStartStateCollision
125-
default_planner_request_adapters/FixStartStatePathConstraints
119+
<arg name="planning_adapters" value="default_planning_request_adapters/AddTimeParameterization
120+
default_planning_request_adapters/ValidateWorkspaceBounds
121+
default_planning_request_adapters/CheckStartStateBounds
122+
default_planning_request_adapters/CheckStartStateCollision
126123
stomp_moveit/StompSmoothingAdapter" />
127124

128125
#. 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.

doc/examples/subframes/subframes_tutorial.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,5 +69,5 @@ For older moveit_config packages that you have not generated yourself recently,
6969
required for subframes might not be configured, and the subframe link might not be found. To fix this for your
7070
moveit_config package, open the ``ompl_planning_pipeline.launch`` file in the ``<robot_moveit_config>/launch``
7171
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``.

doc/examples/time_parameterization/time_parameterization_tutorial.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ Finally, add the Ruckig smoothing algorithm to the list of planning request adap
3434

3535
.. code-block:: yaml
3636
37-
request_adapters: >-
38-
default_planner_request_adapters/AddRuckigTrajectorySmoothing
39-
default_planner_request_adapters/AddTimeOptimalParameterization
37+
response_adapters:
38+
- default_planning_request_adapters/AddRuckigTrajectorySmoothing
39+
- default_planning_request_adapters/AddTimeOptimalParameterization
4040
...

doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -46,15 +46,20 @@ def generate_launch_description():
4646
# Load additional OMPL pipeline
4747
ompl_planning_pipeline_config = {
4848
"ompl_rrtc": {
49-
"planning_plugin": "ompl_interface/OMPLPlanner",
50-
"request_adapters": """\
51-
default_planner_request_adapters/AddTimeOptimalParameterization \
52-
default_planner_request_adapters/FixWorkspaceBounds \
53-
default_planner_request_adapters/FixStartStateBounds \
54-
default_planner_request_adapters/FixStartStateCollision \
55-
default_planner_request_adapters/FixStartStatePathConstraints \
56-
""",
57-
"start_state_max_bounds_error": 0.1,
49+
"planning_plugins": [
50+
"ompl_interface/OMPLPlanner",
51+
],
52+
"request_adapters": [
53+
"default_planning_request_adapters/ResolveConstraintFrames",
54+
"default_planning_request_adapters/ValidateWorkspaceBounds",
55+
"default_planning_request_adapters/CheckStartStateBounds",
56+
"default_planning_request_adapters/CheckStartStateCollision",
57+
],
58+
"response_adapters": [
59+
"default_planning_response_adapters/AddTimeOptimalParameterization",
60+
"default_planning_response_adapters/ValidateSolution",
61+
"default_planning_response_adapters/DisplayMotionPath",
62+
],
5863
}
5964
}
6065
ompl_planning_yaml = load_yaml(

0 commit comments

Comments
 (0)