From 4efd960cc9e2d3d5a0550e55ef3277fef93524c4 Mon Sep 17 00:00:00 2001
From: Omid Heidari <omid.github@gmail.com>
Date: Tue, 13 Aug 2019 12:52:34 -0600
Subject: [PATCH] Necessary files to run LERP (#40)

* added new files for emptyplan

* edited demo.launch to accept planner arg

* Added emptyplan_planning.yaml so it can be used for new planners. It is an empty file.
Added rosparam in emptyplan_planning_pipeline.launch.xml to load its yaml file

* added necessary files for LERP

* chaged the virtual joint to fixed

* added yaml file

* addressed the comments

* revet back to floating for virtual joint and revert moveit.rviz
---
 config/lerp_planning.yaml                |  1 +
 launch/lerp_planning_pipeline.launch.xml | 22 ++++++++++++++++++++++
 2 files changed, 23 insertions(+)
 create mode 100644 config/lerp_planning.yaml
 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/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