diff --git a/test/grasp_from_side_test.cpp b/test/grasp_from_side_test.cpp
index 2efce1e594650cbb2419ffb2b044debef6f3782c..be86834da795ed0893341a99d0dfc54dd7d97d84 100644
--- a/test/grasp_from_side_test.cpp
+++ b/test/grasp_from_side_test.cpp
@@ -32,7 +32,7 @@ protected:
         ros::NodeHandle n("panda_grasping");
 
         gripper_orientation.setRPY(0, 0, -M_PI_4);
-        place_pose.position.z = 0.4 + 0.1 + 0.01; // table height + object height / 2 + buffer
+        place_pose.position.z = 0.4 + 0.05; // table height + object height / 2 + buffer
         place_orientation.setRPY(0, 0, M_PI / 2);
 
         CleanupScene();
@@ -88,10 +88,11 @@ protected:
         collision_objects[2].id = "object";
 
         collision_objects[2].primitives.resize(1);
-        collision_objects[2].primitives[0].type = collision_objects[1].primitives[0].CYLINDER;
-        collision_objects[2].primitives[0].dimensions.resize(2);
-        collision_objects[2].primitives[0].dimensions[0] = 0.2;
-        collision_objects[2].primitives[0].dimensions[1] = 0.008;
+        collision_objects[2].primitives[0].type = collision_objects[1].primitives[0].BOX;
+        collision_objects[2].primitives[0].dimensions.resize(3);
+        collision_objects[2].primitives[0].dimensions[0] = 0.05;
+        collision_objects[2].primitives[0].dimensions[1] = 0.05;
+        collision_objects[2].primitives[0].dimensions[2] = 0.1;
         collision_objects[2].primitive_poses.resize(1);
         collision_objects[2].primitive_poses[0] = obj_pose;
         collision_objects[2].operation = collision_objects[2].ADD;
@@ -140,7 +141,7 @@ TEST_F(Grasping, SIDE_GRASPING_1) {
 
     obj_pose.position.x = 0.5;
     obj_pose.position.y = -0.5;
-    obj_pose.position.z = 0.5;
+    obj_pose.position.z = 0.45;
     obj_pose.orientation.w = 1.0;
 
 
@@ -172,7 +173,7 @@ TEST_F(Grasping, SIDE_GRASPING_2) {
 
     obj_pose.position.x = -0.5;
     obj_pose.position.y = -0.5;
-    obj_pose.position.z = 0.5;
+    obj_pose.position.z = 0.45;
     obj_pose.orientation.w = 1.0;
 
     place_pose.orientation = tf2::toMsg(place_orientation);
@@ -203,7 +204,7 @@ TEST_F(Grasping, SIDE_GRASPING_3) {
 
     obj_pose.position.x = 0.5;
     obj_pose.position.y = 0.5;
-    obj_pose.position.z = 0.5;
+    obj_pose.position.z = 0.45;
     obj_pose.orientation.w = 1.0;
 
     place_pose.orientation = tf2::toMsg(place_orientation);
@@ -234,7 +235,7 @@ TEST_F(Grasping, SIDE_GRASPING_4) {
 
     obj_pose.position.x = 0.5;
     obj_pose.position.y = -0.5;
-    obj_pose.position.z = 0.5;
+    obj_pose.position.z = 0.45;
     obj_pose.orientation.w = 1.0;
 
     place_pose.orientation = tf2::toMsg(place_orientation);