diff --git a/src/grasping/environment_util.cpp b/src/grasping/environment_util.cpp
index a54405a2d139cab1d3805aa7b32641107c119e95..b838534bca48859e7f9dd0e05d4d5def842af94d 100644
--- a/src/grasping/environment_util.cpp
+++ b/src/grasping/environment_util.cpp
@@ -13,7 +13,7 @@ void EnvironmentUtil::constructPlate(std::vector<moveit_msgs::CollisionObject> &
     plate.id = "plate";
 
     plate.primitives.resize(1);
-    plate.primitives[0].type = 1u;
+    plate.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
     plate.primitives[0].dimensions.resize(3);
     plate.primitives[0].dimensions[0] = x_dimension;
     plate.primitives[0].dimensions[1] = y_dimension;
@@ -39,7 +39,7 @@ void EnvironmentUtil::constructSupport(std::vector<moveit_msgs::CollisionObject>
     pick_support.id = id;
 
     pick_support.primitives.resize(1);
-    pick_support.primitives[0].type = 1u;
+    pick_support.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
     pick_support.primitives[0].dimensions.resize(3);
     pick_support.primitives[0].dimensions[0] = object_x_dimension;
     pick_support.primitives[0].dimensions[1] = object_y_dimension;
@@ -64,7 +64,7 @@ moveit_msgs::CollisionObject EnvironmentUtil::constructObjectToPick(std::vector<
     object_to_pick.id = id;
 
     object_to_pick.primitives.resize(1);
-    object_to_pick.primitives[0].type = object_to_pick.primitives[0].BOX;
+    object_to_pick.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
     object_to_pick.primitives[0].dimensions.resize(3);
     object_to_pick.primitives[0].dimensions[0] = dimensions.x;
     object_to_pick.primitives[0].dimensions[1] = dimensions.y;