diff --git a/doc/concepts/motion_planning.rst b/doc/concepts/motion_planning.rst index b10a48bd38..f05d1cceb6 100644 --- a/doc/concepts/motion_planning.rst +++ b/doc/concepts/motion_planning.rst @@ -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 ^^^^^^^^^^^^^^^^^^^^^^ 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 ^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp b/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp index 3fd2c116aa..ad8fe38bd9 100644 --- a/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp +++ b/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp @@ -94,13 +94,13 @@ int main(int argc, char** argv) // Note that we are using the ROS pluginlib library here. std::unique_ptr> planner_plugin_loader; planning_interface::PlannerManagerPtr planner_instance; - std::string planner_plugin_name; + std::vector planner_plugin_names; // We will get the name of planning plugin we want to load // from the ROS parameter server, and then load the planner // making sure to catch all exceptions. - if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugin", planner_plugin_name)) - RCLCPP_FATAL(LOGGER, "Could not find planner plugin name"); + if (!motion_planning_api_tutorial_node->get_parameter("ompl.planning_plugins", planner_plugin_names)) + RCLCPP_FATAL(LOGGER, "Could not find planner plugin names"); try { planner_plugin_loader.reset(new pluginlib::ClassLoader( @@ -110,9 +110,11 @@ int main(int argc, char** argv) { RCLCPP_FATAL(LOGGER, "Exception while creating planning plugin loader %s", ex.what()); } + + const auto& planner_name = planner_plugin_names.at(0); try { - planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); + planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_name)); if (!planner_instance->initialize(robot_model, motion_planning_api_tutorial_node, motion_planning_api_tutorial_node->get_namespace())) RCLCPP_FATAL(LOGGER, "Could not initialize planner instance"); @@ -124,7 +126,7 @@ int main(int argc, char** argv) std::stringstream ss; for (const auto& cls : classes) ss << cls << " "; - RCLCPP_ERROR(LOGGER, "Exception while loading planner '%s': %s\nAvailable plugins: %s", planner_plugin_name.c_str(), + RCLCPP_ERROR(LOGGER, "Exception while loading planner '%s': %s\nAvailable plugins: %s", planner_name.c_str(), ex.what(), ss.str().c_str()); } @@ -166,14 +168,14 @@ int main(int argc, char** argv) geometry_msgs::msg::PoseStamped pose; pose.header.frame_id = "panda_link0"; pose.pose.position.x = 0.3; - pose.pose.position.y = 0.4; + pose.pose.position.y = 0.0; pose.pose.position.z = 0.75; - pose.pose.orientation.w = 1.0; + pose.pose.orientation.z = 1.0; - // A tolerance of 0.01 m is specified in position - // and 0.01 radians in orientation - std::vector tolerance_pose(3, 0.01); - std::vector tolerance_angle(3, 0.01); + // A tolerance of 0.1 m is specified in position + // and 0.1 radians in orientation + std::vector tolerance_pose(3, 0.1); + std::vector tolerance_angle(3, 0.1); // We will create the request as a constraint using a helper function available // from the @@ -185,16 +187,28 @@ int main(int argc, char** argv) req.group_name = PLANNING_GROUP; req.goal_constraints.push_back(pose_goal); + // Define workspace bounds + req.workspace_parameters.min_corner.x = req.workspace_parameters.min_corner.y = + req.workspace_parameters.min_corner.z = -5.0; + req.workspace_parameters.max_corner.x = req.workspace_parameters.max_corner.y = + req.workspace_parameters.max_corner.z = 5.0; + // We now construct a planning context that encapsulate the scene, // the request and the response. We call the planner using this // planning context planning_interface::PlanningContextPtr context = planner_instance->getPlanningContext(planning_scene, req, res.error_code); + + if (!context) + { + RCLCPP_ERROR(LOGGER, "Failed to create planning context"); + return -1; + } context->solve(res); if (res.error_code.val != res.error_code.SUCCESS) { RCLCPP_ERROR(LOGGER, "Could not compute plan successfully"); - return 0; + return -1; } // Visualize the result @@ -246,7 +260,7 @@ int main(int argc, char** argv) if (res.error_code.val != res.error_code.SUCCESS) { RCLCPP_ERROR(LOGGER, "Could not compute plan successfully"); - return 0; + return -1; } /* Visualize the trajectory */ res.getMessage(response); diff --git a/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp b/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp index e13600cb53..61259cff64 100644 --- a/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp +++ b/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp @@ -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"; diff --git a/doc/examples/moveit_cpp/config/moveit_cpp.yaml b/doc/examples/moveit_cpp/config/moveit_cpp.yaml index ffa333f8a4..0dbd6f88ee 100644 --- a/doc/examples/moveit_cpp/config/moveit_cpp.yaml +++ b/doc/examples/moveit_cpp/config/moveit_cpp.yaml @@ -14,5 +14,6 @@ planning_pipelines: plan_request_params: planning_attempts: 1 planning_pipeline: ompl + planner_id: "RRTConnectkConfigDefault" max_velocity_scaling_factor: 1.0 max_acceleration_scaling_factor: 1.0 diff --git a/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py b/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py index b1ea4678f2..4e1a9143c2 100644 --- a/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py +++ b/doc/examples/moveit_cpp/launch/moveit_cpp_tutorial.launch.py @@ -11,6 +11,7 @@ def generate_launch_description(): MoveItConfigsBuilder("moveit_resources_panda") .robot_description(file_path="config/panda.urdf.xacro") .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") + .planning_pipelines("ompl", ["ompl"]) .moveit_cpp( file_path=get_package_share_directory("moveit2_tutorials") + "/config/moveit_cpp.yaml" diff --git a/doc/examples/planning_adapters/planning_adapters_tutorial.rst b/doc/examples/planning_adapters/planning_adapters_tutorial.rst index ef8cde65e9..49db9f9ca1 100644 --- a/doc/examples/planning_adapters/planning_adapters_tutorial.rst +++ b/doc/examples/planning_adapters/planning_adapters_tutorial.rst @@ -6,7 +6,7 @@ Planning Adapter Tutorials ========================== -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. +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. Getting Started --------------- @@ -46,11 +46,10 @@ To achieve this, follow the steps: #. Open the ``ompl_planning_pipeline.launch`` file in the ``/launch`` folder of your robot. For the Panda robot it is this `file `_. Edit this launch file, find the lines where ```` 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: #. Open the ``stomp_planning_pipeline.launch`` file in the ``/launch`` folder of your robot. For the Panda robot it is `this `_ file. Edit this launch file, find the lines where ```` 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: #. Open the ``ompl_planning_pipeline.launch`` file in the ``/launch`` folder of your robot. For the Panda robot it is this `file `_. Edit this launch file, find the lines where ```` 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. diff --git a/doc/examples/subframes/subframes_tutorial.rst b/doc/examples/subframes/subframes_tutorial.rst index b62a5ee259..5afd044d8e 100644 --- a/doc/examples/subframes/subframes_tutorial.rst +++ b/doc/examples/subframes/subframes_tutorial.rst @@ -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 ``/launch`` folder of your robot. For the Panda robot it is :panda_codedir:`this ` file. -Edit this launch file, find the lines where ```` 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 ```` is mentioned and insert ``default_planning_request_adapters/ResolveConstraintFrames`` after +the line ``default_planning_request_adapters/FixStartStatePathConstraints``. diff --git a/doc/examples/time_parameterization/time_parameterization_tutorial.rst b/doc/examples/time_parameterization/time_parameterization_tutorial.rst index 418c1e26c7..cab3d7a5b2 100644 --- a/doc/examples/time_parameterization/time_parameterization_tutorial.rst +++ b/doc/examples/time_parameterization/time_parameterization_tutorial.rst @@ -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 ... diff --git a/doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py b/doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py index ebf3d07ffe..739b51d1d9 100644 --- a/doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py +++ b/doc/how_to_guides/benchmarking/launch/run_benchmarks.launch.py @@ -46,15 +46,20 @@ def generate_launch_description(): # Load additional OMPL pipeline 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, + "planning_plugins": [ + "ompl_interface/OMPLPlanner", + ], + "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( diff --git a/doc/how_to_guides/chomp_planner/chomp_planner_tutorial.rst b/doc/how_to_guides/chomp_planner/chomp_planner_tutorial.rst index 9c401b427a..4baa791e0d 100644 --- a/doc/how_to_guides/chomp_planner/chomp_planner_tutorial.rst +++ b/doc/how_to_guides/chomp_planner/chomp_planner_tutorial.rst @@ -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 ----------------------------------------- -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 ``/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, ``/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 diff --git a/doc/how_to_guides/parallel_planning/launch/parallel_planning_example.launch.py b/doc/how_to_guides/parallel_planning/launch/parallel_planning_example.launch.py index b7362d3ee7..7e84fa8f73 100644 --- a/doc/how_to_guides/parallel_planning/launch/parallel_planning_example.launch.py +++ b/doc/how_to_guides/parallel_planning/launch/parallel_planning_example.launch.py @@ -57,15 +57,20 @@ def launch_setup(context, *args, **kwargs): # Load additional OMPL pipeline 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, + "planning_plugins": [ + "ompl_interface/OMPLPlanner", + ], + "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( diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst index 3a20e20a73..5535a2af3b 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst +++ b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst @@ -299,7 +299,7 @@ Using the planner The *pilz_industrial_motion_planner::CommandPlanner* is provided as a MoveIt Motion Planning Pipeline and, therefore, can be used with all other manipulators using MoveIt. Loading the plugin requires the param -``/move_group//planning_plugin`` to be set to ``pilz_industrial_motion_planner/CommandPlanner`` +``/move_group//planning_plugins`` to be set to ``[pilz_industrial_motion_planner/CommandPlanner]`` before the ``move_group`` node is started. For example, the `panda_moveit_config package `_ @@ -308,7 +308,7 @@ has a ``pilz_industrial_motion_planner`` pipeline set up as follows: :: - ros2 param get /move_group pilz_industrial_motion_planner.planning_plugin + ros2 param get /move_group pilz_industrial_motion_planner.planning_plugins String value is: pilz_industrial_motion_planner/CommandPlanner diff --git a/doc/how_to_guides/stomp_planner/stomp_planner.rst b/doc/how_to_guides/stomp_planner/stomp_planner.rst index f99c31cfc8..e97299b692 100644 --- a/doc/how_to_guides/stomp_planner/stomp_planner.rst +++ b/doc/how_to_guides/stomp_planner/stomp_planner.rst @@ -31,13 +31,17 @@ Using STOMP with Your Robot #. Simply add the `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 + planning_plugins: + - stomp_moveit/StompPlanner + 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 @@ -51,24 +55,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 `_ 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 `_ repository you should be able to simply launch the demo setup and start planning with STOMP in RViZ ::