diff --git a/gazebo_grasp_plugin/src/GazeboGraspFix.cpp b/gazebo_grasp_plugin/src/GazeboGraspFix.cpp
index c990fdaaedb11c309f9f7883852b5db7e36a52e7..b268cfacfcf00ef383414e1b1e6f146bf2214141 100644
--- a/gazebo_grasp_plugin/src/GazeboGraspFix.cpp
+++ b/gazebo_grasp_plugin/src/GazeboGraspFix.cpp
@@ -92,7 +92,10 @@ void GazeboGraspFix::InitValues(){
 }
 
 
-void GazeboGraspFix::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
+void GazeboGraspFix::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
+{
+    std::cout<<"Loading grasp-fix plugin"<<std::endl;
+
     this->model = _parent;
     this->world = this->model->GetWorld();
     this->physics = this->model->GetWorld()->GetPhysicsEngine();
diff --git a/gazebo_test_tools/src/cube_spawner_node.cpp b/gazebo_test_tools/src/cube_spawner_node.cpp
index 3cd7c91c033ff9a6ddb868595cc6e1ebe44fd4c2..59d716e744178b628bd65989017f780453340efb 100644
--- a/gazebo_test_tools/src/cube_spawner_node.cpp
+++ b/gazebo_test_tools/src/cube_spawner_node.cpp
@@ -6,7 +6,7 @@ int main(int argc, char** argv) {
 
     if (argc < 5)
     {
-        ROS_INFO("Usage: %s <name> [x y z].",argv[0]);
+        ROS_INFO("Usage: %s <name> [x y z] [frame_id].",argv[0]);
         return 0;
     }
 
@@ -22,11 +22,14 @@ int main(int argc, char** argv) {
     float y=0;
     float z=0;
 
+    std::string frame_id="world";
     if (argc>2) x=atof(argv[2]);
     if (argc>3) y=atof(argv[3]);
     if (argc>4) z=atof(argv[4]);
-    
-    spawner.spawnCube(name,"world",x,y,z,0,0,0,1);
+    if (argc>5) frame_id=argv[5];
+   
+
+    spawner.spawnCube(name,frame_id,x,y,z,0,0,0,1);
     
     return 0;
 }