diff --git a/include/adc_circuit.h b/include/adc_circuit.h
index a17de92b432f4bb1ec79507cbfd105471d9e90e3..63ecdf6535ef92de857786c2829e307f95e30555 100644
--- a/include/adc_circuit.h
+++ b/include/adc_circuit.h
@@ -11,6 +11,9 @@
 #include "../src/xml/OpenDRIVE_1.4H.hxx"
 #endif
 
+#define SIGNS_LAUNCH_FILE "spawn_signs.launch"
+#define OBJECTS_LAUNCH_FILE "spawn_objects.launch"
+
 /**
  * \class CAdcCircuit
  *
@@ -82,17 +85,20 @@ class CAdcCircuit
 
     /**
      * \brief Function to generate a .launch to spwan all
-     * the recognized signs.
+     * the recognized signs and another for the objects.
      *
      * First it saves the header of the file. Secondly it
      * calls CAdcRoad::append_signs_spwan. Finally, it saves
      * the end of the launch file.
      *
-     * \param filename The route to the output .launch file.
+     * It follows the same steps to generate the objects launch file
+     * calling CAdcRoad::append_objects_spwan.
+     *
+     * \param dir The route to the output .launch file.
      *
      * \throws CException If the output file can't be opened.
      */
-    void generate_spwan_launch_file(std::string &filename);
+    void generate_spawn_launch_files(std::string &dir);
 
     /**
      * \brief Function to load the .xodr info.
diff --git a/include/adc_object.h b/include/adc_object.h
index aa4e9bab5a13f66985e63f74be388c0776875da2..f73774e205ff07d14eb2d4e158a301bd10264517 100644
--- a/include/adc_object.h
+++ b/include/adc_object.h
@@ -268,7 +268,7 @@ class CAdcObject
      * \param filename The route to the output .launch file.
      *
      */
-    void append_object_spawn(std::string &filename);
+    void append_objects_spawn(std::string &filename);
 
     /**
      * \brief Function to load the .xodr info.
diff --git a/include/adc_road.h b/include/adc_road.h
index a5b691b01c855293d994227dc0431b60eaaff3ac..b0cf8a66701137f0b78e506f9f7d95eac79de695 100644
--- a/include/adc_road.h
+++ b/include/adc_road.h
@@ -189,6 +189,16 @@ class CAdcRoad
      */
     void append_signs_spawn(std::string &filename);
 
+    /**
+     * \brief Function to append each object spwan lines on a .launch file.
+     *
+     * It calls CAdcObject::append_objects_spawn function.
+     *
+     * \param filename The route to the output .launch file.
+     *
+     */
+    void append_objects_spawn(std::string &filename);
+
     /**
      * \brief Function to load the .xodr info.
      *
diff --git a/include/opendrive_to_gazebo.h b/include/opendrive_to_gazebo.h
index 68f3727116e97dce184bc78db12c7cb1bfabd0a4..a7f108c8b5a4ce44a6e49fdca828fe9379c2ddad 100644
--- a/include/opendrive_to_gazebo.h
+++ b/include/opendrive_to_gazebo.h
@@ -57,14 +57,14 @@ class COpenDriveFormat
 
     /**
      * \brief Function to generate a .launch to spwan all
-     * the recognized signs.
+     * the recognized signs and another for the objects.
      *
-     * It calls CAdcCircuit::generate_spwan_launch_file function.
+     * It calls CAdcCircuit::generate_spawn_launch_files function.
      *
-     * \param filename The route to the output .launch file.
+     * \param dir The route to the output launch directory.
      *
      */
-    void generate_spwan_launch_file(std::string &filename);
+    void generate_spawn_launch_files(std::string &dir);
 
     /**
      * \brief Default destructor.
diff --git a/src/adc_circuit.cpp b/src/adc_circuit.cpp
index 380c83e923146c32dff2cd6f456350456d3590c4..aa320b392ab8df6ac9460d4b858e21e5f9d2224c 100644
--- a/src/adc_circuit.cpp
+++ b/src/adc_circuit.cpp
@@ -48,35 +48,57 @@ void CAdcCircuit::get_signals(std::vector<CAdcSignals*> &signals)
     this->roads[i]->get_signals(signals);
 }
 
-void CAdcCircuit::generate_spwan_launch_file(std::string &filename)
+void CAdcCircuit::generate_spawn_launch_files(std::string &dir)
 {
-  std::remove(filename.c_str());
+  std::string signs_filename = dir + SIGNS_LAUNCH_FILE;
+  std::string objects_filename = dir + OBJECTS_LAUNCH_FILE;
+
+  std::remove(signs_filename.c_str());
+  std::remove(objects_filename.c_str());
   //First the header
   std::ostringstream oss;
   oss << "<?xml version=\"1.0\"?>" << std::endl << std::endl;
   oss << "<launch>" << std::endl;
   oss << "  <arg name=\"parent\" default=\"map\"/>" << std::endl;
 
-  std::ofstream out_file;
-  out_file.open(filename.c_str(), std::ios_base::app);
-  if (!out_file.is_open())
-    throw CException(_HERE_,"CAdcCircuit::generate_spwan_launch_file -> The output file can't be open");
-  out_file << oss.str() << std::endl;
-  out_file.close();
+  std::ofstream signs_out_file;
+  signs_out_file.open(signs_filename.c_str(), std::ios_base::app);
+  if (!signs_out_file.is_open())
+    throw CException(_HERE_,"CAdcCircuit::generate_spawn_launch_file -> The sings output file can't be open");
+  signs_out_file << oss.str() << std::endl;
+  signs_out_file.close();
+
+  std::ofstream objects_out_file;
+  objects_out_file.open(objects_filename.c_str(), std::ios_base::app);
+  if (!objects_out_file.is_open())
+    throw CException(_HERE_,"CAdcCircuit::generate_spawn_launch_file -> The objects output file can't be open");
+  objects_out_file << oss.str() << std::endl;
+  objects_out_file.close();
 
   //sign info
   for (unsigned int i = 0; i < this->roads.size(); i++)
-    this->roads[i]->append_signs_spawn(filename);
+    this->roads[i]->append_signs_spawn(signs_filename);
+
+  //object info
+  for (unsigned int i = 0; i < this->roads.size(); i++)
+    this->roads[i]->append_objects_spawn(objects_filename);
 
   //End
   oss.str("");
   oss.clear();
   oss << std::endl << "</launch>" << std::endl;
-  out_file.open(filename.c_str(), std::ios_base::app);
-  if (!out_file.is_open())
-    throw CException(_HERE_,"CAdcCircuit::generate_spwan_launch_file -> The output file can't be open");
-  out_file << oss.str() << std::endl;
-  out_file.close();
+
+  signs_out_file.open(signs_filename.c_str(), std::ios_base::app);
+  if (!signs_out_file.is_open())
+    throw CException(_HERE_,"CAdcCircuit::generate_spwan_launch_file -> The signs output file can't be open");
+  signs_out_file << oss.str() << std::endl;
+  signs_out_file.close();
+
+  objects_out_file.open(objects_filename.c_str(), std::ios_base::app);
+  if (!objects_out_file.is_open())
+    throw CException(_HERE_,"CAdcCircuit::generate_spwan_launch_file -> The objects output file can't be open");
+  objects_out_file << oss.str() << std::endl;
+  objects_out_file.close();
 }
 
 void CAdcCircuit::load(std::auto_ptr<OpenDRIVE> &open_drive)
diff --git a/src/adc_object.cpp b/src/adc_object.cpp
index 41601e44891f4f38997b11ca055c8b028717aea8..12bbb0b04d1667c3940bb0883e7b7677c0555948 100644
--- a/src/adc_object.cpp
+++ b/src/adc_object.cpp
@@ -280,9 +280,39 @@ void CAdcObject::debug(bool world_pose)
   }
 }
 
-void CAdcObject::append_object_spawn(std::string &filename)
+void CAdcObject::append_objects_spawn(std::string &filename)
 {
+  if (this->repeat || this->outline)
+  {
+    std::cout << "WARNING: Outline and repeat objects not supported" << std::endl;
+    return;
+  }
+  std::ostringstream oss;
+  oss << std::endl << "  <include file=\"$(find iri_object_description)/launch/spawn_object.launch\">" << std::endl;
+  oss << "    <arg name=\"name\"  value=\"" << this->name << this->id << "\"/>" << std::endl;
+  oss << "    <arg name=\"model\"  value=\"" << (this->radius != 0.0 ? "cyl": "box") << "\"/>" << std::endl;
+
+  if (this->radius != 0.0)
+    oss << "    <arg name=\"radius\"  value=\"" << this->radius << "\"/>" << std::endl;
+  else
+  {
+    oss << "    <arg name=\"length\"  value=\"" << this->length << "\"/>" << std::endl;
+    oss << "    <arg name=\"width\"  value=\"" << this->width << "\"/>" << std::endl;    
+  }
+
+  oss << "    <arg name=\"height\"  value=\"" << this->height << "\"/>" << std::endl;
+  oss << "    <arg name=\"x\"  value=\"" << this->world_x << "\"/>" << std::endl;
+  oss << "    <arg name=\"y\"  value=\"" << this->world_y << "\"/>" << std::endl;
+  oss << "    <arg name=\"yaw\"  value=\"" << this->world_yaw << "\"/>" << std::endl;
+  oss << "    <arg name=\"parent\"  value=\"$(arg parent)\"/>" << std::endl;
 
+  oss << "  </include>" << std::endl;
+  std::ofstream out_file;
+  out_file.open(filename.c_str(), std::ios_base::app);
+  if (!out_file.is_open())
+    throw CException(_HERE_,"CAdcObject::append_objects_spawn -> The output file can't be open");
+  out_file << oss.str() << std::endl;
+  out_file.close();
 }
 
 void CAdcObject::load(std::auto_ptr<objects::object_type> &object_info)
diff --git a/src/adc_road.cpp b/src/adc_road.cpp
index 4e1130106b5cf94deaeaf46b20e42142012d8292..18bed174f256829f259cd25ba7a5c3854d36fbdb 100644
--- a/src/adc_road.cpp
+++ b/src/adc_road.cpp
@@ -221,6 +221,12 @@ void CAdcRoad::append_signs_spawn(std::string &filename)
     this->signals[i]->append_sign_spawn(filename);
 }
 
+void CAdcRoad::append_objects_spawn(std::string &filename)
+{
+  for (unsigned int i = 0; i < this->objects.size(); i++)
+    this->objects[i]->append_objects_spawn(filename);
+}
+
 void CAdcRoad::load(std::auto_ptr<OpenDRIVE::road_type> &road_info)
 {
   std::stringstream ss(road_info->id().get());
diff --git a/src/adc_signals.cpp b/src/adc_signals.cpp
index 898db52df4a58973a768bc7ee7d79d3c9473538a..0e7f176590b00487fd05b61d53d33309930cad0c 100644
--- a/src/adc_signals.cpp
+++ b/src/adc_signals.cpp
@@ -212,7 +212,7 @@ void CAdcSignals::append_sign_spawn(std::string &filename)
   std::ofstream out_file;
   out_file.open(filename.c_str(), std::ios_base::app);
   if (!out_file.is_open())
-    throw CException(_HERE_,"CAdcCircuit::generate_spwan_launch_file -> The output file can't be open");
+    throw CException(_HERE_,"CAdcSignals::append_sign_spawn -> The output file can't be open");
   out_file << oss.str() << std::endl;
   out_file.close();
 }
diff --git a/src/examples/opendrive_to_gazebo_test.cpp b/src/examples/opendrive_to_gazebo_test.cpp
index beca6fef3702bf84dbad5d1d19f18480d37e882c..ceb67157d8205306d2ebe3e7a769716570a24dac 100644
--- a/src/examples/opendrive_to_gazebo_test.cpp
+++ b/src/examples/opendrive_to_gazebo_test.cpp
@@ -8,7 +8,7 @@ int main(int argc, char *argv[])
 {
   COpenDriveFormat open_drive_format;
   std::string xml_file = "../src/xml/atlatec_generic.xodr";
-  std::string launch_file = "../spawn_signs.launch";
+  std::string launch_dir = "../../../../iri_ws/src/model_car_simulator/sign_description/launch/";
   // std::string xml_file = "../src/xml/atlatec_vires.xodr";
   try
   {
@@ -19,7 +19,7 @@ int main(int argc, char *argv[])
     // open_drive_format.get_signals(signals);
     // for (unsigned int i = 0; i < signals.size(); i++)
     //   signals[i]->debug(true);
-    open_drive_format.generate_spwan_launch_file(launch_file);
+    open_drive_format.generate_spawn_launch_files(launch_dir);
   }
   catch (CException &e)
   {
diff --git a/src/opendrive_to_gazebo.cpp b/src/opendrive_to_gazebo.cpp
index 3ca162b7e61d6b77e250d09a877707ba0449f80b..5ddf4768243b04a586283e12358e50d6993d4e52 100644
--- a/src/opendrive_to_gazebo.cpp
+++ b/src/opendrive_to_gazebo.cpp
@@ -60,11 +60,11 @@ void COpenDriveFormat::get_signals(std::vector<CAdcSignals*> &signals)
   this->adc_circuit.get_signals(signals);
 }
 
-void COpenDriveFormat::generate_spwan_launch_file(std::string &filename)
+void COpenDriveFormat::generate_spawn_launch_files(std::string &dir)
 {
-  std::cout << "Generating " << filename << " ..." << std::endl;
-  this->adc_circuit.generate_spwan_launch_file(filename);
-  std::cout << "Generating " << filename << " done" << std::endl;
+  std::cout << "Generating spawn files ..." << std::endl;
+  this->adc_circuit.generate_spawn_launch_files(dir);
+  std::cout << "Done" << std::endl;
 }
 
 COpenDriveFormat::~COpenDriveFormat()