From 6a216a42efd4aac49e0070c12160d7cfdf05713d Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Wed, 1 Apr 2020 09:17:31 +0200
Subject: [PATCH] fix box name

---
 src/SafetyZones/GazeboZoneSpawner.cpp | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/src/SafetyZones/GazeboZoneSpawner.cpp b/src/SafetyZones/GazeboZoneSpawner.cpp
index 268fe5e..f9e98a1 100644
--- a/src/SafetyZones/GazeboZoneSpawner.cpp
+++ b/src/SafetyZones/GazeboZoneSpawner.cpp
@@ -46,14 +46,14 @@ void GazeboZoneSpawner::spawnCollisionBox(shape_msgs::SolidPrimitive shape, geom
   gazebo_msgs::SpawnModel spawnService;
   spawnService.request.robot_namespace = "box space";
   // spawnModelService.request.initial_pose = pose; // not required here
-  spawnService.request.model_name = sdf->Root()->GetElement("model")->GetAttribute("name")->GetAsString();
+  spawnService.request.model_name = std::string("box") + poseStream.str() + sizeStream.str();
   spawnService.request.model_xml = sdf->ToString().c_str();
   // spawnModelService.request.reference_frame = ; // if left empty, world is used
   if (client.call(spawnService)) {
     if ( spawnService.response.success) {
-      ROS_INFO_NAMED("GazeboZoneSpawner", "Successfully spawned Box. %s", spawnService.response.status_message.c_str());
+      ROS_INFO_NAMED("GazeboZoneSpawner", "Successfully spawned Box 's'.  %s", spawnService.request.model_name, spawnService.response.status_message.c_str());
     } else {
-      ROS_INFO_NAMED("GazeboZoneSpawner", "Failed to spawn Box. %s", spawnService.response.status_message.c_str());
+      ROS_INFO_NAMED("GazeboZoneSpawner", "Failed to spawn Box '%s'. %s", spawnService.request.model_name, spawnService.response.status_message.c_str());
     }
   } else {
     ROS_ERROR_NAMED("GazeboZoneSpawner", "Failed to call service '/gazebo/spawn_sdf_model'");
-- 
GitLab