From a6933601ca5e967c3608cfe9050bac4767eaf7b3 Mon Sep 17 00:00:00 2001
From: SebastianEbert <sebastian.ebert@tu-dresden.de>
Date: Fri, 31 Jul 2020 13:34:44 +0200
Subject: [PATCH] updated repo to work with new workspace configuration

---
 CMakeLists.txt                |  2 ++
 launch/sample_grasp.launch    | 13 +++++++++++++
 src/pick_and_place_sample.cpp |  5 +----
 3 files changed, 16 insertions(+), 4 deletions(-)
 create mode 100644 launch/sample_grasp.launch

diff --git a/CMakeLists.txt b/CMakeLists.txt
index d6d5ca2..c08734b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -52,9 +52,11 @@ add_library(EnvironmentUtil src/grasping/environment_util.cpp src/grasping/envir
 add_library(GraspUtil src/grasping/grasp_util.cpp src/grasping/grasp_util.h)
 
 add_executable(grasp_service src/grasping/grasp_service.cpp)
+add_executable(pick_and_place_sample src/pick_and_place_sample.cpp)
 
 target_link_libraries(EnvironmentUtil ${catkin_LIBRARIES})
 target_link_libraries(GraspUtil ${catkin_LIBRARIES})
+target_link_libraries(pick_and_place_sample ${catkin_LIBRARIES})
 target_link_libraries(grasp_service ${catkin_LIBRARIES} EnvironmentUtil GraspUtil)
 
 add_dependencies(grasp_service panda_grasping_generate_messages_cpp)
diff --git a/launch/sample_grasp.launch b/launch/sample_grasp.launch
new file mode 100644
index 0000000..5ec2d7a
--- /dev/null
+++ b/launch/sample_grasp.launch
@@ -0,0 +1,13 @@
+<launch>
+    <include file="$(find panda_simulation)/launch/simulation.launch"/>
+
+    <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
+    <!--<node name="rqt_console" pkg="rqt_console" type="rqt_console" />-->
+
+    <node pkg="panda_grasping" type="pick_and_place_sample" name="pick_and_place_sample" output="screen" />
+
+    <!-- sample commands -->
+    <!-- rosservice call panda_grasping/PickObjectService '{pose: {position: {x: 0.5, y: 0.0, z: 0.2}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}}, dimensions: {x: 0.02, y: 0.02, z: 0.2}}' -->
+    <!-- rosservice call panda_grasping/PlaceObjectService '{pose: {position: {x: 0.0, y: 0.5, z: 0.2}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}}, dimensions: {x: 0.02, y: 0.02, z: 0.2}}' -->
+
+</launch>
diff --git a/src/pick_and_place_sample.cpp b/src/pick_and_place_sample.cpp
index 39b0ce9..64f3cf4 100644
--- a/src/pick_and_place_sample.cpp
+++ b/src/pick_and_place_sample.cpp
@@ -96,7 +96,7 @@ void pick(moveit::planning_interface::MoveGroupInterface& move_group)
     /* Defined with respect to frame_id */
     grasps[0].pre_grasp_approach.direction.header.frame_id = "panda_link0";
     /* Direction is set as positive x axis */
-    grasps[0].pre_grasp_approach.direction.vector.x = 1.0;
+    grasps[0].pre_grasp_approach.direction.vector.z = -1.0;
     grasps[0].pre_grasp_approach.min_distance = 0.095;
     grasps[0].pre_grasp_approach.desired_distance = 0.115;
 
@@ -319,9 +319,6 @@ int main(int argc, char** argv)
 
     place(group);
 
-    //std::vector<std::string>objectsToRemove{"object"};
-    //planning_scene_interface.removeCollisionObjects(objectsToRemove);
-
     ros::waitForShutdown();
     return 0;
 }
\ No newline at end of file
-- 
GitLab