diff --git a/src/SafetyZones/GazeboZoneSpawner.cpp b/src/SafetyZones/GazeboZoneSpawner.cpp
index f9e98a11cc6f54fa9d7d45eda4d4739ef53704cd..3102ce426d379e2ef1f9c3f86623fc0460e4dbc7 100644
--- a/src/SafetyZones/GazeboZoneSpawner.cpp
+++ b/src/SafetyZones/GazeboZoneSpawner.cpp
@@ -51,9 +51,9 @@ void GazeboZoneSpawner::spawnCollisionBox(shape_msgs::SolidPrimitive shape, geom
   // 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'.  %s", spawnService.request.model_name, spawnService.response.status_message.c_str());
+      ROS_INFO_NAMED("GazeboZoneSpawner", "Successfully spawned Box 's'.  %s", spawnService.request.model_name.c_str(), spawnService.response.status_message.c_str());
     } else {
-      ROS_INFO_NAMED("GazeboZoneSpawner", "Failed to spawn Box '%s'. %s", spawnService.request.model_name, spawnService.response.status_message.c_str());
+      ROS_INFO_NAMED("GazeboZoneSpawner", "Failed to spawn Box '%s'. %s", spawnService.request.model_name.c_str(), spawnService.response.status_message.c_str());
     }
   } else {
     ROS_ERROR_NAMED("GazeboZoneSpawner", "Failed to call service '/gazebo/spawn_sdf_model'");