From 3becee28e68a830784392b84d102fc1b2ab43467 Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Thu, 30 Apr 2020 10:43:17 +0200
Subject: [PATCH] Adapted to store signals as pointers

---
 include/adc_circuit.h                   |  2 +-
 include/adc_road.h                      |  6 ++---
 include/open_drive_format.h             |  2 +-
 src/adc_circuit.cpp                     |  4 ++--
 src/adc_road.cpp                        | 29 +++++++++++++++----------
 src/examples/open_drive_format_test.cpp |  4 ++--
 src/open_drive_format.cpp               |  4 ++--
 7 files changed, 29 insertions(+), 22 deletions(-)

diff --git a/include/adc_circuit.h b/include/adc_circuit.h
index d6eafd2..2ee5c3d 100644
--- a/include/adc_circuit.h
+++ b/include/adc_circuit.h
@@ -74,7 +74,7 @@ class CAdcCircuit
      *
      * \param signals Variable to store the information.
      */
-    void get_signals(std::vector<CAdcSignals> &signals);
+    void get_signals(std::vector<CAdcSignals*> &signals);
 
     /**
      * \brief Function to generate a .launch to spwan all
diff --git a/include/adc_road.h b/include/adc_road.h
index 74a2652..9c1dc9a 100644
--- a/include/adc_road.h
+++ b/include/adc_road.h
@@ -22,7 +22,7 @@ class CAdcRoad
     std::string name; ///< Road's name.
     double length;///< Road's length.
     std::vector<CAdcGeometry*> geometries;///< Road's geometries.
-    std::vector<CAdcSignals> signals; ///< Road's signals.
+    std::vector<CAdcSignals*> signals; ///< Road's signals.
 
   public:
     /**
@@ -87,7 +87,7 @@ class CAdcRoad
      * \param sign The road's sign to add.
      *
      */
-    void add_signal(CAdcSignals sign);
+    void add_signal(CAdcSignals* sign);
 
     /**
      * \brief Function to set road's id.
@@ -146,7 +146,7 @@ class CAdcRoad
      *
      * \param signals Variable to store the information.
      */
-    void get_signals(std::vector<CAdcSignals> &signals);
+    void get_signals(std::vector<CAdcSignals*> &signals);
 
     /**
      * \brief Function to append each sign spwan lines on a .launch file.
diff --git a/include/open_drive_format.h b/include/open_drive_format.h
index fb8c0a9..9ebf5ad 100644
--- a/include/open_drive_format.h
+++ b/include/open_drive_format.h
@@ -53,7 +53,7 @@ class COpenDriveFormat
      * \param signals Variable to store the information.
      *
      */
-    void get_signals(std::vector<CAdcSignals> &signals);
+    void get_signals(std::vector<CAdcSignals*> &signals);
 
     /**
      * \brief Function to generate a .launch to spwan all
diff --git a/src/adc_circuit.cpp b/src/adc_circuit.cpp
index 02054fc..21efc1a 100644
--- a/src/adc_circuit.cpp
+++ b/src/adc_circuit.cpp
@@ -36,9 +36,9 @@ void CAdcCircuit::calculate_signals_pose(bool debug)
     this->roads[i].calculate_signals_pose(debug);
 }
 
-void CAdcCircuit::get_signals(std::vector<CAdcSignals> &signals)
+void CAdcCircuit::get_signals(std::vector<CAdcSignals*> &signals)
 {
-  std::vector<CAdcSignals>().swap(signals);
+  std::vector<CAdcSignals*>().swap(signals);
   for (unsigned int i = 0; i < this->roads.size(); i++)
     this->roads[i].get_signals(signals);
 }
diff --git a/src/adc_road.cpp b/src/adc_road.cpp
index 65639a1..db5ba8e 100644
--- a/src/adc_road.cpp
+++ b/src/adc_road.cpp
@@ -22,7 +22,8 @@ CAdcRoad::CAdcRoad(const CAdcRoad &road)
   this->length = road.length;
   this->name = road.name;
   clear_signals();
-  this->signals = road.signals;
+  for (unsigned int i = 0; i < road.signals.size(); i++)
+    this->signals.push_back(new CAdcSignals(*road.signals[i]));
   clear_geometries();
   for (unsigned int i = 0; i < road.geometries.size(); i++)
     this->geometries.push_back(road.geometries[i]->clone());
@@ -42,8 +43,12 @@ void CAdcRoad::operator = (const CAdcRoad &road)
   this->id = road.id;
   this->length = road.length;
   this->name = road.name;
-  this->signals = road.signals;
-  this->geometries = road.geometries;
+  clear_signals();
+  for (unsigned int i = 0; i < road.signals.size(); i++)
+    this->signals.push_back(new CAdcSignals(*road.signals[i]));
+  clear_geometries();
+  for (unsigned int i = 0; i < road.geometries.size(); i++)
+    this->geometries.push_back(road.geometries[i]->clone());
 }
 
 void CAdcRoad::clear_geometries(void)
@@ -60,10 +65,12 @@ void CAdcRoad::add_geometry(CAdcGeometry* geometry)
 
 void CAdcRoad::clear_signals(void)
 {
-  std::vector<CAdcSignals>().swap(this->signals);
+  for (unsigned int i = 0; i < this->signals.size(); i++)
+    delete this->signals[i];
+  std::vector<CAdcSignals*>().swap(this->signals);
 }
 
-void CAdcRoad::add_signal(CAdcSignals sign)
+void CAdcRoad::add_signal(CAdcSignals* sign)
 {
   this->signals.push_back(sign);
 }
@@ -94,7 +101,7 @@ void CAdcRoad::debug(void)
   for (unsigned int i = 0; i < this->geometries.size(); i++)
     this->geometries[i]->debug();
   for (unsigned int i = 0; i < this->signals.size(); i++)
-    this->signals[i].debug();
+    this->signals[i]->debug();
 }
 
 void CAdcRoad::calculate_signals_pose(bool debug)
@@ -102,25 +109,25 @@ void CAdcRoad::calculate_signals_pose(bool debug)
   double s, t, heading, x, y, yaw;
   for (unsigned int i = 0; i < this->signals.size(); i++)
   {
-    this->signals[i].get_pose(s, t, heading);
+    this->signals[i]->get_pose(s, t, heading);
     for (unsigned int j = 0; j < this->geometries.size(); j++)
     {
       if (this->geometries[j]->on_range(s))
       {
         this->geometries[j]->get_world_pose(s, t, heading, x, y, yaw);
-        this->signals[i].set_world_pose(x, y, yaw);
+        this->signals[i]->set_world_pose(x, y, yaw);
         break;
       }
     }
     if (debug)
     {
       std::cout << "Road " << this->name << " id = " << this->id << "; length = " << this->length << std::endl;
-      this->signals[i].debug(debug);
+      this->signals[i]->debug(debug);
     }
   }
 }
 
-void CAdcRoad::get_signals(std::vector<CAdcSignals> &signals)
+void CAdcRoad::get_signals(std::vector<CAdcSignals*> &signals)
 {
   for (unsigned int i = 0; i < this->signals.size(); i++)
     signals.push_back(this->signals[i]);
@@ -129,5 +136,5 @@ void CAdcRoad::get_signals(std::vector<CAdcSignals> &signals)
 void CAdcRoad::append_signs_spawn(std::string &filename)
 {
   for (unsigned int i = 0; i < this->signals.size(); i++)
-    this->signals[i].append_sign_spawn(filename);
+    this->signals[i]->append_sign_spawn(filename);
 }
\ No newline at end of file
diff --git a/src/examples/open_drive_format_test.cpp b/src/examples/open_drive_format_test.cpp
index 704c105..2cde0f8 100644
--- a/src/examples/open_drive_format_test.cpp
+++ b/src/examples/open_drive_format_test.cpp
@@ -15,10 +15,10 @@ int main(int argc, char *argv[])
     open_drive_format.load(xml_file, false);
     open_drive_format.calculate_signals_pose(false);
 
-    std::vector<CAdcSignals> signals;
+    std::vector<CAdcSignals*> signals;
     // open_drive_format.get_signals(signals);
     // for (unsigned int i = 0; i < signals.size(); i++)
-    //   signals[i].debug(true);
+    //   signals[i]->debug(true);
     open_drive_format.generate_spwan_launch_file(launch_file);
   }
   catch (CException &e)
diff --git a/src/open_drive_format.cpp b/src/open_drive_format.cpp
index 2e28718..4664f5e 100644
--- a/src/open_drive_format.cpp
+++ b/src/open_drive_format.cpp
@@ -117,7 +117,7 @@ void COpenDriveFormat::load(std::string &filename, bool debug)
             bool reverse = false;
             if (signal_it->orientation().present() && signal_it->orientation().get() == orientation::cxx_1)
               reverse = true;
-            CAdcSignals sign(id, s, t, heading, type, sub_type, value, text, reverse);
+            CAdcSignals *sign = new CAdcSignals(id, s, t, heading, type, sub_type, value, text, reverse);
             road.add_signal(sign);
           }
         }
@@ -145,7 +145,7 @@ void COpenDriveFormat::calculate_signals_pose(bool debug)
   std::cout << "Calculating world signs poses done" << std::endl;
 }
 
-void COpenDriveFormat::get_signals(std::vector<CAdcSignals> &signals)
+void COpenDriveFormat::get_signals(std::vector<CAdcSignals*> &signals)
 {
   this->adc_circuit.get_signals(signals);
 }
-- 
GitLab