From b351e8abbb98c96d882cd198b35aad59dd7707ee Mon Sep 17 00:00:00 2001 From: Rick Staa <rick.staa@outlook.com> Date: Wed, 13 Oct 2021 20:41:52 +0200 Subject: [PATCH] Add LERP config files Adds files needed to run the [lerp_planning_example](https://ros-planning.github.io/moveit_tutorials/doc/creating_moveit_plugins/plugin_tutorial.html) --- config/lerp_planning.yaml | 1 + launch/demo_lerp.launch | 6 ++++++ launch/lerp_planning_pipeline.launch.xml | 22 ++++++++++++++++++++++ 3 files changed, 29 insertions(+) create mode 100644 config/lerp_planning.yaml create mode 100644 launch/demo_lerp.launch create mode 100644 launch/lerp_planning_pipeline.launch.xml diff --git a/config/lerp_planning.yaml b/config/lerp_planning.yaml new file mode 100644 index 0000000..9d2eebd --- /dev/null +++ b/config/lerp_planning.yaml @@ -0,0 +1 @@ +num_steps: 40 diff --git a/launch/demo_lerp.launch b/launch/demo_lerp.launch new file mode 100644 index 0000000..d5d8355 --- /dev/null +++ b/launch/demo_lerp.launch @@ -0,0 +1,6 @@ + +<launch> + <include file="$(dirname)/demo.launch"> + <arg name="pipeline" value="lerp"/> + </include> +</launch> \ No newline at end of file diff --git a/launch/lerp_planning_pipeline.launch.xml b/launch/lerp_planning_pipeline.launch.xml new file mode 100644 index 0000000..c119357 --- /dev/null +++ b/launch/lerp_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ +<launch> + + <!-- LERP Plugin for MoveIt! --> + <arg name="planning_plugin" value="lerp_interface/LERPPlanner" /> + + <!-- The request adapters (plugins) used when planning with TrajOpt. + ORDER MATTERS --> + <arg name="planning_adapters" value="default_planner_request_adapters/AddTimeParameterization + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints" /> + + <arg name="start_state_max_bounds_error" value="0.1" /> + + <param name="planning_plugin" value="$(arg planning_plugin)" /> + <param name="request_adapters" value="$(arg planning_adapters)" /> + <param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" /> + + <rosparam command="load" file="$(find panda_moveit_config)/config/lerp_planning.yaml"/> + +</launch> -- GitLab