From f97145f5ac62987888b7dee1c9b258f5a4cb1700 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 13 Apr 2020 16:14:50 +0200
Subject: [PATCH] Changed the CrazyflieData message to be called
 FlyingVehicleData and changed the names of its properties from occluded to
 isValid and from crazyflieName to vehicleName

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         |  2 +-
 .../forms/enablecontrollerloadyamlbar.ui      | 28 +++++------
 .../flyingAgentGUI/include/controllertabs.h   |  4 +-
 .../include/csonecontrollertab.h              |  2 +-
 .../include/defaultcontrollertab.h            |  2 +-
 .../include/pickercontrollertab.h             |  2 +-
 .../include/remotecontrollertab.h             |  8 ++--
 .../rosNodeThread_for_flyingAgentGUI.h        |  2 +-
 .../include/studentcontrollertab.h            |  2 +-
 .../include/templatecontrollertab.h           |  2 +-
 .../include/tuningcontrollertab.h             |  2 +-
 .../flyingAgentGUI/src/controllertabs.cpp     |  8 ++--
 .../flyingAgentGUI/src/csonecontrollertab.cpp | 12 ++---
 .../src/defaultcontrollertab.cpp              |  9 ++--
 .../src/pickercontrollertab.cpp               |  7 +--
 .../src/remotecontrollertab.cpp               | 44 ++++++------------
 .../src/studentcontrollertab.cpp              |  9 ++--
 .../src/templatecontrollertab.cpp             |  9 ++--
 .../src/tuningcontrollertab.cpp               |  7 +--
 .../GUI_Qt/systemConfigGUI/include/crazyFly.h |  6 +--
 .../rosNodeThread_for_systemConfigGUI.h       |  2 +-
 .../GUI_Qt/systemConfigGUI/src/crazyFly.cpp   |  8 ++--
 .../systemConfigGUI/src/mainguiwindow.cpp     |  7 ++-
 .../include/classes/QuadrotorSimulator.h      | 37 ++++++++++-----
 .../include/nodes/DemoControllerService.h     | 15 ------
 .../include/nodes/FlyingAgentClient.h         |  8 ++--
 .../dfall_pkg/include/nodes/MocapEmulator.h   |  2 +-
 .../include/nodes/RemoteControllerService.h   | 17 -------
 .../include/nodes/SafeControllerService.h     |  4 +-
 .../include/nodes/TuningControllerService.h   | 17 -------
 .../src/dfall_pkg/msg/CrazyflieContext.msg    |  2 +-
 ...azyflieData.msg => FlyingVehicleState.msg} |  4 +-
 .../src/dfall_pkg/msg/GyroMeasurements.msg    |  2 +-
 dfall_ws/src/dfall_pkg/msg/ViconData.msg      |  5 +-
 .../src/classes/QuadrotorSimulator.cpp        | 46 +++++++++++++++----
 .../src/nodes/CsoneControllerService.cpp      | 12 ++---
 .../src/nodes/DefaultControllerService.cpp    | 19 --------
 .../src/nodes/DemoControllerService.cpp       | 12 ++---
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp | 22 ++++-----
 .../src/dfall_pkg/src/nodes/MocapEmulator.cpp | 14 +++---
 .../src/nodes/MpcControllerService.cpp        | 26 +++--------
 .../src/nodes/PickerControllerService.cpp     | 12 ++---
 .../src/nodes/RemoteControllerService.cpp     | 28 +++++------
 .../src/nodes/StudentControllerService.cpp    | 12 ++---
 .../src/nodes/TemplateControllerService.cpp   | 12 ++---
 .../src/nodes/TestMotorsControllerService.cpp | 12 ++---
 .../src/nodes/TuningControllerService.cpp     | 12 ++---
 .../src/nodes/ViconDataPublisher.cpp          | 18 ++++----
 .../src/qualisys/QualisysDataPublisher.py     | 14 +++---
 .../dfall_pkg/srv/CMQueryCrazyflieName.srv    |  3 +-
 dfall_ws/src/dfall_pkg/srv/Controller.srv     |  6 +--
 51 files changed, 261 insertions(+), 316 deletions(-)
 rename dfall_ws/src/dfall_pkg/msg/{CrazyflieData.msg => FlyingVehicleState.msg} (74%)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index df3c30f9..6542cb7f 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -250,7 +250,7 @@ endif()
 add_message_files(
   FILES
   UnlabeledMarker.msg
-  CrazyflieData.msg
+  FlyingVehicleState.msg
   ViconData.msg
   ControlCommand.msg
   CrazyflieContext.msg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index f52ce5f9..9a431b5b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -239,7 +239,7 @@
          </widget>
         </item>
         <item>
-         <widget class="QPushButton" name="load_yaml_template_button">
+         <widget class="QPushButton" name="load_yaml_remote_button">
           <property name="sizePolicy">
            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
             <horstretch>0</horstretch>
@@ -259,12 +259,12 @@
            </size>
           </property>
           <property name="text">
-           <string>Template</string>
+           <string>Remote</string>
           </property>
          </widget>
         </item>
         <item>
-         <widget class="QPushButton" name="load_yaml_remote_button">
+         <widget class="QPushButton" name="load_yaml_template_button">
           <property name="sizePolicy">
            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
             <horstretch>0</horstretch>
@@ -284,7 +284,7 @@
            </size>
           </property>
           <property name="text">
-           <string>Remote</string>
+           <string>Template</string>
           </property>
          </widget>
         </item>
@@ -463,7 +463,7 @@
          </widget>
         </item>
         <item>
-         <widget class="QPushButton" name="enable_template_button">
+         <widget class="QPushButton" name="enable_remote_button">
           <property name="sizePolicy">
            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
             <horstretch>0</horstretch>
@@ -482,19 +482,13 @@
             <height>50</height>
            </size>
           </property>
-          <property name="font">
-           <font>
-            <weight>50</weight>
-            <bold>false</bold>
-           </font>
-          </property>
           <property name="text">
-           <string>Template</string>
+           <string>Remote</string>
           </property>
          </widget>
         </item>
         <item>
-         <widget class="QPushButton" name="enable_remote_button">
+         <widget class="QPushButton" name="enable_template_button">
           <property name="sizePolicy">
            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
             <horstretch>0</horstretch>
@@ -513,8 +507,14 @@
             <height>50</height>
            </size>
           </property>
+          <property name="font">
+           <font>
+            <weight>50</weight>
+            <bold>false</bold>
+           </font>
+          </property>
           <property name="text">
-           <string>Remote</string>
+           <string>Template</string>
           </property>
          </widget>
         </item>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 08df7f2a..ec3e39c1 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -57,7 +57,7 @@
 // Include the DFALL message types
 //#include "dfall_pkg/IntWithHeader.h"
 //#include "dfall_pkg/SetpointWithHeader.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/ViconData.h"
 #include "dfall_pkg/AreaBounds.h"
 #include "dfall_pkg/CrazyflieContext.h"
@@ -108,7 +108,7 @@ public slots:
 
 signals:
     void agentIDsToCoordinateChanged(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void measuredPoseValueChanged(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void measuredPoseValueChanged(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSignal();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h
index 5ba4e055..9bdef6b6 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/csonecontrollertab.h
@@ -114,7 +114,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 64f315c4..c462a1b1 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -89,7 +89,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 52b79e13..12270b72 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -117,7 +117,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/remotecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/remotecontrollertab.h
index 60d50bc2..1738a169 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/remotecontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/remotecontrollertab.h
@@ -56,7 +56,7 @@
 //#include "dfall_pkg/IntWithHeader.h"
 #include "dfall_pkg/SetpointWithHeader.h"
 #include "dfall_pkg/CustomButtonWithHeader.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/ViconSubscribeObjectName.h"
 
 // Include the DFALL service types
@@ -94,7 +94,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
@@ -176,8 +176,8 @@ private:
 
     // COPIED FROM PREVIOUS REMOTE CONTROLLER GUI
     // For receiving message with the data of the remote
-    void remoteDataCallback(const dfall_pkg::CrazyflieData& objectData);
-    void remoteControlSetpointCallback(const dfall_pkg::CrazyflieData& setpointData);
+    void remoteDataCallback(const dfall_pkg::FlyingVehicleState& objectData);
+    void remoteControlSetpointCallback(const dfall_pkg::FlyingVehicleState& setpointData);
 
 
     // For receiving message that the setpoint was changed
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
index 79c447e8..bd16b604 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
@@ -52,7 +52,7 @@
 #include "dfall_pkg/CMCommand.h"
 
 //#include "dfall_pkg/UnlabeledMarker.h"
-//#include "dfall_pkg/CrazyflieData.h"
+//#include "dfall_pkg/FlyingVehicleState.h"
 //#include "dfall_pkg/ViconData.h"
 
 using namespace dfall_pkg;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index be7ed5f4..587290b0 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -90,7 +90,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
index 0f9377bb..119c326f 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
@@ -92,7 +92,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index cf8ecf05..d680c50c 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -112,7 +112,7 @@ public:
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
-    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid);
     void poseDataUnavailableSlot();
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index c29d10d6..fe2cf599 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -368,11 +368,11 @@ void ControllerTabs::poseDataReceivedCallback(const dfall_pkg::ViconData& viconD
     m_should_search_pose_data_for_object_name_mutex.lock();
     if (m_should_search_pose_data_for_object_name)
     {
-        for(std::vector<dfall_pkg::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
+        for(std::vector<dfall_pkg::FlyingVehicleState>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
         {
-            dfall_pkg::CrazyflieData pose_in_global_frame = *it;
+            dfall_pkg::FlyingVehicleState pose_in_global_frame = *it;
 
-            if(pose_in_global_frame.crazyflieName == m_object_name_for_emitting_pose_data)
+            if(pose_in_global_frame.vehicleName == m_object_name_for_emitting_pose_data)
             {
 
                 // Convert it into the local frame
@@ -394,7 +394,7 @@ void ControllerTabs::poseDataReceivedCallback(const dfall_pkg::ViconData& viconD
                         pose_in_global_frame.roll,
                         pose_in_global_frame.pitch,
                         pose_in_global_frame.yaw,
-                        pose_in_global_frame.occluded
+                        pose_in_global_frame.isValid
                     );
             }
         }
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp
index 401093fb..37b30105 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/csonecontrollertab.cpp
@@ -43,7 +43,7 @@ CsoneControllerTab::CsoneControllerTab(QWidget *parent) :
     ui->setupUi(this);
 
     // Hide the two red frames that are used to indcated
-    // when pose data is occluded
+    // when pose data is NOT valid
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
@@ -632,10 +632,9 @@ void CsoneControllerTab::on_lineEdit_step_duration_editingFinished()
 //    ----------------------------------------------------------------------------------
 
 
-void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    // Check if the object is occluded for this data
-    if (!occluded)
+    if (isValid)
     {
         // Ensure the red frames are not visible
         if ( ui->red_frame_position_left->isVisible() )
@@ -645,7 +644,8 @@ void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float rol
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_position_left->isVisible()) )
             ui->red_frame_position_left->setVisible(true);
         if ( !(ui->red_frame_position_right->isVisible()) )
@@ -653,7 +653,7 @@ void CsoneControllerTab::setMeasuredPose(float x , float y , float z , float rol
     }
 
     // Pass the data through to the plotting function
-    if (!occluded)
+    if (isValid)
     {
         newDataForPerformingStepAndPlotting(x,pitch*RAD2DEG);
     }
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 7904b231..171f3803 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -43,7 +43,7 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     ui->setupUi(this);
 
     // Hide the two red frames that are used to indcated
-    // when pose data is occluded
+    // when pose data is NOT valid
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
@@ -126,9 +126,9 @@ DefaultControllerTab::~DefaultControllerTab()
 //    ----------------------------------------------------------------------------------
 
 
-void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
         QString qstr = "";
@@ -173,7 +173,8 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_position_left->isVisible()) )
             ui->red_frame_position_left->setVisible(true);
         if ( !(ui->red_frame_position_right->isVisible()) )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index 0375c8f6..bba7f61d 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -537,9 +537,9 @@ void PickerControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithH
 //    ----------------------------------------------------------------------------------
 
 
-void PickerControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void PickerControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
         QString qstr = "";
@@ -583,7 +583,8 @@ void PickerControllerTab::setMeasuredPose(float x , float y , float z , float ro
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->frame_x_unavailable->isVisible()) )
         {
             ui->frame_x_unavailable  ->setVisible(true);
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/remotecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/remotecontrollertab.cpp
index 38385a27..56d2dc98 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/remotecontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/remotecontrollertab.cpp
@@ -43,7 +43,7 @@ RemoteControllerTab::RemoteControllerTab(QWidget *parent) :
     ui->setupUi(this);
 
     // Hide the two red frames that are used to indcated
-    // when pose data is occluded
+    // when pose data is NOT valid
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
@@ -209,25 +209,17 @@ void RemoteControllerTab::on_deactivate_button_clicked()
 
 
 #ifdef CATKIN_MAKE
-void RemoteControllerTab::remoteDataCallback(const dfall_pkg::CrazyflieData& objectData)
+void RemoteControllerTab::remoteDataCallback(const dfall_pkg::FlyingVehicleState& objectData)
 {
-    // Check if the object is occluded
-    if (objectData.occluded)
+    // Check if the object date isValid
+    if (!objectData.isValid)
     {
-
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_remote->isVisible()) )
+        {
             ui->red_frame_remote->setVisible(true);
-
-//        // Set the column heading label to have a red background
-//        // > IMPORTANT: Set the background auto fill property to true
-//        ui->remote_data_label->setAutoFillBackground(true);
-//        // > Get the pallette currently set for the label
-//        QPalette pal = ui->remote_roll_label->palette();
-//        // > Set the palette property that will change the background
-//        pal.setColor(QPalette::Window, QColor(Qt::red));
-//        // > Update the palette for the label
-//        ui->remote_data_label->setPalette(pal);
+        }
     }
     else
     {
@@ -237,25 +229,18 @@ void RemoteControllerTab::remoteDataCallback(const dfall_pkg::CrazyflieData& obj
         ui->remote_data_yaw  ->setText(QString::number( objectData.yaw   * RAD2DEG, 'f', 1));
         ui->remote_data_z    ->setText(QString::number( objectData.z,               'f', 2));
 
-
         // Ensure the red frames are not visible
         if ( ui->red_frame_remote->isVisible() )
+        {
             ui->red_frame_remote->setVisible(false);
-
-//        // Set the column heading label to have a "normal" background
-//        // > IMPORTANT: Set the background auto fill property to true
-//        ui->remote_data_label->setAutoFillBackground(false);
-//        // > Get the pallette currently set for the roll label
-//        QPalette pal = ui->remote_roll_label->palette();
-//        // > Update the palette for the column heading label
-//        ui->remote_data_label->setPalette(pal);
+        }
     }
 }
 #endif
 
 
 #ifdef CATKIN_MAKE
-void RemoteControllerTab::remoteControlSetpointCallback(const dfall_pkg::CrazyflieData& setpointData)
+void RemoteControllerTab::remoteControlSetpointCallback(const dfall_pkg::FlyingVehicleState& setpointData)
 {
     ui->remote_setpoint_roll ->setText(QString::number( setpointData.roll  * RAD2DEG, 'f', 1));
     ui->remote_setpoint_pitch->setText(QString::number( setpointData.pitch * RAD2DEG, 'f', 1));
@@ -308,9 +293,9 @@ void RemoteControllerTab::publish_custom_button_command(int button_index , QLine
 //    ----------------------------------------------------------------------------------
 
 
-void RemoteControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void RemoteControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
         QString qstr = "";
@@ -337,7 +322,8 @@ void RemoteControllerTab::setMeasuredPose(float x , float y , float z , float ro
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_position_left->isVisible()) )
             ui->red_frame_position_left->setVisible(true);
         if ( !(ui->red_frame_position_right->isVisible()) )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index 64207a97..6896bd79 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -43,7 +43,7 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
     ui->setupUi(this);
 
     // Hide the two red frames that are used to indcated
-    // when pose data is occluded
+    // when pose data is NOT valid
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
@@ -205,9 +205,9 @@ void StudentControllerTab::on_custom_button_5_clicked()
 //    ----------------------------------------------------------------------------------
 
 
-void StudentControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void StudentControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
         QString qstr = "";
@@ -252,7 +252,8 @@ void StudentControllerTab::setMeasuredPose(float x , float y , float z , float r
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_position_left->isVisible()) )
             ui->red_frame_position_left->setVisible(true);
         if ( !(ui->red_frame_position_right->isVisible()) )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
index 24f9fb07..0d963a49 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
@@ -43,7 +43,7 @@ TemplateControllerTab::TemplateControllerTab(QWidget *parent) :
     ui->setupUi(this);
 
     // Hide the two red frames that are used to indcated
-    // when pose data is occluded
+    // when pose data is NOT valide
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
@@ -191,9 +191,9 @@ void TemplateControllerTab::on_custom_button_3_clicked()
 //    ----------------------------------------------------------------------------------
 
 
-void TemplateControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void TemplateControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
         QString qstr = "";
@@ -220,7 +220,8 @@ void TemplateControllerTab::setMeasuredPose(float x , float y , float z , float
     }
     else
     {
-        // Make visible the red frames to indicate occluded
+        // Make visible the red frames to indicate that
+        // measurement is NOT valid
         if ( !(ui->red_frame_position_left->isVisible()) )
             ui->red_frame_position_left->setVisible(true);
         if ( !(ui->red_frame_position_right->isVisible()) )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index f6578b32..04f58ca4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -139,9 +139,9 @@ TuningControllerTab::~TuningControllerTab()
 //    ----------------------------------------------------------------------------------
 
 
-void TuningControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+void TuningControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
 {
-    if (!occluded)
+    if (isValid)
     {
         m_gain_setpoint_mutex.lock();
 
@@ -203,7 +203,8 @@ void TuningControllerTab::setMeasuredPose(float x , float y , float z , float ro
     }
     else
     {
-//        // Make visible the red frames to indicate occluded
+//        // Make visible the red frames to indicate that
+//        // measurement is NOT valid
 //        if ( !(ui->red_frame_position_left->isVisible()) )
 //            ui->red_frame_position_left->setVisible(true);
 //        if ( !(ui->red_frame_position_right->isVisible()) )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h
index d26b198c..008ce939 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h
@@ -41,7 +41,7 @@
 
 #ifdef CATKIN_MAKE
 // Include the Crazyflie Data Struct
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 // Include other classes
 #include "classes/GetParamtersAndNamespaces.h"
 #else
@@ -63,7 +63,7 @@ using namespace dfall_pkg;
 class crazyFly : public QGraphicsSvgItem
 {
 public:
-    explicit crazyFly(const CrazyflieData* p_crazyfly_msg, QString filename, QGraphicsItem * parent = 0);
+    explicit crazyFly(const FlyingVehicleState* p_crazyfly_msg, QString filename, QGraphicsItem * parent = 0);
     ~crazyFly();
     QRectF boundingRect() const;
 
@@ -71,7 +71,7 @@ public:
                const QStyleOptionGraphicsItem * option,
                QWidget * widget);
 
-    void updateCF(const CrazyflieData* p_crazyfly_msg);
+    void updateCF(const FlyingVehicleState* p_crazyfly_msg);
 
     std::string getName();
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h
index 1a4f037c..e74a75eb 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h
@@ -44,7 +44,7 @@
 #include <ros/ros.h>
 #include <ros/network.h>
 #include "dfall_pkg/UnlabeledMarker.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/ViconData.h"
 
 using namespace dfall_pkg;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp
index 5bea8cf6..417019b3 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp
@@ -36,7 +36,7 @@
 #include <QBrush>
 
 
-crazyFly::crazyFly(const CrazyflieData* p_crazyfly_msg, QString filename, QGraphicsItem * parent)
+crazyFly::crazyFly(const FlyingVehicleState* p_crazyfly_msg, QString filename, QGraphicsItem * parent)
     : QGraphicsSvgItem(filename)
 {
     updateCF(p_crazyfly_msg);
@@ -83,11 +83,11 @@ std::string crazyFly::getName()
 }
 
 
-void crazyFly::updateCF(const CrazyflieData* p_crazyfly_msg)
+void crazyFly::updateCF(const FlyingVehicleState* p_crazyfly_msg)
 {
-    m_occluded = p_crazyfly_msg->occluded;
+    m_occluded = !(p_crazyfly_msg->isValid);
 
-    m_name = p_crazyfly_msg->crazyflieName;
+    m_name = p_crazyfly_msg->vehicleName;
     if(!m_occluded)             //if it is occluded, the info we got is useless
     {
         m_x = p_crazyfly_msg->x;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp
index a93637d1..6e249d79 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp
@@ -417,7 +417,7 @@ void MainGUIWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to
         int index_name_found;
         for(int j = 0; j < crazyfly_vector_size_before; j++)
         {
-            if(crazyflies_vector[j]->getName() == p_msg->crazyflies[i].crazyflieName)
+            if(crazyflies_vector[j]->getName() == p_msg->crazyflies[i].vehicleName)
             {
                 name_found = true; // name found. This can only happen once per i-iteration, names are unique
                 index_name_found = j; // index in already existing vector, to update it later (really needed?)
@@ -431,7 +431,7 @@ void MainGUIWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to
         else                    //name not found, newly arrived, add it to the vector
         {
             // now, if name follows our format, put the corresponding number. If not, put the unknown image
-            std::string s = p_msg->crazyflies[i].crazyflieName;
+            std::string s = p_msg->crazyflies[i].vehicleName;
             std::smatch m;
             std::regex e ("CF([0-9]{2})");
 
@@ -473,7 +473,6 @@ void MainGUIWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to
             {
                 if(crazyflies_vector[i]->isOccluded())
                 {
-                    // ROS_INFO("===================OCCLUDED");
                     if(crazyflies_vector[i]->isAddedToScene())
                     {
                         scene->removeItem(crazyflies_vector[i]);
@@ -500,7 +499,7 @@ void MainGUIWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to
         bool name_found = false;
         for(int i = 0; i < p_msg->crazyflies.size(); i++)
         {
-            if(crazyflies_vector[j]->getName() == p_msg->crazyflies[i].crazyflieName)
+            if(crazyflies_vector[j]->getName() == p_msg->crazyflies[i].vehicleName)
             {
                 name_found = true;
             }
diff --git a/dfall_ws/src/dfall_pkg/include/classes/QuadrotorSimulator.h b/dfall_ws/src/dfall_pkg/include/classes/QuadrotorSimulator.h
index b520e0f0..ec1bc998 100644
--- a/dfall_ws/src/dfall_pkg/include/classes/QuadrotorSimulator.h
+++ b/dfall_ws/src/dfall_pkg/include/classes/QuadrotorSimulator.h
@@ -111,6 +111,15 @@ public:
 
 public:
 
+	// The current state
+	std::vector<float> m_position          = {0.0,0.0,0.0};
+	std::vector<float> m_velocity          = {0.0,0.0,0.0};
+	std::vector<float> m_euler_angles      = {0.0,0.0,0.0};
+	std::vector<float> m_euler_velocities  = {0.0,0.0,0.0};
+
+
+private:
+
 	// Identifier String
 	std::string m_id_string = "none";
 
@@ -120,16 +129,6 @@ public:
 	// Mass of the quadrotor [kilograms]
 	float m_mass_in_kg = 0.032;
 
-	// The current state
-	std::vector<float> m_position          = {0.0,0.0,0.0};
-	std::vector<float> m_velocity          = {0.0,0.0,0.0};
-	std::vector<float> m_euler_angles      = {0.0,0.0,0.0};
-	std::vector<float> m_euler_velocities  = {0.0,0.0,0.0};
-
-
-
-private:
-	
 	// The flying state
 	bool m_isFlying = false;
 
@@ -194,6 +193,21 @@ private:
 
 public:
 
+	// Function to get the ID as a string
+	std::string get_id_string();
+
+	// Function to set the ID as a string
+	void set_id_string(std::string new_id_string);
+
+	// Function to get the mass in kilograms
+	float get_mass_in_kg();
+
+	// Function to set the mass in kilograms
+	void set_mass_in_kg(float new_mass_in_kg);
+
+	// Function to get the flying state
+	bool get_isFlying();
+
 	// Function to simulate the quadrotor for one time step
 	void simulate_for_one_time_step(float deltaT);
 
@@ -203,8 +217,7 @@ public:
 	// Function to update the commanding agent id
 	void update_commanding_agent_id( int new_commanding_agent_id );
 
-	// Function to get the flying state
-	bool getIsFlying();
+	
 
 	// Function to set the reset state
 	void setResetState_xyz_yaw(float x, float y, float z, float yaw);
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h
index 111c7e47..a4791592 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h
@@ -378,21 +378,6 @@ ros::Publisher my_current_xyz_yaw_publisher;
 ros::Subscriber xyz_yaw_to_follow_subscriber;
 
 
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
-
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 61b6d330..de922337 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -55,7 +55,7 @@
 // Include the DFALL message types
 #include "dfall_pkg/IntWithHeader.h"
 #include "dfall_pkg/ViconData.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/ControlCommand.h"
 #include "dfall_pkg/CrazyflieContext.h"
 #include "dfall_pkg/Setpoint.h"
@@ -276,10 +276,10 @@ ros::Publisher m_controllerUsedPublisher;
 void viconCallback(const ViconData& viconData);
 // > For extracting the pose data of an specific
 //   object by name
-int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index ,CrazyflieData& pose);
+int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index ,FlyingVehicleState& pose);
 // > For converting the global frame motion capture
 //   data to the local frame of this agent
-void coordinatesToLocal(CrazyflieData& cf);
+void coordinatesToLocal(FlyingVehicleState& cf);
 // > Callback run when motion capture data has not
 //   been receive for a specified time
 void timerCallback_mocap_timeout_check(const ros::TimerEvent&);
@@ -290,7 +290,7 @@ void sendZeroOutputCommandForMotors();
 
 
 // FOR THE SAFETY CHECKS ON POSITION AND TILT ANGLE
-bool safetyCheck_on_positionAndTilt(CrazyflieData data);
+bool safetyCheck_on_positionAndTilt(FlyingVehicleState data);
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/MocapEmulator.h b/dfall_ws/src/dfall_pkg/include/nodes/MocapEmulator.h
index ec94b908..bfa09a73 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/MocapEmulator.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/MocapEmulator.h
@@ -55,7 +55,7 @@
 // Include the DFALL message types
 #include "dfall_pkg/IntWithHeader.h"
 #include "dfall_pkg/ViconData.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/ControlCommand.h"
 #include "dfall_pkg/CrazyflieContext.h"
 #include "dfall_pkg/AreaBounds.h"
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h
index 4fc07894..75b3273b 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h
@@ -378,23 +378,6 @@ int m_coordID;
 
 
 
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
-
-
-
 
 //    ----------------------------------------------------------------------------------
 //    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h
index f7c666e3..2fa26a99 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h
@@ -56,7 +56,7 @@
 
 // Include the DFALL message types
 #include "dfall_pkg/IntWithHeader.h"
-#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/FlyingVehicleState.h"
 #include "dfall_pkg/Setpoint.h"
 #include "dfall_pkg/ControlCommand.h"
 #include "dfall_pkg/Controller.h"
@@ -155,7 +155,7 @@ std::vector<float>  setpoint(4);
 std::vector<float> defaultSetpoint(4);
 float saturationThrust;
 
-CrazyflieData previousLocation;
+FlyingVehicleState previousLocation;
 
 
 // Variable for the namespaces for the paramter services
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
index b3b7b064..cff8cd0c 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
@@ -416,23 +416,6 @@ int m_coordID;
 
 
 
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
-
-
-
 
 //    ----------------------------------------------------------------------------------
 //    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
diff --git a/dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg b/dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg
index 31427567..95974964 100755
--- a/dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg
+++ b/dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg
@@ -1,3 +1,3 @@
 string crazyflieName
 string crazyflieAddress
-AreaBounds localArea
+AreaBounds localArea
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/CrazyflieData.msg b/dfall_ws/src/dfall_pkg/msg/FlyingVehicleState.msg
similarity index 74%
rename from dfall_ws/src/dfall_pkg/msg/CrazyflieData.msg
rename to dfall_ws/src/dfall_pkg/msg/FlyingVehicleState.msg
index 91ddb357..e5c00c0a 100644
--- a/dfall_ws/src/dfall_pkg/msg/CrazyflieData.msg
+++ b/dfall_ws/src/dfall_pkg/msg/FlyingVehicleState.msg
@@ -1,4 +1,4 @@
-string crazyflieName
+string vehicleName
 float64 x
 float64 y
 float64 z
@@ -6,4 +6,4 @@ float64 roll
 float64 pitch
 float64 yaw
 float64 acquiringTime #delta t
-bool occluded
+bool isValid
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/GyroMeasurements.msg b/dfall_ws/src/dfall_pkg/msg/GyroMeasurements.msg
index 48e5c3df..79ec2739 100644
--- a/dfall_ws/src/dfall_pkg/msg/GyroMeasurements.msg
+++ b/dfall_ws/src/dfall_pkg/msg/GyroMeasurements.msg
@@ -1,4 +1,4 @@
-string crazyflieName
+string vehicleName
 float64 rollrate
 float64 pitchrate
 float64 yawrate
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/ViconData.msg b/dfall_ws/src/dfall_pkg/msg/ViconData.msg
index c263cdf9..ae818655 100755
--- a/dfall_ws/src/dfall_pkg/msg/ViconData.msg
+++ b/dfall_ws/src/dfall_pkg/msg/ViconData.msg
@@ -1,3 +1,2 @@
-CrazyflieData[] crazyflies
-UnlabeledMarker[] markers
-
+FlyingVehicleState[] crazyflies
+UnlabeledMarker[] markers
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/src/classes/QuadrotorSimulator.cpp b/dfall_ws/src/dfall_pkg/src/classes/QuadrotorSimulator.cpp
index bb38b1b3..ea5eac21 100644
--- a/dfall_ws/src/dfall_pkg/src/classes/QuadrotorSimulator.cpp
+++ b/dfall_ws/src/dfall_pkg/src/classes/QuadrotorSimulator.cpp
@@ -53,9 +53,11 @@ QuadrotorSimulator::QuadrotorSimulator ( std::string id ) :
 	m_dist_body_z(-0.1,0.1)
 {
 	// Set the input argument to the ID string
-	this->m_id_string = id;
+	this->set_id_string( id );
+	//this->m_id_string = id;
 	// Set the default mass
-	this->m_mass_in_kg = 0.032;
+	this->set_mass_in_kg( 0.032 );
+	//this->m_mass_in_kg = mass;
 }
 
 QuadrotorSimulator::QuadrotorSimulator ( std::string id , float mass ) :
@@ -69,9 +71,9 @@ QuadrotorSimulator::QuadrotorSimulator ( std::string id , float mass ) :
 	m_dist_body_z(-0.1,0.1)
 {
 	// Set the input argument to the ID string
-	this->m_id_string = id;
+	this->set_id_string( id );
 	// Set the input argument to the mass
-	this->m_mass_in_kg = mass;
+	this->set_mass_in_kg( 0.032 );
 }
 
 
@@ -92,6 +94,36 @@ QuadrotorSimulator::QuadrotorSimulator ( std::string id , float mass ) :
 //    ----------------------------------------------------------------------------------
 
 
+// Function to get the ID as a string
+std::string QuadrotorSimulator::get_id_string()
+{
+	return this->m_id_string;
+}
+
+// Function to set the ID as a string
+void QuadrotorSimulator::set_id_string(std::string new_id_string)
+{
+	this->m_id_string = new_id_string;
+}
+
+// Function to get the mass in kilograms
+float QuadrotorSimulator::get_mass_in_kg()
+{
+	return this->m_mass_in_kg;
+}
+
+// Function to set the mass in kilograms
+void QuadrotorSimulator::set_mass_in_kg(float new_mass_in_kg)
+{
+	this->m_mass_in_kg = new_mass_in_kg;
+}
+
+// Function to get the flying state
+bool QuadrotorSimulator::get_isFlying()
+{
+	return this->m_isFlying;
+}
+
 // Function to simulate the quadrotor for one time step
 void QuadrotorSimulator::simulate_for_one_time_step(float deltaT)
 {
@@ -274,12 +306,6 @@ void QuadrotorSimulator::update_commanding_agent_id( int new_commanding_agent_id
 
 }
 
-// Function to get the flying state
-bool QuadrotorSimulator::getIsFlying()
-{
-	return this->m_isFlying;
-}
-
 // Function to set the reset state
 void QuadrotorSimulator::setResetState_xyz_yaw(float x, float y, float z, float yaw)
 {
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/CsoneControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/CsoneControllerService.cpp
index b80cd3bb..64ffed03 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/CsoneControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/CsoneControllerService.cpp
@@ -82,23 +82,23 @@
 // following two properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is
-// defined in the file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is
+// defined in the file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the
 // motion capture system of the Crazyflie that is to be controlled by this
 // service.
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access
+// This property is an array of "FlyingVehicleState" structures, what allows access
 // to the motion capture measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 8ad564c7..c36e7bc4 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -1585,25 +1585,6 @@ void loadCrazyflieContext()
 
     if(m_centralManager.call(contextCall)) {
         new_context = contextCall.response.crazyflieContext;
-        //ROS_INFO_STREAM("[DEFAULT CONTROLLER] CrazyflieContext:\n" << new_context);
-
-        //if((m_context.crazyflieName != "") && (new_context.crazyflieName != m_context.crazyflieName)) //linked crazyflie name changed and it was not empty before
-        //{
-
-            // Motors off is done in python script now everytime we disconnect
-
-            // send motors OFF and disconnect before setting m_context = new_context
-            // std_msgs::Int32 msg;
-            // msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-            // commandPublisher.publish(msg);
-
-            // ROS_INFO("[DEFAULT CONTROLLER] CF is now different for this student. Disconnect and turn it off");
-
-            // IntWithHeader msg;
-            // msg.shouldCheckForAgentID = false;
-            // msg.data = CMD_DISCONNECT;
-            // m_crazyRadioCommandPublisher.publish(msg);
-        //}
 
         m_symmetric_area_bounds_x = 0.5 * (new_context.localArea.xmax - new_context.localArea.xmin);
         m_symmetric_area_bounds_y = 0.5 * (new_context.localArea.ymax - new_context.localArea.ymin);
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
index 9dcffe20..e83ad504 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
@@ -80,22 +80,22 @@
 // The arument "request" is a structure provided to this service with the following two
 // properties:
 // request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by this
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index e2d4514a..553e6e56 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -86,7 +86,7 @@ void viconCallback(const ViconData& viconData)
 	static int number_of_consecutive_occulsions = 0;
 
 	// Initilise a variable for the pose data of this agent
-	CrazyflieData poseDataForThisAgent;
+	FlyingVehicleState poseDataForThisAgent;
 
 	// Extract the pose data for the allocated object from the
 	// full motion capture array
@@ -95,8 +95,8 @@ void viconCallback(const ViconData& viconData)
 	m_poseDataIndex = getPoseDataForObjectNameWithExpectedIndex( viconData, m_context.crazyflieName , m_poseDataIndex , poseDataForThisAgent );
 
 	// Initilise a variable for the pose data of another agent
-	CrazyflieData poseDataForOtherAgent;
-	poseDataForOtherAgent.occluded = true;
+	FlyingVehicleState poseDataForOtherAgent;
+	poseDataForOtherAgent.isValid = false;
 
 	// Extract the pose data for the other object from the
 	// full motion capture array
@@ -164,8 +164,8 @@ void viconCallback(const ViconData& viconData)
 
 
 		// Only continue if:
-		// (1) the agent is NOT occulded
-		if(!poseDataForThisAgent.occluded)
+		// (1) the agent's pose data is valid
+		if(poseDataForThisAgent.isValid)
 		{
 			// Update the flag
 			m_isOcculded_mocap_data = false;
@@ -285,7 +285,7 @@ void viconCallback(const ViconData& viconData)
 				// Update the flying state
 				requestChangeFlyingStateTo( STATE_MOTORS_OFF );
 			}
-		} // END OF: "if(!poseDataForThisAgent.occluded)"
+		} // END OF: "if(poseDataForThisAgent.isValid)"
 
 	}
 	else
@@ -301,7 +301,7 @@ void viconCallback(const ViconData& viconData)
 
 
 
-int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index , CrazyflieData& pose_to_fill_in)
+int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index , FlyingVehicleState& pose_to_fill_in)
 {
     // Initialise an integer for the index where the object
     // "name" is found
@@ -321,7 +321,7 @@ int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::s
     )
     {
         // Check if the names match
-        if (viconData.crazyflies[expected_index].crazyflieName == name)
+        if (viconData.crazyflies[expected_index].vehicleName == name)
         {
             object_index = expected_index;
         }
@@ -334,7 +334,7 @@ int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::s
         for( int i=0 ; i<length_poseData ; i++ )
         {    
             // Check if the names match
-            if(viconData.crazyflies[i].crazyflieName == name)
+            if(viconData.crazyflies[i].vehicleName == name)
             {
                 object_index = i;
             }
@@ -355,7 +355,7 @@ int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::s
 }
 
 
-void coordinatesToLocal(CrazyflieData& cf)
+void coordinatesToLocal(FlyingVehicleState& cf)
 {
 	// Get the area into a local variable
     AreaBounds area = m_context.localArea;
@@ -430,7 +430,7 @@ void sendZeroOutputCommandForMotors()
 //    ----------------------------------------------------------------------------------
 
 // Checks if crazyflie is within allowed area
-bool safetyCheck_on_positionAndTilt(CrazyflieData data)
+bool safetyCheck_on_positionAndTilt(FlyingVehicleState data)
 {
     // Check on the X position
     float symmetric_bound_x = 0.5 * (m_context.localArea.xmax-m_context.localArea.xmin);
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/MocapEmulator.cpp b/dfall_ws/src/dfall_pkg/src/nodes/MocapEmulator.cpp
index c7877f0f..ab75c383 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/MocapEmulator.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/MocapEmulator.cpp
@@ -83,13 +83,13 @@ void timerCallback_mocap_publisher(const ros::TimerEvent&)
 			it->simulate_for_one_time_step( yaml_mocap_deltaT_in_seconds );
 
 			// Local variable for the data of this quadrotor
-			CrazyflieData quadrotor_data;
+			FlyingVehicleState quadrotor_data;
 
 			// Fill in the details
 			// > For the name
-			quadrotor_data.crazyflieName = it->m_id_string;
+			quadrotor_data.vehicleName = it->get_id_string();
 			// > For the occulsion flag
-			quadrotor_data.occluded = false;
+			quadrotor_data.isValid = true;
 			// > For position
 			quadrotor_data.x = it->m_position[0];
 			quadrotor_data.y = it->m_position[1];
@@ -156,7 +156,7 @@ void loadContextForEachQuadrotor()
 		CMQueryCrazyflieName contextCall;
 
 		// Set the name of this quadrotor
-		contextCall.request.crazyflieName = it->m_id_string;
+		contextCall.request.crazyflieName = it->get_id_string();
 
 		// Wait for the service to exist
 		m_centralManagerService.waitForExistence(ros::Duration(0.5));
@@ -184,13 +184,13 @@ void loadContextForEachQuadrotor()
     		it->setResetState_xyz_yaw(new_reset_x,new_reset_y,0.0,0.0);
 
 			// Print out the new context
-			//ROS_INFO_STREAM("[MOCAP EMULATOR] Quadrotor simulator with ID \"" << it->m_id_string << "\" connected to agent ID " << new_agent_id << " in database.");
+			//ROS_INFO_STREAM("[MOCAP EMULATOR] Quadrotor simulator with ID \"" << it->get_id_string() << "\" connected to agent ID " << new_agent_id << " in database.");
 		}
 		else
 		{
-			// Let the user know that the "m_id_string" was not found
+			// Let the user know that the "id_string" was not found
 			// for this quadrotor simulation
-			ROS_INFO_STREAM("[MOCAP EMULATOR] Quadrotor simulator with ID \"" << it->m_id_string << "\" does not appear in the database.");
+			ROS_INFO_STREAM("[MOCAP EMULATOR] Quadrotor simulator with ID \"" << it->get_id_string() << "\" does not appear in the database.");
 
 			// Set the "new agent id" to reflect this
 			new_agent_id = -1;
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
index ec962cbb..675e5a32 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
@@ -174,20 +174,6 @@ std::string namespace_to_coordinator_parameter_service;
 int my_agentID = 0;
 
 
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
 
 
 
@@ -282,22 +268,22 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&st
 // The arument "request" is a structure provided to this service with the following two
 // properties:
 // request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by this
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index 10152881..aa340b95 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -293,22 +293,22 @@ void smoothSetpointChanges()
 // properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
index 3dda3026..6ca55d90 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
@@ -81,22 +81,22 @@
 // properties:
 
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by this
@@ -391,11 +391,11 @@ void viconSubscribeObjectNameCallback(const ViconSubscribeObjectName& msg)
 //is called when new data from Vicon arrives
 void viconCallback(const ViconData& viconData)
 {
-	for(std::vector<CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
+	for(std::vector<FlyingVehicleState>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
 	{
-		CrazyflieData objectData_in_globalFrame = *it;
+		FlyingVehicleState objectData_in_globalFrame = *it;
 
-		if(objectData_in_globalFrame.crazyflieName == viconObjectName_forRemote)
+		if(objectData_in_globalFrame.vehicleName == viconObjectName_forRemote)
         {
             
 			if (shouldPublishRemote_xyz_rpy)
@@ -410,8 +410,8 @@ void viconCallback(const ViconData& viconData)
 				ROS_INFO_STREAM("[REMOTE CONTROLLER] Remote [z,r,p,y] = [ " << objectData_in_globalFrame.z << " , " << objectData_in_globalFrame.roll << " , " << objectData_in_globalFrame.pitch << " , " << objectData_in_globalFrame.yaw << " ]" );
 			}
 
-			// Update the remote set-point is not occluded
-			if(!objectData_in_globalFrame.occluded)
+			// Update the remote set-point if the data isValid
+			if(objectData_in_globalFrame.isValid)
 			{
 
 				// Update the z height variable that is used when activating
@@ -445,7 +445,7 @@ void viconCallback(const ViconData& viconData)
 					}
 
 					// Publish the updated setpoint
-					CrazyflieData setpointToPublish;
+					FlyingVehicleState setpointToPublish;
 					setpointToPublish.roll  = setpointFromRemote_roll;
 					setpointToPublish.pitch = setpointFromRemote_pitch;
 					setpointToPublish.yaw   = setpointFromRemote_yaw;
@@ -1678,13 +1678,13 @@ int main(int argc, char* argv[]) {
 	ros::Subscriber viconSubscribeObjectNameSubscriber = nodeHandle.subscribe("ViconSubscribeObjectName", 1, viconSubscribeObjectNameCallback);
 
 	// Advertise the message topic of the Remote (y,roll,pitch,yaw)
-	remote_xyz_rpy_publisher = nodeHandle.advertise<CrazyflieData>("RemoteData", 1);
+	remote_xyz_rpy_publisher = nodeHandle.advertise<FlyingVehicleState>("RemoteData", 1);
 
 	// Subscribe to the message that triggers activates/deactivates remote control mode
 	ros::Subscriber shouldActivateSubscriber = nodeHandle.subscribe("Activate", 1, shouldActivateCallback);
 
 	// Advertise the message topic of the Remote (y,roll,pitch,yaw)
-	remote_control_setpoint_publisher = nodeHandle.advertise<CrazyflieData>("RemoteControlSetpoint", 1);
+	remote_control_setpoint_publisher = nodeHandle.advertise<FlyingVehicleState>("RemoteControlSetpoint", 1);
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index 64f37fda..292113d3 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -102,22 +102,22 @@ float yaml_ki_z = 1.0;
 // properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by this
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
index c7a19525..d92fa498 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
@@ -82,23 +82,23 @@
 // following two properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is
-// defined in the file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is
+// defined in the file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the
 // motion capture system of the Crazyflie that is to be controlled by this
 // service.
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access
+// This property is an array of "FlyingVehicleState" structures, what allows access
 // to the motion capture measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TestMotorsControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TestMotorsControllerService.cpp
index 77e303cc..92c5b4a5 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TestMotorsControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TestMotorsControllerService.cpp
@@ -82,23 +82,23 @@
 // following two properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is
-// defined in the file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is
+// defined in the file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the
 // motion capture system of the Crazyflie that is to be controlled by this
 // service.
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access
+// This property is an array of "FlyingVehicleState" structures, what allows access
 // to the motion capture measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
index 7ddc0d55..ab91b275 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
@@ -81,22 +81,22 @@
 // properties:
 //
 // >> request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
+// This property is itself a structure of type "FlyingVehicleState",  which is defined in the
+// file "FlyingVehicleState.msg", and has the following properties
+//     string vehicleName
 //     float64 x                         The x position of the Crazyflie [metres]
 //     float64 y                         The y position of the Crazyflie [metres]
 //     float64 z                         The z position of the Crazyflie [metres]
 //     float64 roll                      The roll component of the intrinsic Euler angles [radians]
 //     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
 //     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+//     float64 acquiringTime #delta t    The time elapsed since the previous "FlyingVehicleState" was received [seconds]
+//     bool isValid                      A boolean indicted whether the Crazyflie for visible at the time of this measurement
 // The values in these properties are directly the measurement taken by the Vicon
 // motion capture system of the Crazyflie that is to be controlled by this service
 //
 // >> request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
+// This property is an array of "FlyingVehicleState" structures, what allows access to the
 // Vicon measurements of other Crazyflies.
 //
 // The argument "response" is a structure that is expected to be filled in by this
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
index be04f3de..7a5fe429 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
@@ -244,10 +244,10 @@ int main(int argc, char* argv[]) {
 
                 
                 //build message
-                CrazyflieData cfData;
-                cfData.crazyflieName = subjectName;
+                FlyingVehicleState cfData;
+                cfData.vehicleName = subjectName;
 
-                cfData.occluded = outputTranslation.Occluded;
+                cfData.isValid = outputTranslation.Occluded;
 
                 cfData.x = outputTranslation.Translation[0] / 1000.0f;
                 cfData.y = outputTranslation.Translation[1] / 1000.0f;
@@ -325,25 +325,25 @@ void testFakeData(ros::Publisher viconDataPublisher)
         f += 10/1000.0f;
         i++;
         // TODO: Fake CF data
-        CrazyflieData crazyfly;
+        FlyingVehicleState crazyfly;
 
-        crazyfly.occluded = false;
+        crazyfly.isValid = false;
 
-        crazyfly.crazyflieName = "CF1";
+        crazyfly.vehicleName = "CF1";
         crazyfly.x = 0;
         crazyfly.y = 0;
         crazyfly.z = 0;
         crazyfly.yaw = 3.14159 * f;
         viconData.crazyflies.push_back(crazyfly);
 
-        crazyfly.crazyflieName = "CF2";
+        crazyfly.vehicleName = "CF2";
         crazyfly.x = 1;
         crazyfly.y = 1;
         crazyfly.z = 0;
         crazyfly.yaw = -3.14159 * f;
         viconData.crazyflies.push_back(crazyfly);
 
-        crazyfly.crazyflieName = "CF3";
+        crazyfly.vehicleName = "CF3";
         crazyfly.x = 1;
         crazyfly.y = -1;
         crazyfly.z = 0;
@@ -352,7 +352,7 @@ void testFakeData(ros::Publisher viconDataPublisher)
 
         if(i > 50 && i < 200)
         {
-            crazyfly.occluded = true;
+            crazyfly.isValid = true;
         }
 
         viconData.crazyflies.push_back(crazyfly);
diff --git a/dfall_ws/src/dfall_pkg/src/qualisys/QualisysDataPublisher.py b/dfall_ws/src/dfall_pkg/src/qualisys/QualisysDataPublisher.py
index cee7ce81..cea66f2a 100755
--- a/dfall_ws/src/dfall_pkg/src/qualisys/QualisysDataPublisher.py
+++ b/dfall_ws/src/dfall_pkg/src/qualisys/QualisysDataPublisher.py
@@ -71,7 +71,7 @@ from std_msgs.msg import String
 
 # Import the D-FaLL message types
 from dfall_pkg.msg import ViconData
-from dfall_pkg.msg import CrazyflieData
+from dfall_pkg.msg import FlyingVehicleState
 from dfall_pkg.msg import UnlabeledMarker
 
 # General import
@@ -278,22 +278,22 @@ class QualisysQtmClient:
                 #print( "rotation = ", rotation )
 
                 # Initialise a "ViconData" struct
-                # > This is defined in the "CrazyflieData.msg" file
-                this_crazyflie_data = CrazyflieData();
+                # > This is defined in the "FlyingVehicleState.msg" file
+                this_crazyflie_data = FlyingVehicleState();
 
                 # Add the name of this object
                 if current_body_index < len(self._list_of_body_names):
-                    this_crazyflie_data.crazyflieName = self._list_of_body_names[current_body_index]
+                    this_crazyflie_data.vehicleName = self._list_of_body_names[current_body_index]
                 else:
-                    this_crazyflie_data.crazyflieName = ''
+                    this_crazyflie_data.vehicleName = ''
 
                 # Check for "nan" as an indication of occulsion
                 if math.isnan(position.x):
                     # Fill in the occlusion flag
-                    this_crazyflie_data.occluded = True
+                    this_crazyflie_data.isValid = False
                 else:
                     # Fill in the occlusion flag
-                    this_crazyflie_data.occluded = False
+                    this_crazyflie_data.isValid = True
 
                     # Fill in the position data
                     this_crazyflie_data.x = position.x * 0.001
diff --git a/dfall_ws/src/dfall_pkg/srv/CMQueryCrazyflieName.srv b/dfall_ws/src/dfall_pkg/srv/CMQueryCrazyflieName.srv
index 85d54384..4584a581 100755
--- a/dfall_ws/src/dfall_pkg/srv/CMQueryCrazyflieName.srv
+++ b/dfall_ws/src/dfall_pkg/srv/CMQueryCrazyflieName.srv
@@ -1,5 +1,4 @@
 string crazyflieName
 ---
 CrazyflieContext crazyflieContext
-uint32 studentID
-
+uint32 studentID
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/srv/Controller.srv b/dfall_ws/src/dfall_pkg/srv/Controller.srv
index 979abc5c..c10a6bad 100644
--- a/dfall_ws/src/dfall_pkg/srv/Controller.srv
+++ b/dfall_ws/src/dfall_pkg/srv/Controller.srv
@@ -1,5 +1,5 @@
 bool isFirstControllerCall
-CrazyflieData ownCrazyflie
-CrazyflieData[] otherCrazyflies
+FlyingVehicleState ownCrazyflie
+FlyingVehicleState[] otherCrazyflies
 ---
-ControlCommand controlOutput
+ControlCommand controlOutput
\ No newline at end of file
-- 
GitLab