From 530c1f724283b879e5ce291e58690d057c9d3243 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 9 Feb 2019 18:15:59 +0100
Subject: [PATCH] Convert all occurances of PPS Client to Flying Agenet Client.
 And adjusted all other occurances of PPS accordingly

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         |   6 +-
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  |  19 +-
 .../flyingAgentGUI/forms/coordinatorrow.ui    |   2 +-
 .../include/Constants_for_Qt_compile.h        |  22 ++-
 .../flyingAgentGUI/include/coordinatorrow.h   |   4 +-
 .../include/enablecontrollerloadyamlbar.h     |   2 +-
 .../src/connectstartstopbar.cpp               |  10 +-
 .../flyingAgentGUI/src/controllertabs.cpp     |   4 +-
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp |   4 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  10 +-
 .../src/enablecontrollerloadyamlbar.cpp       |   2 +-
 .../GUI_Qt/studentGUI/include/MainWindow.h    |   4 +-
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      |  40 ++--
 dfall_ws/src/dfall_pkg/PPS.perspective        |   2 +-
 .../src/dfall_pkg/crazyradio/CrazyRadio.py    |  51 +++--
 dfall_ws/src/dfall_pkg/crazyradio/TestCF.py   |  28 +--
 .../{PPSClient.h => FlyingAgentClient.h}      |   0
 dfall_ws/src/dfall_pkg/launch/Agent.launch    |   6 +-
 dfall_ws/src/dfall_pkg/scripts/land_crazyflie |   2 +-
 .../dfall_pkg/scripts/load_custom_controller  |   2 +-
 .../dfall_pkg/scripts/load_safe_controller    |   2 +-
 .../dfall_pkg/scripts/motors_off_crazyflie    |   2 +-
 .../src/dfall_pkg/scripts/take_off_crazyflie  |   2 +-
 .../dfall_pkg/src/nodes/BatteryMonitor.cpp    |  43 ++++-
 .../src/nodes/DefaultControllerService.cpp    |  16 +-
 .../src/nodes/DemoControllerService.cpp       |  22 +--
 .../{PPSClient.cpp => FlyingAgentClient.cpp}  | 180 +++++++++---------
 .../src/nodes/MpcControllerService.cpp        |  40 ++--
 .../src/nodes/PickerControllerService.cpp     |  28 +--
 .../src/nodes/RemoteControllerService.cpp     |  44 ++---
 .../src/nodes/SafeControllerService.cpp       |   2 +-
 .../src/nodes/StudentControllerService.cpp    |  12 +-
 .../src/nodes/TuningControllerService.cpp     |  20 +-
 33 files changed, 338 insertions(+), 295 deletions(-)
 rename dfall_ws/src/dfall_pkg/include/nodes/{PPSClient.h => FlyingAgentClient.h} (100%)
 rename dfall_ws/src/dfall_pkg/src/nodes/{PPSClient.cpp => FlyingAgentClient.cpp} (84%)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index 3fb5b938..ee4cb694 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -327,7 +327,7 @@ if(VICON_LIBRARY)
 	add_executable(ViconDataPublisher       src/nodes/ViconDataPublisher.cpp)
 endif()
 
-add_executable(PPSClient                 src/nodes/PPSClient.cpp
+add_executable(FlyingAgentClient         src/nodes/FlyingAgentClient.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(BatteryMonitor            src/nodes/BatteryMonitor.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
@@ -420,7 +420,7 @@ if(VICON_LIBRARY)
 	add_dependencies(ViconDataPublisher       dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 endif()
 
-add_dependencies(PPSClient                 dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(FlyingAgentClient         dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(BatteryMonitor            dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(DefaultControllerService  dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(SafeControllerService     dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
@@ -472,7 +472,7 @@ if(VICON_LIBRARY)
 	target_link_libraries(ViconDataPublisher ${VICON_LIBRARY})
 endif()
 
-target_link_libraries(PPSClient                 ${catkin_LIBRARIES})
+target_link_libraries(FlyingAgentClient         ${catkin_LIBRARIES})
 target_link_libraries(BatteryMonitor            ${catkin_LIBRARIES})
 target_link_libraries(DefaultControllerService  ${catkin_LIBRARIES})
 target_link_libraries(SafeControllerService     ${catkin_LIBRARIES})
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
index 49dac78b..f1119906 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
@@ -742,17 +742,17 @@ void MainGUIWindow::on_refresh_student_ids_button_clicked()
     #ifdef CATKIN_MAKE
     ui->list_discovered_student_ids->clear();
 
-    // \/(\d)\/PPSClient
+    // \/(\d)\/FlyingAgentClient
     ros::V_string v_str;
     ros::master::getNodes(v_str);
     for(int i = 0; i < v_str.size(); i++)
     {
         std::string s = v_str[i];
         std::smatch m;
-        //std::regex e ("\\/(\\d)\\/PPSClient");
-        std::regex e ("\\/agent(\\d\\d\\d)\\/PPSClient");
+        //std::regex e ("\\/(\\d)\\/FlyingAgentClient");
+        std::regex e ("\\/agent(\\d\\d\\d)\\/FlyingAgentClient");
 
-        // std::regex e("\\/PPSClien(.)");
+        // std::regex e("\\/FlyingAgentClient(.)");
 
         // while(std::regex_search(s, m, e))
         // {
@@ -1314,7 +1314,6 @@ void MainGUIWindow::customSendYamlAsMessageTimerCallback(const ros::TimerEvent&)
 
 // load parameters from corresponding YAML file
 //
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
 float MainGUIWindow::getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
 {
     float val;
@@ -1324,7 +1323,7 @@ float MainGUIWindow::getParameterFloat(ros::NodeHandle& nodeHandle, std::string
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+
 void MainGUIWindow::getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1334,7 +1333,7 @@ void MainGUIWindow::getParameterFloatVector(ros::NodeHandle& nodeHandle, std::st
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+
 int MainGUIWindow::getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
 {
     int val;
@@ -1344,7 +1343,7 @@ int MainGUIWindow::getParameterInt(ros::NodeHandle& nodeHandle, std::string name
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+
 void MainGUIWindow::getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1354,7 +1353,7 @@ void MainGUIWindow::getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHa
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+
 int MainGUIWindow::getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1362,7 +1361,7 @@ int MainGUIWindow::getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeH
     }
     return val.size();
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+
 bool MainGUIWindow::getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 {
     bool val;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
index ffb245eb..cba391ca 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
@@ -81,7 +81,7 @@
       <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
      </property>
      <property name="text">
-      <string>IDYYY , PPS_CFXX</string>
+      <string>IDYYY , CFXX</string>
      </property>
      <property name="checkable">
       <bool>true</bool>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
index d96707d4..b361da05 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
@@ -81,7 +81,27 @@
 
 
 
-// Types PPS firmware
+// These constants define the modes that can be used for controller this is
+// running on-board the Crazyflie 2.0.
+// Therefore, the constants defined here need to be in agreement with those
+// defined in the firmware running on-board the Crazyflie 2.0.
+// The following is a short description about each mode:
+//
+// CF_COMMAND_TYPE_MOTORS
+//     In this mode the Crazyflie will apply the requested 16-bit per motor
+//     command directly to each of the motors
+//
+// CF_COMMAND_TYPE_RATE
+//     In this mode the Crazyflie will apply the requested 16-bit per motor
+//     command directly to each of the motors, and additionally request the
+//     body frame roll, pitch, and yaw angular rates from the PID rate
+//     controllers implemented in the Crazyflie 2.0 firmware.
+//
+// CF_COMMAND_TYPE_ANGLE
+//     In this mode the Crazyflie will apply the requested 16-bit per motor
+//     command directly to each of the motors, and additionally request the
+//     body frame roll, pitch, and yaw angles from the PID attitude
+//     controllers implemented in the Crazyflie 2.0 firmware.
 #define CF_COMMAND_TYPE_MOTORS 6
 #define CF_COMMAND_TYPE_RATE   7
 #define CF_COMMAND_TYPE_ANGLE  8
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 6a0734db..efce79c5 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -157,11 +157,11 @@ private:
     void loadCrazyflieContext();
 
     // > For requesting the current flying state
-    //   i.e., using the service advertised by the PPS client
+    //   i.e., using the service advertised by the Flying Agent Client
     void getCurrentFlyingState();
 
     // > For requesting the current state of the Crazy Radio
-    //   i.e., using the service advertised by the PPS client
+    //   i.e., using the service advertised by the Flying Agent Client
     void getCurrentCrazyRadioState();
 
     // > For updating the text in the UI element of
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 6095810a..c8a54e33 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -38,7 +38,7 @@
 // COMMANDS FOR THE FLYING STATE/CONTROLLER USED
 // The constants that "command" changes in the
 // operation state of this agent. These "commands"
-// are sent from this GUI node to the "PPSClient"
+// are sent from this GUI node to the "FlyingAgentClient"
 // node where the command is enacted
 // #define CMD_USE_SAFE_CONTROLLER      1
 // #define CMD_USE_DEMO_CONTROLLER      2
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 36498a1f..b15b8e0b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -106,10 +106,10 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
     // SUBSCRIBERS AND PUBLISHERS:
 
     // > For Crazyradio commands based on button clicks
-    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/crazyRadioCommand", 1);
 
     // > For Flying state commands based on button clicks
-    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
+    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/Command", 1);
 
     if (m_type == TYPE_AGENT)
     {
@@ -126,7 +126,7 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
         batteryLevelSubscriber = base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &ConnectStartStopBar::batteryLevelCallback, this);
     
         // > For updating the "flying_state_label" picture
-        flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
+        flyingStateSubscriber = base_nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
     }
 #endif
 
@@ -614,7 +614,7 @@ void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // > Request the current flying state
-        ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("PPSClient/getCurrentFlyingState", false);
+        ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("FlyingAgentClient/getCurrentFlyingState", false);
         dfall_pkg::IntIntService getFlyingStateCall;
         getFlyingStateCall.request.data = 0;
         getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
@@ -654,7 +654,7 @@ void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
         batteryLevelSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &ConnectStartStopBar::batteryLevelCallback, this);
 
         // > For updating the "flying_state_label" picture
-        flyingStateSubscriber = agent_base_nodeHandle.subscribe("PPSClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
+        flyingStateSubscriber = agent_base_nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
     }
     else
     {
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 ecbb608e..38f9d5d9 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
@@ -128,7 +128,7 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     // Only if this is an agent GUI
     if (m_type == TYPE_AGENT)
     {
-        controllerUsedSubscriber = nodeHandle_for_this_gui.subscribe("PPSClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
+        controllerUsedSubscriber = nodeHandle_for_this_gui.subscribe("FlyingAgentClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
     }
 
 
@@ -457,7 +457,7 @@ void ControllerTabs::setAgentIDsToCoordinate(QVector<int> agentIDs , bool should
 
         // SUBSCRIBERS
         // > For receiving message that the setpoint was changed
-        controllerUsedSubscriber = agent_base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
+        controllerUsedSubscriber = agent_base_nodeHandle.subscribe("FlyingAgentClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
     }
     else
     {
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
index 64bece6d..af56b464 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
@@ -26,7 +26,7 @@ void Coordinator::on_refresh_button_clicked()
 
 #ifdef CATKIN_MAKE
     // USE A REGULAR EXPRESSION TO IDENTIFY NODES THAT EXIST
-    // > The regular expression we use is: \/agent(\d\d\d)\/PPSClient
+    // > The regular expression we use is: \/agent(\d\d\d)\/FlyingAgentClient
     //   with the different that the escaped character is \\ instead of \ only
 
     // GET A "V_string" OF ALL THE NODES CURRENTLY IN EXISTENCE
@@ -39,7 +39,7 @@ void Coordinator::on_refresh_button_clicked()
         // TEST THE NAME OF THIS NODE AGAINST THE REGULAR EXPRESSION
         std::string s = v_str[i];
         std::smatch m;
-        std::regex e ("\\/agent(\\d\\d\\d)\\/PPSClient");
+        std::regex e ("\\/agent(\\d\\d\\d)\\/FlyingAgentClient");
 
         if(std::regex_search(s, m, e))
         {
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 8a1af80b..a31d6804 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -107,7 +107,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     // SUBSCRIBERS AND PUBLISHERS:
 
     // > For Crazyradio commands based on button clicks
-    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/crazyRadioCommand", 1);
     // > For updating the "rf_status_label" picture
     crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &CoordinatorRow::crazyRadioStatusCallback, this);
 
@@ -119,20 +119,20 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     batteryLevelSubscriber = base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &CoordinatorRow::batteryLevelCallback, this);
 
     // > For Flying state commands based on button clicks
-    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
+    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/Command", 1);
     // > For updating the "flying_state_label" picture
-    flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/flyingState", 1, &CoordinatorRow::flyingStateChangedCallback, this);
+    flyingStateSubscriber = base_nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &CoordinatorRow::flyingStateChangedCallback, this);
 
     // > For changes in the database that defines {agentID,cfID,flying zone} links
     databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &CoordinatorRow::databaseChangedCallback, this);;
     centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<dfall_pkg::CMQuery>("CentralManagerService/Query", false);
 
     // > For updating the controller that is currently operating
-    controllerUsedSubscriber = base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
+    controllerUsedSubscriber = base_nodeHandle.subscribe("FlyingAgentClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
 
     // > For requesting the current flying state,
     //   this is used only for initialising the icon
-    getCurrentFlyingStateService = base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("PPSClient/getCurrentFlyingState", false);
+    getCurrentFlyingStateService = base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("FlyingAgentClient/getCurrentFlyingState", false);
 
     // > For requesting the current state of the Crazy Radio,
     //   this is used only for initialising the icon
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index fa8700c5..5b3de64b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -30,7 +30,7 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE COMMAND PUBLISHER
-    commandPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
+    commandPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/Command", 1);
 
     // CREATE THE REQUEST LOAD YAML FILE PUBLISHER
     // Get the node handle to this parameter service
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
index 608102b2..c792c916 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
@@ -69,7 +69,7 @@
 
 // The constants that "command" changes in the
 // operation state of this agent. These "commands"
-// are sent from this GUI node to the "PPSClient"
+// are sent from this GUI node to the "FlyingAgentClient"
 // node where the command is enacted
 #define CMD_USE_SAFE_CONTROLLER      1
 #define CMD_USE_DEMO_CONTROLLER      2
@@ -288,7 +288,7 @@ private:
 
     ros::Publisher crazyRadioCommandPublisher;
     ros::Subscriber crazyRadioStatusSubscriber;
-    ros::Publisher PPSClientCommandPublisher;
+    ros::Publisher FlyingAgentClientCommandPublisher;
     ros::Subscriber CFBatterySubscriber;
     ros::Subscriber flyingStateSubscriber;
     ros::Subscriber batteryStateSubscriber;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
index aed81191..3d74934f 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
@@ -153,11 +153,11 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
 
     CFBatterySubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, &MainWindow::CFBatteryCallback, this);
 
-    flyingStateSubscriber = nodeHandle.subscribe("PPSClient/flyingState", 1, &MainWindow::flyingStateChangedCallback, this);
+    flyingStateSubscriber = nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &MainWindow::flyingStateChangedCallback, this);
 
-    batteryStateSubscriber = nodeHandle.subscribe("PPSClient/batteryState", 1, &MainWindow::batteryStateChangedCallback, this);
+    batteryStateSubscriber = nodeHandle.subscribe("FlyingAgentClient/batteryState", 1, &MainWindow::batteryStateChangedCallback, this);
 
-    controllerUsedSubscriber = nodeHandle.subscribe("PPSClient/controllerUsed", 1, &MainWindow::controllerUsedChangedCallback, this);
+    controllerUsedSubscriber = nodeHandle.subscribe("FlyingAgentClient/controllerUsed", 1, &MainWindow::controllerUsedChangedCallback, this);
 
 
     safeSetpointSubscriber = nodeHandle.subscribe("SafeControllerService/Setpoint", 1, &MainWindow::safeSetpointCallback, this);
@@ -167,18 +167,18 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     controllerSetpointPublisher = my_nodeHandle.advertise<Setpoint>("ControllerSetpoint", 1);
 
 
-    // communication with PPS Client, just to make it possible to communicate through terminal also we use PPSClient's name
-    //ros::NodeHandle nh_PPSClient(m_ros_namespace + "/PPSClient");
-    ros::NodeHandle nh_PPSClient("PPSClient");
-    crazyRadioCommandPublisher = nh_PPSClient.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
-    PPSClientCommandPublisher = nh_PPSClient.advertise<std_msgs::Int32>("Command", 1);    
+    // communication with Flying Agent Client, just to make it possible to communicate through terminal also we use FlyingAgentClient's name
+    //ros::NodeHandle nh_FlyingAgentClient(m_ros_namespace + "/FlyingAgentClient");
+    ros::NodeHandle nh_FlyingAgentClient("FlyingAgentClient");
+    crazyRadioCommandPublisher = nh_FlyingAgentClient.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
+    FlyingAgentClientCommandPublisher = nh_FlyingAgentClient.advertise<std_msgs::Int32>("Command", 1);    
 
 
     // > For publishing a message that requests the
     //   YAML parameters to be re-loaded from file
     // > The message contents specify which controller
     //   the parameters should be re-loaded for
-    requestLoadControllerYamlPublisher = nh_PPSClient.advertise<std_msgs::Int32>("requestLoadControllerYaml", 1);
+    requestLoadControllerYamlPublisher = nh_FlyingAgentClient.advertise<std_msgs::Int32>("requestLoadControllerYaml", 1);
 
 
     // Subscriber for locking the load the controller YAML
@@ -186,7 +186,7 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     requestLoadControllerYaml_from_my_GUI_Subscriber = nodeHandle.subscribe("/my_GUI/requestLoadControllerYaml", 1, &MainWindow::requestLoadControllerYaml_from_my_GUI_Callback, this);
 
     // First get student ID
-    if(!nh_PPSClient.getParam("agentID", m_student_id))
+    if(!nh_FlyingAgentClient.getParam("agentID", m_student_id))
     {
 		ROS_ERROR("Failed to get agentID");
 	}
@@ -966,21 +966,21 @@ void MainWindow::on_take_off_button_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_land_button_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_CRAZYFLY_LAND;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_motors_OFF_button_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 
@@ -1487,49 +1487,49 @@ void MainWindow::on_enable_safe_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_SAFE_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_demo_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_DEMO_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_student_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_STUDENT_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_mpc_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_MPC_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_remote_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_REMOTE_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_tuning_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_TUNING_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 void MainWindow::on_enable_picker_controller_clicked()
 {
     std_msgs::Int32 msg;
     msg.data = CMD_USE_PICKER_CONTROLLER;
-    this->PPSClientCommandPublisher.publish(msg);
+    this->FlyingAgentClientCommandPublisher.publish(msg);
 }
 
 
diff --git a/dfall_ws/src/dfall_pkg/PPS.perspective b/dfall_ws/src/dfall_pkg/PPS.perspective
index 57c0387a..87d70db1 100644
--- a/dfall_ws/src/dfall_pkg/PPS.perspective
+++ b/dfall_ws/src/dfall_pkg/PPS.perspective
@@ -191,7 +191,7 @@
               "keys": {
                 "publishers": {
                   "type": "repr", 
-                  "repr": "u\"[{'type_name': 'std_msgs/Int32', 'topic_name': '/PPSClient/Command', 'enabled': False, 'rate': 1.0, 'expressions': {u'/PPSClient/Command/data': '3'}, 'publisher_id': 0, 'counter': 0}]\""
+                  "repr": "u\"[{'type_name': 'std_msgs/Int32', 'topic_name': '/FlyingAgentClient/Command', 'enabled': False, 'rate': 1.0, 'expressions': {u'/FlyingAgentClient/Command/data': '3'}, 'publisher_id': 0, 'counter': 0}]\""
                 }
               }, 
               "groups": {}
diff --git a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
index 3746f705..ddc1fdf4 100755
--- a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
+++ b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
@@ -72,10 +72,9 @@ logging.basicConfig(level=logging.ERROR)
 # CONTROLLER_ANGLE = 1
 # CONTROLLER_RATE = 0
 
-
-TYPE_PPS_MOTORS = 6
-TYPE_PPS_RATE =   7
-TYPE_PPS_ANGLE =  8
+CF_COMMAND_TYPE_MOTORS = 6
+CF_COMMAND_TYPE_RATE =   7
+CF_COMMAND_TYPE_ANGLE =  8
 
 RAD_TO_DEG = 57.296
 
@@ -88,7 +87,7 @@ DISCONNECTED = 2
 CMD_RECONNECT = 0
 CMD_DISCONNECT = 1
 
-# Commands for PPSClient
+# Commands for FlyingAgentClient
 #CMD_USE_SAFE_CONTROLLER =       1
 #CMD_USE_DEMO_CONTROLLER =       2
 #CMD_USE_STUDENT_CONTROLLER =    3
@@ -106,7 +105,7 @@ rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf')
 rospy.loginfo(record_file)
 bag = rosbag.Bag(record_file, 'w')
 
-class PPSRadioClient:
+class CrazyRadioClient:
     """
        CrazyRadio client that recieves the commands from the controller and
        sends them in a CRTP package to the crazyflie with the specified
@@ -126,7 +125,7 @@ class PPSRadioClient:
         self.link_uri = ""
 
         self.status_pub = rospy.Publisher(node_name + '/CrazyRadioStatus', Int32, queue_size=1)
-        self.PPSClient_command_pub = rospy.Publisher('PPSClient/Command', IntWithHeader, queue_size=1)
+        self.FlyingAgentClient_command_pub = rospy.Publisher('FlyingAgentClient/Command', IntWithHeader, queue_size=1)
         time.sleep(1.0)
 
         # Initialize the CrazyFlie and add callbacks
@@ -173,7 +172,7 @@ class PPSRadioClient:
         msg = IntWithHeader()
         msg.shouldCheckForID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
-        self.PPSClient_command_pub.publish(msg)
+        self.FlyingAgentClient_command_pub.publish(msg)
         time.sleep(0.1)
         print "[CRAZY RADIO] Disconnecting from %s" % self.link_uri
         self._cf.close_link()
@@ -233,7 +232,7 @@ class PPSRadioClient:
         msg = IntWithHeader()
         msg.shouldCheckForID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
-        cf_client.PPSClient_command_pub.publish(msg)
+        cf_client.FlyingAgentClient_command_pub.publish(msg)
 
         rospy.loginfo("[CRAZY RADIO] Connection to %s successful: " % link_uri)
         # Config for Logging
@@ -263,7 +262,7 @@ class PPSRadioClient:
         msg = IntWithHeader()
         msg.shouldCheckForID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
-        self.PPSClient_command_pub.publish(msg)
+        self.FlyingAgentClient_command_pub.publish(msg)
 
         self.logconf.stop()
         rospy.loginfo("logconf stopped")
@@ -273,19 +272,19 @@ class PPSRadioClient:
     def _send_to_commander_motor(self, cmd1, cmd2, cmd3, cmd4):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHH', TYPE_PPS_MOTORS, cmd1, cmd2, cmd3, cmd4)
+        pk.data = struct.pack('<BHHHH', CF_COMMAND_TYPE_MOTORS, cmd1, cmd2, cmd3, cmd4)
         self._cf.send_packet(pk)
 
     def _send_to_commander_rate(self, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHHfff', TYPE_PPS_RATE, cmd1, cmd2, cmd3, cmd4, roll_rate * RAD_TO_DEG, pitch_rate * RAD_TO_DEG, yaw_rate * RAD_TO_DEG)
+        pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_RATE, cmd1, cmd2, cmd3, cmd4, roll_rate * RAD_TO_DEG, pitch_rate * RAD_TO_DEG, yaw_rate * RAD_TO_DEG)
         self._cf.send_packet(pk)
 
     def _send_to_commander_angle(self, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHHfff', TYPE_PPS_ANGLE, cmd1, cmd2, cmd3, cmd4, roll * RAD_TO_DEG, pitch * RAD_TO_DEG, yaw * RAD_TO_DEG)
+        pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_ANGLE, cmd1, cmd2, cmd3, cmd4, roll * RAD_TO_DEG, pitch * RAD_TO_DEG, yaw * RAD_TO_DEG)
         self._cf.send_packet(pk)
 
     # def _send_to_commander(self,roll, pitch, yaw, thrust, cmd1, cmd2, cmd3, cmd4, mode):
@@ -350,13 +349,13 @@ def controlCommandCallback(data):
 
     #cmd1..4 must not be 0, as crazyflie onboard controller resets!
     #pitch and yaw are inverted on crazyflie controller
-    if data.onboardControllerType == TYPE_PPS_MOTORS:
+    if data.onboardControllerType == CF_COMMAND_TYPE_MOTORS:
         cf_client._send_to_commander_motor(data.motorCmd1, data.motorCmd2, data.motorCmd3, data.motorCmd4)
 
-    elif data.onboardControllerType == TYPE_PPS_RATE:
+    elif data.onboardControllerType == CF_COMMAND_TYPE_RATE:
         cf_client._send_to_commander_rate(data.motorCmd1, data.motorCmd2, data.motorCmd3, data.motorCmd4, data.roll, -data.pitch, -data.yaw)
 
-    elif data.onboardControllerType == TYPE_PPS_ANGLE:
+    elif data.onboardControllerType == CF_COMMAND_TYPE_ANGLE:
         cf_client._send_to_commander_angle(data.motorCmd1, data.motorCmd2, data.motorCmd3, data.motorCmd4, data.roll, -data.pitch, -data.yaw)
         # cf_client._send_to_commander(data.roll, -data.pitch, -data.yaw, 0, data.motorCmd1, data.motorCmd2, data.motorCmd3, data.motorCmd4, data.onboardControllerType)
 
@@ -380,7 +379,7 @@ if __name__ == '__main__':
     # Initialize the low-level drivers (don't list the debug drivers)
     cflib.crtp.init_drivers(enable_debug_driver=False)
 
-    #wait until address parameter is set by PPSClient
+    #wait until address parameter is set by FlyingAgentClient
     while not rospy.has_param("~crazyFlieAddress"):
         time.sleep(0.05)
 
@@ -394,8 +393,8 @@ if __name__ == '__main__':
 
     # Fetch the YAML paramter "agentID" and "coordID"
     global m_agentID
-    m_agentID = rospy.get_param(ros_namespace + "/PPSClient/agentID")
-    coordID   = rospy.get_param(ros_namespace + "/PPSClient/coordID")
+    m_agentID = rospy.get_param(ros_namespace + "/FlyingAgentClient/agentID")
+    coordID   = rospy.get_param(ros_namespace + "/FlyingAgentClient/coordID")
     # Convert the coordinator ID to a zero-padded string
     coordID_as_string = format(coordID, '03')
 
@@ -404,19 +403,19 @@ if __name__ == '__main__':
     global cfbattery_pub
     cfbattery_pub = rospy.Publisher(node_name + '/CFBattery', Float32, queue_size=10)
 
-    # Initialise a "PPSRadioClient" type variable that handles
+    # Initialise a "CrazyRadioClient" type variable that handles
     # all communication over the CrazyRadio
     global cf_client
-    cf_client = PPSRadioClient()
+    cf_client = CrazyRadioClient()
 
     print "[CRAZY RADIO] DEBUG 2"
 
     # Subscribe to the commands for when to (dis-)connect the
     # CrazyRadio connection with the Crazyflie
-    # > For the radio commands from the PPSClient of this agent
-    rospy.Subscriber("PPSClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
+    # > For the radio commands from the FlyingAgentClient of this agent
+    rospy.Subscriber("FlyingAgentClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
     # > For the radio command from the coordinator
-    rospy.Subscriber("/dfall/coord" + coordID_as_string + "/PPSClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
+    rospy.Subscriber("/dfall/coord" + coordID_as_string + "/FlyingAgentClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
 
 
     # Advertise a Serice for the current status
@@ -427,7 +426,7 @@ if __name__ == '__main__':
 
     time.sleep(1.0)
 
-    rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
+    rospy.Subscriber("FlyingAgentClient/ControlCommand", ControlCommand, controlCommandCallback)
 
     print "[CRAZY RADIO] Node READY :-)"
     rospy.spin()
@@ -438,7 +437,7 @@ if __name__ == '__main__':
     msg = IntWithHeader()
     msg.shouldCheckForID = False
     msg.data = CMD_CRAZYFLY_MOTORS_OFF
-    cf_client.PPSClient_command_pub.publish(msg)
+    cf_client.FlyingAgentClient_command_pub.publish(msg)
     #wait for client to send its commands
     time.sleep(1.0)
 
diff --git a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
index 5cc25317..3cfb0e2a 100755
--- a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
+++ b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
@@ -36,9 +36,9 @@ logging.basicConfig(level=logging.ERROR)
 
 # Types:
 
-TYPE_PPSMOTORS = 6
-TYPE_PPSRATE   = 7
-TYPE_PPSANGLE =  8
+CF_COMMAND_TYPE_MOTORS = 6
+CF_COMMAND_TYPE_RATE   = 7
+CF_COMMAND_TYPE_ANGLE =  8
 
 CONTROLLER_MOTOR = 2
 CONTROLLER_ANGLE = 1
@@ -54,7 +54,7 @@ DISCONNECTED = 2
 CMD_RECONNECT = 0
 CMD_DISCONNECT = 1
 
-# Commands for PPSClient
+# Commands for FlyingAgentClient
 CMD_USE_SAFE_CONTROLLER =   1
 CMD_USE_CUSTOM_CONTROLLER = 2
 CMD_CRAZYFLY_TAKE_OFF =     3
@@ -67,7 +67,7 @@ CMD_CRAZYFLY_MOTORS_OFF =   5
 # rospy.loginfo(record_file)
 # bag = rosbag.Bag(record_file, 'w')
 
-class PPSRadioClient:
+class CrazyRadioClient:
     """
        CrazyRadio client that recieves the commands from the controller and
        sends them in a CRTP package to the crazyflie with the specified
@@ -87,7 +87,7 @@ class PPSRadioClient:
         self.link_uri = ""
 
         # self.status_pub = rospy.Publisher(node_name + '/CrazyRadioStatus', Int32, queue_size=1)
-        # self.PPSClient_command_pub = rospy.Publisher('PPSClient/Command', Int32, queue_size=1)
+        # self.FlyingAgentClient_command_pub = rospy.Publisher('FlyingAgentClient/Command', Int32, queue_size=1)
         time.sleep(1.0)
 
         # Initialize the CrazyFlie and add callbacks
@@ -192,19 +192,19 @@ class PPSRadioClient:
     def _send_to_commander_motor(self, cmd1, cmd2, cmd3, cmd4):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHH', TYPE_PPSMOTORS, cmd1, cmd2, cmd3, cmd4)
+        pk.data = struct.pack('<BHHHH', CF_COMMAND_TYPE_MOTORS, cmd1, cmd2, cmd3, cmd4)
         self._cf.send_packet(pk)
 
     def _send_to_commander_rate(self, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHHfff', TYPE_PPSRATE, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate)
+        pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_RATE, cmd1, cmd2, cmd3, cmd4, roll_rate, pitch_rate, yaw_rate)
         self._cf.send_packet(pk)
 
     def _send_to_commander_angle(self, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw):
         pk = CRTPPacket()
         pk.port = CRTPPort.COMMANDER_GENERIC
-        pk.data = struct.pack('<BHHHHfff', TYPE_PPSANGLE, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw)
+        pk.data = struct.pack('<BHHHHfff', CF_COMMAND_TYPE_ANGLE, cmd1, cmd2, cmd3, cmd4, roll, pitch, yaw)
         self._cf.send_packet(pk)
 
 if __name__ == '__main__':
@@ -215,7 +215,7 @@ if __name__ == '__main__':
     # Initialize the low-level drivers (don't list the debug drivers)
     cflib.crtp.init_drivers(enable_debug_driver=False)
 
-    #wait until address parameter is set by PPSClient
+    #wait until address parameter is set by FlyingAgentClient
     # while not rospy.has_param("~crazyFlieAddress"):
     #     time.sleep(0.05)
 
@@ -228,19 +228,19 @@ if __name__ == '__main__':
 
     global cf_client
 
-    cf_client = PPSRadioClient()
-    # rospy.Subscriber("PPSClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
+    cf_client = CrazyRadioClient()
+    # rospy.Subscriber("FlyingAgentClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
 
     # time.sleep(1.0)
 
-    # rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
+    # rospy.Subscriber("FlyingAgentClient/ControlCommand", ControlCommand, controlCommandCallback)
 
     # rospy.spin()
     # rospy.loginfo("Turning off crazyflie")
 
 
     # change state to motors OFF
-    # cf_client.PPSClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
+    # cf_client.FlyingAgentClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
     #wait for client to send its commands
     # time.sleep(1.0)
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PPSClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/include/nodes/PPSClient.h
rename to dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
diff --git a/dfall_ws/src/dfall_pkg/launch/Agent.launch b/dfall_ws/src/dfall_pkg/launch/Agent.launch
index 24882047..0eca8749 100755
--- a/dfall_ws/src/dfall_pkg/launch/Agent.launch
+++ b/dfall_ws/src/dfall_pkg/launch/Agent.launch
@@ -27,12 +27,12 @@
 			<rosparam command="load" file="$(find dfall_pkg)/param/BatteryMonitor.yaml" />
 		</node>
 
-		<!-- PPS CLIENT -->
+		<!-- FLYING AGENT CLIENT -->
 		<node
 			pkg    = "dfall_pkg"
-			name   = "PPSClient"
+			name   = "FlyingAgentClient"
 			output = "screen"
-			type   = "PPSClient"
+			type   = "FlyingAgentClient"
 			>
 			<param name="agentID" value="$(arg agentID)" />
 			<param name="coordID" value="$(arg coordID)" />
diff --git a/dfall_ws/src/dfall_pkg/scripts/land_crazyflie b/dfall_ws/src/dfall_pkg/scripts/land_crazyflie
index 38d16c7d..d475b564 100755
--- a/dfall_ws/src/dfall_pkg/scripts/land_crazyflie
+++ b/dfall_ws/src/dfall_pkg/scripts/land_crazyflie
@@ -2,5 +2,5 @@
 
 if [ "$#" -ne 0 ]
 then echo "usage: land crazyfly <no arguments>"
-else rostopic pub -1 /$ROS_NAMESPACE/PPSClient/Command std_msgs/Int32 4;
+else rostopic pub -1 /$ROS_NAMESPACE/FlyingAgentClient/Command std_msgs/Int32 4;
 fi
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/scripts/load_custom_controller b/dfall_ws/src/dfall_pkg/scripts/load_custom_controller
index 50a3eefd..fb99d4e7 100755
--- a/dfall_ws/src/dfall_pkg/scripts/load_custom_controller
+++ b/dfall_ws/src/dfall_pkg/scripts/load_custom_controller
@@ -2,6 +2,6 @@
 
 if [ "$#" -ne 0 ] 
 then echo "usage: load_custom_controller <no arguments>"
-else rostopic pub -1 /$ROS_NAMESPACE/PPSClient/Command std_msgs/Int32 2;
+else rostopic pub -1 /$ROS_NAMESPACE/FlyingAgentClient/Command std_msgs/Int32 2;
 fi
 
diff --git a/dfall_ws/src/dfall_pkg/scripts/load_safe_controller b/dfall_ws/src/dfall_pkg/scripts/load_safe_controller
index 25570c51..c58ec1d3 100755
--- a/dfall_ws/src/dfall_pkg/scripts/load_safe_controller
+++ b/dfall_ws/src/dfall_pkg/scripts/load_safe_controller
@@ -2,6 +2,6 @@
 
 if [ "$#" -ne 0 ] 
 then echo "usage: load_safe_controller <no arguments>"
-else rostopic pub -1 /$ROS_NAMESPACE/PPSClient/Command std_msgs/Int32 1;
+else rostopic pub -1 /$ROS_NAMESPACE/FlyingAgentClient/Command std_msgs/Int32 1;
 fi
 
diff --git a/dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie b/dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie
index c4acfeef..a607a00a 100755
--- a/dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie
+++ b/dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie
@@ -2,6 +2,6 @@
 
 if [ "$#" -ne 0 ] 
 then echo "usage: motors_off_crazyflie <no arguments>"
-else rostopic pub -1 /$ROS_NAMESPACE/PPSClient/Command std_msgs/Int32 5;
+else rostopic pub -1 /$ROS_NAMESPACE/FlyingAgentClient/Command std_msgs/Int32 5;
 fi
 
diff --git a/dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie b/dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie
index 0bc0d306..6491218d 100755
--- a/dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie
+++ b/dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie
@@ -2,6 +2,6 @@
 
 if [ "$#" -ne 0 ]
 then echo "usage: take_off crazyfly <no arguments>"
-else rostopic pub -1 /$ROS_NAMESPACE/PPSClient/Command std_msgs/Int32 3;
+else rostopic pub -1 /$ROS_NAMESPACE/FlyingAgentClient/Command std_msgs/Int32 3;
 fi
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
index 24787c0d..f83abf9a 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
@@ -405,11 +405,12 @@ int main(int argc, char* argv[])
 	// Starting the ROS-node
 	ros::init(argc, argv, "BatteryMonitor");
 
-	// Create a "ros::NodeHandle" type local variable named "nodeHandle",
-	// the "~" indcates that "self" is the node handle assigned.
+	// Create a "ros::NodeHandle" type local variable "nodeHandle"
+	// as the current node, the "~" indcates that "self" is the
+	// node handle assigned to this variable.
 	ros::NodeHandle nodeHandle("~");
 
-	// Get the namespace of this node
+	// Get the namespace of this "BatteryMonitor" node
 	std::string m_namespace = ros::this_node::getNamespace();
 	ROS_INFO_STREAM("[BATTERY MONITOR] ros::this_node::getNamespace() =  " << m_namespace);
 
@@ -417,8 +418,19 @@ int main(int argc, char* argv[])
 
 	// AGENT ID AND COORDINATOR ID
 
+	// NOTES:
+	// > If you look at the "Agent.launch" file in the "launch" folder,
+	//   you will see the following line of code:
+	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
+	//   This line of code adds a parameter named "agentID" to the
+	//   "FlyingAgentClient" node.
+	// > Thus, to get access to this "agentID" paremeter, we first
+	//   need to get a handle to the "FlyingAgentClient" node within which this
+	//   controller service is nested.
+
+
 	// Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
@@ -435,6 +447,19 @@ int main(int argc, char* argv[])
 
 	// PARAMETER SERVICE NAMESPACE AND NODEHANDLES:
 
+	// NOTES:
+	// > The parameters that are specified thorugh the *.yaml files
+	//   are managed by a separate node called the "Parameter Service"
+	// > A separate node is used for reasons of speed and generality
+	// > To allow for a distirbuted architecture, there are two
+	//   "ParamterService" nodes that are relevant:
+	//   1) the one that is nested under the "m_agentID" namespace
+	//   2) the one that is nested under the "m_coordID" namespace
+	// > The following lines of code create the namespace (as strings)
+	//   to there two relevant "ParameterService" nodes.
+	// > The node handles are also created because they are needed
+	//   for the ROS Subscriptions that follow.
+
 	// Set the class variable "m_namespace_to_own_agent_parameter_service",
 	// i.e., the namespace of parameter service for this agent
 	m_namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
@@ -455,7 +480,7 @@ int main(int argc, char* argv[])
 
 	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
 
-	// The parameters service publish messages with names of the form:
+	// The parameter service publishes messages with names of the form:
 	// /dfall/.../ParameterService/<filename with .yaml extension>
 	ros::Subscriber batteryMonitor_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "BatteryMonitor", 1, isReadyBatteryMonitorYamlCallback);
 	ros::Subscriber batteryMonitor_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("BatteryMonitor", 1, isReadyBatteryMonitorYamlCallback);
@@ -487,9 +512,9 @@ int main(int argc, char* argv[])
 	std::string namespace_to_crazyradio = m_namespace + "/CrazyRadio";
     ros::NodeHandle nodeHandle_to_crazyradio(namespace_to_crazyradio);
 
-    // Get a node handle to the PPS Client
-	std::string namespace_to_ppsclient = m_namespace + "/PPSClient";
-    ros::NodeHandle nodeHandle_to_ppsclient(namespace_to_ppsclient);
+    // Get a node handle to the Flying Agent Client
+	std::string namespace_to_FlyingAgentClient = m_namespace + "/FlyingAgentClient";
+    ros::NodeHandle nodeHandle_to_FlyingAgentClient(namespace_to_FlyingAgentClient);
 
 	// Subscribe to the voltage of the battery
 	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle_to_crazyradio.subscribe("CFBattery", 1, newBatteryVoltageCallback);
@@ -498,7 +523,7 @@ int main(int argc, char* argv[])
 	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle_to_crazyradio.subscribe("CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
 	// Subscribe to the flying state of the agent
-	ros::Subscriber agentOperatingStateSubscriber = nodeHandle_to_ppsclient.subscribe("flyingState", 1, agentOperatingStateCallback);
+	ros::Subscriber agentOperatingStateSubscriber = nodeHandle_to_FlyingAgentClient.subscribe("flyingState", 1, agentOperatingStateCallback);
 
 	// Initialise the operating state
 	m_agent_operating_state = AGENT_OPERATING_STATE_MOTORS_OFF;
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 2dedaf61..20a5397d 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -170,7 +170,7 @@
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
 {
 
@@ -214,7 +214,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	float stateErrorBody[9];
 	convertIntoBodyFrame(stateErrorInertial, stateErrorBody, request.ownCrazyflie.yaw);
 
@@ -424,7 +424,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 // This is the yaw component of the intrinsic Euler angles in [radians] as measured by
 // the Vicon motion capture system
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
 {
 
@@ -782,8 +782,8 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //    ----------------------------------------------------------------------------------
 
 
-int main(int argc, char* argv[]) {
-
+int main(int argc, char* argv[])
+{
 	// Starting the ROS-node
 	ros::init(argc, argv, "DefaultControllerService");
 
@@ -805,14 +805,14 @@ int main(int argc, char* argv[]) {
 	//   you will see the following line of code:
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
-	//   "PPSClient" node.
+	//   "FlyingAgentClient" node.
 	// > Thus, to get access to this "agentID" paremeter, we first
-	//   need to get a handle to the "PPSClient" node within which this
+	//   need to get a handle to the "FlyingAgentClient" node within which this
 	//   controller service is nested.
 
 
 	// Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
index bfc3bebc..ded12476 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
@@ -169,7 +169,7 @@
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
 {
 
@@ -1259,7 +1259,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 }
 
@@ -1280,7 +1280,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float computeMotorPolyBackward(float thrust)
 {
 	// Compute the 16-bit command signal that generates the "thrust" force
@@ -1316,7 +1316,7 @@ float computeMotorPolyBackward(float thrust)
 //     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void setpointCallback(const Setpoint& newSetpoint)
 {
     setpoint[0] = newSetpoint.x;
@@ -1327,7 +1327,7 @@ void setpointCallback(const Setpoint& newSetpoint)
 
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // > This function is called anytime a message is published on the topic to which the
 //   class instance variable "xyz_yaw_to_follow_subscriber" is subscribed
 void xyz_yaw_to_follow_callback(const Setpoint& newSetpoint)
@@ -1499,7 +1499,7 @@ void isReadyDemoControllerYamlCallback(const IntWithHeader & msg)
 
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters fetched from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void fetchDemoControllerYamlParameters(ros::NodeHandle& nodeHandle)
@@ -1627,7 +1627,7 @@ void fetchDemoControllerYamlParameters(ros::NodeHandle& nodeHandle)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters loaded from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void processFetchedParameters()
@@ -1734,7 +1734,7 @@ void processFetchedParameters()
 //    M   M  A   A  III  N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int main(int argc, char* argv[]) {
 
 	// Starting the ROS-node
@@ -1757,14 +1757,14 @@ int main(int argc, char* argv[]) {
 	//   you will see the following line of code:
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
-	//   "PPSClient" node.
+	//   "FlyingAgentClient" node.
 	// > Thus, to get access to this "studentID" paremeter, we first
-	//   need to get a handle to the "PPSClient" node within which this
+	//   need to get a handle to the "FlyingAgentClient" node within which this
 	//   controller service is nested.
 
 
 	// Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PPSClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
similarity index 84%
rename from dfall_ws/src/dfall_pkg/src/nodes/PPSClient.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 3e6a8057..467973ab 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/PPSClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -34,7 +34,7 @@
 
 
 // INCLUDE THE HEADER
-#include "nodes/PPSClient.h"
+#include "nodes/FlyingAgentClient.h"
 
 
 
@@ -65,15 +65,15 @@
 bool safetyCheck(CrazyflieData data, ControlCommand controlCommand) {
 	//position check
 	if((data.x < context.localArea.xmin) or (data.x > context.localArea.xmax)) {
-		ROS_INFO_STREAM("[PPS CLIENT] x safety failed");
+		ROS_INFO_STREAM("[FLYING AGENT CLIENT] x safety failed");
 		return false;
 	}
 	if((data.y < context.localArea.ymin) or (data.y > context.localArea.ymax)) {
-		ROS_INFO_STREAM("[PPS CLIENT] y safety failed");
+		ROS_INFO_STREAM("[FLYING AGENT CLIENT] y safety failed");
 		return false;
 	}
 	if((data.z < context.localArea.zmin) or (data.z > context.localArea.zmax)) {
-		ROS_INFO_STREAM("[PPS CLIENT] z safety failed");
+		ROS_INFO_STREAM("[FLYING AGENT CLIENT] z safety failed");
 		return false;
 	}
 
@@ -82,11 +82,11 @@ bool safetyCheck(CrazyflieData data, ControlCommand controlCommand) {
 	//the angleMargin is a value in the range (0,1). The closer to 1, the closer to 90 deg are the roll and pitch angles allowed to become before the safeController takes over
 	if(yaml_strictSafety){
 		if((data.roll > PI/2*yaml_angleMargin) or (data.roll < -PI/2*yaml_angleMargin)) {
-			ROS_INFO_STREAM("[PPS CLIENT] roll too big.");
+			ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
 			return false;
 		}
 		if((data.pitch > PI/2*yaml_angleMargin) or (data.pitch < -PI/2*yaml_angleMargin)) {
-			ROS_INFO_STREAM("[PPS CLIENT] pitch too big.");
+			ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
 			return false;
 		}
 	}
@@ -137,11 +137,11 @@ void takeOffCF(CrazyflieData& current_local_coordinates) //local because the set
     // setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
     setpoint_msg.yaw = 0.0;
     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-    ROS_INFO("[PPS CLIENT] Take OFF:");
-    ROS_INFO("[PPS CLIENT] ------Current coordinates:");
-    ROS_INFO("[PPS CLIENT] X: %f, Y: %f, Z: %f", current_local_coordinates.x, current_local_coordinates.y, current_local_coordinates.z);
-    ROS_INFO("[PPS CLIENT] ------New coordinates:");
-    ROS_INFO("[PPS CLIENT] X: %f, Y: %f, Z: %f", setpoint_msg.x, setpoint_msg.y, setpoint_msg.z);
+    ROS_INFO("[FLYING AGENT CLIENT] Take OFF:");
+    ROS_INFO("[FLYING AGENT CLIENT] ------Current coordinates:");
+    ROS_INFO("[FLYING AGENT CLIENT] X: %f, Y: %f, Z: %f", current_local_coordinates.x, current_local_coordinates.y, current_local_coordinates.z);
+    ROS_INFO("[FLYING AGENT CLIENT] ------New coordinates:");
+    ROS_INFO("[FLYING AGENT CLIENT] X: %f, Y: %f, Z: %f", setpoint_msg.x, setpoint_msg.y, setpoint_msg.z);
 
     // now, use safe controller to go to that setpoint
     loadSafeController();
@@ -172,12 +172,12 @@ void changeFlyingStateTo(int new_state)
 {
     if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
     {
-        ROS_INFO("[PPS CLIENT] Change state to: %d", new_state);
+        ROS_INFO("[FLYING AGENT CLIENT] Change state to: %d", new_state);
         flying_state = new_state;
     }
     else
     {
-        ROS_INFO("[PPS CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
+        ROS_INFO("[FLYING AGENT CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
         flying_state = STATE_MOTORS_OFF;
     }
 
@@ -226,7 +226,7 @@ void viconCallback(const ViconData& viconData)
                     if(changed_state_flag) // stuff that will be run only once when changing state
                     {
                         changed_state_flag = false;
-                        ROS_INFO("[PPS CLIENT] STATE_MOTORS_OFF");
+                        ROS_INFO("[FLYING AGENT CLIENT] STATE_MOTORS_OFF");
                     }
                     break;
                 case STATE_TAKE_OFF: //we need to move up from where we are now.
@@ -235,7 +235,7 @@ void viconCallback(const ViconData& viconData)
                         changed_state_flag = false;
                         takeOffCF(local);
                         finished_take_off = false;
-                        ROS_INFO("[PPS CLIENT] STATE_TAKE_OFF");
+                        ROS_INFO("[FLYING AGENT CLIENT] STATE_TAKE_OFF");
                         timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_take_off), takeOffTimerCallback, true);
                     }
                     if(finished_take_off)
@@ -251,7 +251,7 @@ void viconCallback(const ViconData& viconData)
                         changed_state_flag = false;
                         // need to change setpoint to the controller one
                         goToControllerSetpoint();
-                        ROS_INFO("[PPS CLIENT] STATE_FLYING");
+                        ROS_INFO("[FLYING AGENT CLIENT] STATE_FLYING");
                     }
                     break;
                 case STATE_LAND:
@@ -260,7 +260,7 @@ void viconCallback(const ViconData& viconData)
                         changed_state_flag = false;
                         landCF(local);
                         finished_land = false;
-                        ROS_INFO("[PPS CLIENT] STATE_LAND");
+                        ROS_INFO("[FLYING AGENT CLIENT] STATE_LAND");
                         timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_landing), landTimerCallback, true);
                     }
                     if(finished_land)
@@ -308,22 +308,22 @@ void viconCallback(const ViconData& viconData)
                                 success = pickerController.call(controllerCall);
                                 break;
                             default:
-                                ROS_ERROR("[PPS CLIENT] the current controller was not recognised");
+                                ROS_ERROR("[FLYING AGENT CLIENT] the current controller was not recognised");
                                 break;
                         }
 
                         // Ensure success and enforce safety
                         if(!success)
                         {
-                            ROS_ERROR("[PPS CLIENT] Failed to call a 'non-safe' controller, switching to safe controller");
-                            //ROS_ERROR_STREAM("[PPS CLIENT] 'non-safe' controller status: valid: " << demoController.isValid() << ", exists: " << demoController.exists());
-                            //ROS_ERROR_STREAM("[PPS CLIENT] 'non-safe' controller name: " << demoController.getService());
+                            ROS_ERROR("[FLYING AGENT CLIENT] Failed to call a 'non-safe' controller, switching to safe controller");
+                            //ROS_ERROR_STREAM("[FLYING AGENT CLIENT] 'non-safe' controller status: valid: " << demoController.isValid() << ", exists: " << demoController.exists());
+                            //ROS_ERROR_STREAM("[FLYING AGENT CLIENT] 'non-safe' controller name: " << demoController.getService());
                             setInstantController(SAFE_CONTROLLER);
                         }
                         else if(!safetyCheck(global, controllerCall.response.controlOutput))
                         {
                             setInstantController(SAFE_CONTROLLER);
-                            ROS_INFO_STREAM("[PPS CLIENT] safety check failed, switching to safe controller");
+                            ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
                         }
 
                         
@@ -362,7 +362,7 @@ void viconCallback(const ViconData& viconData)
 
                         bool success = safeController.call(controllerCall);
                         if(!success) {
-                            ROS_ERROR_STREAM("[PPS CLIENT] Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
+                            ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
                         }
                     }
 
@@ -394,7 +394,7 @@ void viconCallback(const ViconData& viconData)
 void loadCrazyflieContext() {
 	CMQuery contextCall;
 	contextCall.request.studentID = m_agentID;
-	ROS_INFO_STREAM("[PPS CLIENT] AgentID:" << m_agentID);
+	ROS_INFO_STREAM("[FLYING AGENT CLIENT] AgentID:" << m_agentID);
 
     CrazyflieContext new_context;
 
@@ -402,7 +402,7 @@ void loadCrazyflieContext() {
 
 	if(centralManager.call(contextCall)) {
 		new_context = contextCall.response.crazyflieContext;
-		ROS_INFO_STREAM("[PPS CLIENT] CrazyflieContext:\n" << new_context);
+		ROS_INFO_STREAM("[FLYING AGENT CLIENT] CrazyflieContext:\n" << new_context);
 
         if((context.crazyflieName != "") && (new_context.crazyflieName != context.crazyflieName)) //linked crazyflie name changed and it was not empty before
         {
@@ -414,7 +414,7 @@ void loadCrazyflieContext() {
             // msg.data = CMD_CRAZYFLY_MOTORS_OFF;
             // commandPublisher.publish(msg);
 
-            ROS_INFO("[PPS CLIENT] CF is now different for this student. Disconnect and turn it off");
+            ROS_INFO("[FLYING AGENT CLIENT] CF is now different for this student. Disconnect and turn it off");
 
             IntWithHeader msg;
             msg.shouldCheckForID = false;
@@ -429,7 +429,7 @@ void loadCrazyflieContext() {
 	}
     else
     {
-		ROS_ERROR("[PPS CLIENT] Failed to load context. Waiting for next Save in DB by teacher");
+		ROS_ERROR("[FLYING AGENT CLIENT] Failed to load context. Waiting for next Save in DB by teacher");
 	}
 }
 
@@ -448,42 +448,42 @@ void commandCallback(const IntWithHeader & msg) {
 
     	switch(cmd) {
         	case CMD_USE_SAFE_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_SAFE_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_SAFE_CONTROLLER Command received");
                 setControllerUsed(SAFE_CONTROLLER);
         		break;
 
         	case CMD_USE_DEMO_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_DEMO_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_DEMO_CONTROLLER Command received");
                 setControllerUsed(DEMO_CONTROLLER);
         		break;
 
             case CMD_USE_STUDENT_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_STUDENT_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_STUDENT_CONTROLLER Command received");
                 setControllerUsed(STUDENT_CONTROLLER);
                 break;
 
             case CMD_USE_MPC_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_MPC_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_MPC_CONTROLLER Command received");
                 setControllerUsed(MPC_CONTROLLER);
                 break;
 
             case CMD_USE_REMOTE_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_REMOTE_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_REMOTE_CONTROLLER Command received");
                 setControllerUsed(REMOTE_CONTROLLER);
                 break;
 
             case CMD_USE_TUNING_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_TUNING_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_TUNING_CONTROLLER Command received");
                 setControllerUsed(TUNING_CONTROLLER);
                 break;
 
             case CMD_USE_PICKER_CONTROLLER:
-                ROS_INFO("[PPS CLIENT] USE_PICKER_CONTROLLER Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] USE_PICKER_CONTROLLER Command received");
                 setControllerUsed(PICKER_CONTROLLER);
                 break;
 
         	case CMD_CRAZYFLY_TAKE_OFF:
-                ROS_INFO("[PPS CLIENT] TAKE_OFF Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] TAKE_OFF Command received");
                 if(flying_state == STATE_MOTORS_OFF)
                 {
                     changeFlyingStateTo(STATE_TAKE_OFF);
@@ -491,19 +491,19 @@ void commandCallback(const IntWithHeader & msg) {
         		break;
 
         	case CMD_CRAZYFLY_LAND:
-                ROS_INFO("[PPS CLIENT] LAND Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] LAND Command received");
                 if(flying_state != STATE_MOTORS_OFF)
                 {
                     changeFlyingStateTo(STATE_LAND);
                 }
         		break;
             case CMD_CRAZYFLY_MOTORS_OFF:
-                ROS_INFO("[PPS CLIENT] MOTORS_OFF Command received");
+                ROS_INFO("[FLYING AGENT CLIENT] MOTORS_OFF Command received");
                 changeFlyingStateTo(STATE_MOTORS_OFF);
                 break;
 
         	default:
-        		ROS_ERROR_STREAM("[PPS CLIENT] unexpected command number: " << cmd);
+        		ROS_ERROR_STREAM("[FLYING AGENT CLIENT] unexpected command number: " << cmd);
         		break;
     	}
     }
@@ -511,13 +511,13 @@ void commandCallback(const IntWithHeader & msg) {
 
 void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg)
 {
-    ROS_INFO("[PPS CLIENT] Received message that the Context Database Changed");
+    ROS_INFO("[FLYING AGENT CLIENT] Received message that the Context Database Changed");
     loadCrazyflieContext();
 }
 
 void emergencyStopCallback(const IntWithHeader & msg)
 {
-    ROS_INFO("[PPS CLIENT] Received message to EMERGENCY STOP");
+    ROS_INFO("[FLYING AGENT CLIENT] Received message to EMERGENCY STOP");
     commandCallback(msg);
 }
 
@@ -528,7 +528,7 @@ void emergencyStopCallback(const IntWithHeader & msg)
 
 void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 {
-    ROS_INFO_STREAM("[PPS CLIENT] Received message with Crazy Radio Status = " << msg.data );
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Received message with Crazy Radio Status = " << msg.data );
     crazyradio_status = msg.data;
     // RESET THE BATTERY STATE IF DISCONNECTED
     //if (crazyradio_status == CRAZY_RADIO_STATE_DISCONNECTED)
@@ -597,13 +597,13 @@ void loadSafeController() {
 
     std::string safeControllerName;
     if(!nodeHandle.getParam("safeController", safeControllerName)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get safe controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get safe controller name");
         return;
     }
 
     ros::service::waitForService(safeControllerName);
     safeController = ros::service::createClient<Controller>(safeControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] loaded safe controller: " << safeController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] loaded safe controller: " << safeController.getService());
 }
 
 void loadDemoController()
@@ -615,12 +615,12 @@ void loadDemoController()
     std::string demoControllerName;
     if(!nodeHandle.getParam("demoController", demoControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get demo controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get demo controller name");
         return;
     }
 
     demoController = ros::service::createClient<Controller>(demoControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded demo controller " << demoController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded demo controller " << demoController.getService());
 }
 
 void loadStudentController()
@@ -632,12 +632,12 @@ void loadStudentController()
     std::string studentControllerName;
     if(!nodeHandle.getParam("studentController", studentControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get student controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get student controller name");
         return;
     }
 
     studentController = ros::service::createClient<Controller>(studentControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded student controller " << studentController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded student controller " << studentController.getService());
 }
 
 void loadMpcController()
@@ -649,12 +649,12 @@ void loadMpcController()
     std::string mpcControllerName;
     if(!nodeHandle.getParam("mpcController", mpcControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get mpc controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get mpc controller name");
         return;
     }
 
     mpcController = ros::service::createClient<Controller>(mpcControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded mpc controller " << mpcController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded mpc controller " << mpcController.getService());
 }
 
 void loadRemoteController()
@@ -666,12 +666,12 @@ void loadRemoteController()
     std::string remoteControllerName;
     if(!nodeHandle.getParam("remoteController", remoteControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get remote controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get remote controller name");
         return;
     }
 
     remoteController = ros::service::createClient<Controller>(remoteControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded remote controller " << remoteController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded remote controller " << remoteController.getService());
 }
 
 void loadTuningController()
@@ -683,12 +683,12 @@ void loadTuningController()
     std::string tuningControllerName;
     if(!nodeHandle.getParam("tuningController", tuningControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get tuning controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get tuning controller name");
         return;
     }
 
     tuningController = ros::service::createClient<Controller>(tuningControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded tuning controller " << tuningController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded tuning controller " << tuningController.getService());
 }
 
 void loadPickerController()
@@ -700,12 +700,12 @@ void loadPickerController()
     std::string pickerControllerName;
     if(!nodeHandle.getParam("pickerController", pickerControllerName))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get picker controller name");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get picker controller name");
         return;
     }
 
     pickerController = ros::service::createClient<Controller>(pickerControllerName, true);
-    ROS_INFO_STREAM("[PPS CLIENT] Loaded picker controller " << pickerController.getService());
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded picker controller " << pickerController.getService());
 }
 
 void sendMessageUsingController(int controller)
@@ -793,21 +793,21 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
     {
         if (flying_state != STATE_MOTORS_OFF)
         {
-            ROS_INFO("[PPS CLIENT] low level battery triggered, now landing.");
+            ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered, now landing.");
             changeFlyingStateTo(STATE_LAND);
         }
         else
         {
-            ROS_INFO("[PPS CLIENT] low level battery triggered, please turn off the Crazyflie.");
+            ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered, please turn off the Crazyflie.");
         }
     }
     else if (new_battery_state == BATTERY_STATE_NORMAL)
     {
-        ROS_INFO("[PPS CLIENT] received message that battery state changed to normal");
+        ROS_INFO("[FLYING AGENT CLIENT] received message that battery state changed to normal");
     }
     else
     {
-        ROS_INFO("[PPS CLIENT] received message that battery state changed to something unknown");
+        ROS_INFO("[FLYING AGENT CLIENT] received message that battery state changed to something unknown");
     }
     
 }
@@ -827,16 +827,16 @@ void setBatteryStateTo(int new_battery_state)
     {
         case BATTERY_STATE_NORMAL:
             m_battery_state = BATTERY_STATE_NORMAL;
-            ROS_INFO("[PPS CLIENT] changed battery state to normal");
+            ROS_INFO("[FLYING AGENT CLIENT] changed battery state to normal");
             break;
         case BATTERY_STATE_LOW:
             m_battery_state = BATTERY_STATE_LOW;
-            ROS_INFO("[PPS CLIENT] changed battery state to low");
+            ROS_INFO("[FLYING AGENT CLIENT] changed battery state to low");
             if(flying_state != STATE_MOTORS_OFF)
                 changeFlyingStateTo(STATE_LAND);
             break;
         default:
-            ROS_INFO("[PPS CLIENT] Unknown battery state command, set to normal");
+            ROS_INFO("[FLYING AGENT CLIENT] Unknown battery state command, set to normal");
             m_battery_state = BATTERY_STATE_NORMAL;
             break;
     }
@@ -889,7 +889,7 @@ void CFBatteryCallback(const std_msgs::Float32& msg)
         if(getBatteryState() != BATTERY_STATE_LOW)
         {
             setBatteryStateTo(BATTERY_STATE_LOW);
-            ROS_INFO("[PPS CLIENT] low level battery triggered");
+            ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered");
         }
         
     }
@@ -977,21 +977,21 @@ void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
             // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
             case LOAD_YAML_FROM_AGENT:
             {
-                ROS_INFO("[PPS CLIENT] Now fetching the SafeController YAML parameter values from this agent.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the SafeController YAML parameter values from this agent.");
                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
                 break;
             }
             // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
             case LOAD_YAML_FROM_COORDINATOR:
             {
-                ROS_INFO("[PPS CLIENT] Now fetching the SafeController YAML parameter values from this agent's coordinator.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the SafeController YAML parameter values from this agent's coordinator.");
                 namespace_to_use = m_namespace_to_coordinator_parameter_service;
                 break;
             }
 
             default:
             {
-                ROS_ERROR("[PPS CLIENT] Paramter service to load from was NOT recognised.");
+                ROS_ERROR("[FLYING AGENT CLIENT] Paramter service to load from was NOT recognised.");
                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
                 break;
             }
@@ -1024,7 +1024,7 @@ void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
     getParameterFloatVector(nodeHandle_for_paramaters,"defaultSetpoint",yaml_default_setpoint,4);
 
     // DEBUGGING: Print out one of the parameters that was loaded
-    ROS_INFO_STREAM("[PPS CLIENT] DEBUGGING: the fetched SafeController/durationTakeOff = " << yaml_duration_take_off);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched SafeController/durationTakeOff = " << yaml_duration_take_off);
 
     /*
     // Here we load the parameters that are specified in the SafeController.yaml file
@@ -1034,27 +1034,27 @@ void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
 
     if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get takeOffDistance");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get takeOffDistance");
     }
 
     if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get landing_distance");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get landing_distance");
     }
 
     if(!nodeHandle_for_safeController.getParam("durationTakeOff", duration_take_off))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get duration_take_off");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_take_off");
     }
 
     if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get duration_landing");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_landing");
     }
 
     if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
     {
-        ROS_ERROR("[PPS CLIENT] Failed to get distance_threshold");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get distance_threshold");
     }
     */
 }
@@ -1080,21 +1080,21 @@ void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
             // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
             case LOAD_YAML_FROM_AGENT:
             {
-                ROS_INFO("[PPS CLIENT] Now fetching the ClientConfig YAML parameter values from this agent.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the ClientConfig YAML parameter values from this agent.");
                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
                 break;
             }
             // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
             case LOAD_YAML_FROM_COORDINATOR:
             {
-                ROS_INFO("[PPS CLIENT] Now fetching the ClientConfig YAML parameter values from this agent's coordinator.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the ClientConfig YAML parameter values from this agent's coordinator.");
                 namespace_to_use = m_namespace_to_coordinator_parameter_service;
                 break;
             }
 
             default:
             {
-                ROS_ERROR("[PPS CLIENT] Paramter service to load from was NOT recognised.");
+                ROS_ERROR("[FLYING AGENT CLIENT] Paramter service to load from was NOT recognised.");
                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
                 break;
             }
@@ -1124,26 +1124,26 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 
 
     // DEBUGGING: Print out one of the parameters that was loaded
-    ROS_INFO_STREAM("[PPS CLIENT] DEBUGGING: the fetched ClientConfig/strictSafety = " << yaml_strictSafety);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched ClientConfig/strictSafety = " << yaml_strictSafety);
 
 
     /*
     if(!nodeHandle.getParam("strictSafety", strictSafety)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get strictSafety param");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get strictSafety param");
         return;
     }
     if(!nodeHandle.getParam("angleMargin", angleMargin)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get angleMargin param");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get angleMargin param");
         return;
     }
 
 
     if(!nodeHandle.getParam("battery_threshold_while_flying", m_battery_threshold_while_flying)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get battery_threshold_while_flying param");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get battery_threshold_while_flying param");
         return;
     }
     if(!nodeHandle.getParam("battery_threshold_while_motors_off", m_battery_threshold_while_motors_off)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get battery_threshold_while_motors_off param");
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get battery_threshold_while_motors_off param");
         return;
     }
     */
@@ -1164,7 +1164,7 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 int main(int argc, char* argv[])
 {
     // Starting the ROS-node
-	ros::init(argc, argv, "PPSClient");
+	ros::init(argc, argv, "FlyingAgentClient");
 
     // Create a "ros::NodeHandle" type local variable named "nodeHandle",
     // the "~" indcates that "self" is the node handle assigned.
@@ -1172,24 +1172,24 @@ int main(int argc, char* argv[])
 
     // Get the namespace of this node
     std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[PPS Client] ros::this_node::getNamespace() =  " << m_namespace);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] ros::this_node::getNamespace() =  " << m_namespace);
 
 
 
     // AGENT ID AND COORDINATOR ID
 
     // Get the ID of the agent and its coordinator
-    bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+    bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
     // Stall the node IDs are not valid
     if ( !isValid_IDs )
     {
-        ROS_ERROR("[PPS Client] Node NOT FUNCTIONING :-)");
+        ROS_ERROR("[FLYING AGENT CLIENT] Node NOT FUNCTIONING :-)");
         ros::spin();
     }
     else
     {
-        ROS_INFO_STREAM("[PPS Client] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
     }
 
 
@@ -1205,8 +1205,8 @@ int main(int argc, char* argv[])
     constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
     // Inform the user of what namespaces are being used
-    ROS_INFO_STREAM("[PPS Client] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
-    ROS_INFO_STREAM("[PPS Client] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
 
     // Create, as local variables, node handles to the parameters services
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
@@ -1327,7 +1327,7 @@ int main(int argc, char* argv[])
 	//ros::Publishers to advertise the control output
 	controlCommandPublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
-	//this topic lets the PPSClient listen to the terminal commands
+	//this topic lets the FlyingAgentClient listen to the terminal commands
     //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
 
 
@@ -1337,7 +1337,7 @@ int main(int argc, char* argv[])
     // > for the agent GUI
     ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, commandCallback);
     // > for the coord GUI
-    ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("PPSClient/Command", 1, commandCallback);
+    ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("FlyingAgentClient/Command", 1, commandCallback);
 
 
 
@@ -1423,7 +1423,7 @@ int main(int argc, char* argv[])
 	// std::string package_path;
 	// package_path = ros::package::getPath("dfall_pkg") + "/";
 	// ROS_INFO_STREAM(package_path);
-	// std::string record_file = package_path + "LoggingPPSClient.bag";
+	// std::string record_file = package_path + "LoggingFlyingAgentClient.bag";
 	// bag.open(record_file, rosbag::bagmode::Write);
 
     ros::spin();
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
index 5aa78721..216676d5 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
@@ -317,7 +317,7 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&st
 // IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
 // > The allowed values for "onboardControllerType" are in the "Defines" section at the
 //   top of this file, they are MOTOR_MODE, RATE_MODE, OR ANGLE_MODE.
-// > In the PPS exercise we will only use the RATE_MODE.
+// > In the classroom exercise we will only use the RATE_MODE.
 // > In RATE_MODE the ".roll", ".ptich", and ".yaw" properties of "response.ControlCommand"
 //   specify the angular rate in [radians/second] that will be requested from the
 //   PID controllers running in the Crazyflie 2.0 firmware.
@@ -361,7 +361,7 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&st
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 
 void angleControlledCrazyflie(float stateInertial[12], float input_angle[4], int Ts_div, Controller::Response &response)
 {
@@ -599,7 +599,7 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter(float (&st
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float computeMotorPolyBackward(float thrust)
 {
     return (-motorPoly[1] + sqrt(motorPoly[1] * motorPoly[1] - 4 * motorPoly[2] * (motorPoly[0] - thrust))) / (2 * motorPoly[2]);
@@ -623,7 +623,7 @@ float computeMotorPolyBackward(float thrust)
 //     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void setpointCallback(const Setpoint& newSetpoint)
 {
     setpoint[0] = newSetpoint.x;
@@ -650,7 +650,7 @@ void setpointCallback(const Setpoint& newSetpoint)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 {
 	// Extract from the "msg" for which controller the and from where to fetch the YAML
@@ -696,7 +696,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters fetched from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void fetchYamlParameters(ros::NodeHandle& nodeHandle)
@@ -746,7 +746,7 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters loaded from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void processFetchedParameters()
@@ -769,7 +769,7 @@ void processFetchedParameters()
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
 {
     float val;
@@ -779,7 +779,7 @@ float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -789,7 +789,7 @@ void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std:
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
 {
     int val;
@@ -799,7 +799,7 @@ int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -809,7 +809,7 @@ void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::stri
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -817,7 +817,7 @@ int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::str
     }
     return val.size();
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 {
     bool val;
@@ -841,7 +841,7 @@ bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 //    M   M  A   A  III  N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int main(int argc, char* argv[]) {
     
     // Starting the ROS-node
@@ -860,16 +860,16 @@ int main(int argc, char* argv[]) {
     // > If you look at the "Student.launch" file in the "launch" folder, you will see
     //   the following line of code:
     //   <param name="studentID" value="$(optenv ROS_NAMESPACE)" />
-    //   This line of code adds a parameter named "studentID" to the "PPSClient"
+    //   This line of code adds a parameter named "studentID" to the "FlyingAgentClient"
     // > Thus, to get access to this "studentID" paremeter, we first need to get a handle
-    //   to the "PPSClient" node within which this controller service is nested.
-    // Get the handle to the "PPSClient" node
-    ros::NodeHandle PPSClient_nodeHandle(m_namespace + "/PPSClient");
+    //   to the "FlyingAgentClient" node within which this controller service is nested.
+    // Get the handle to the "FlyingAgentClient" node
+    ros::NodeHandle FlyingAgentClient_nodeHandle(m_namespace + "/FlyingAgentClient");
     // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
+    if(!FlyingAgentClient_nodeHandle.getParam("agentID", my_agentID))
     {
     	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[MPC CONTROLLER] Failed to get agentID from PPSClient");
+		ROS_ERROR("[MPC CONTROLLER] Failed to get agentID from FlyingAgentClient");
 	}
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index f814b8d0..59a38b1c 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -626,7 +626,7 @@ void smoothSetpointChanges()
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
 {
 
@@ -1086,7 +1086,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 }
 
@@ -1107,7 +1107,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float computeMotorPolyBackward(float thrust)
 {
 	// Compute the 16-bit command signal that generates the "thrust" force
@@ -1296,7 +1296,7 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 
 
 
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // void setpointCallback(const Setpoint& newSetpoint)
 // {
 //     m_setpoint[0] = newSetpoint.x;
@@ -1642,7 +1642,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //    ----------------------------------------------------------------------------------
 
 
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
 // {
 //     float val;
@@ -1652,7 +1652,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //     }
 //     return val;
 // }
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
 // {
 //     if(!nodeHandle.getParam(name, val)){
@@ -1662,7 +1662,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
 //     }
 // }
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
 // {
 //     int val;
@@ -1672,7 +1672,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //     }
 //     return val;
 // }
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
 // {
 //     if(!nodeHandle.getParam(name, val)){
@@ -1682,7 +1682,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
 //     }
 // }
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
 // {
 //     if(!nodeHandle.getParam(name, val)){
@@ -1690,7 +1690,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //     }
 //     return val.size();
 // }
-// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// // This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 // {
 //     bool val;
@@ -1714,7 +1714,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //    M   M  A   A  III  N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int main(int argc, char* argv[]) {
     
     // Starting the ROS-node
@@ -1738,14 +1738,14 @@ int main(int argc, char* argv[]) {
 	//   you will see the following line of code:
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
-	//   "PPSClient" node.
+	//   "FlyingAgentClient" node.
 	// > Thus, to get access to this "studentID" paremeter, we first
-	//   need to get a handle to the "PPSClient" node within which this
+	//   need to get a handle to the "FlyingAgentClient" node within which this
 	//   controller service is nested.
 
 
     // Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
index 2ae0b709..93f7d6cc 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
@@ -115,7 +115,7 @@
 // IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
 // > The allowed values for "onboardControllerType" are in the "Defines" section at the
 //   top of this file, they are MOTOR_MODE, RATE_MODE, OR ANGLE_MODE.
-// > In the PPS exercise we will only use the RATE_MODE.
+// > In the classroom exercise we will only use the RATE_MODE.
 // > In RATE_MODE the ".roll", ".ptich", and ".yaw" properties of "response.ControlCommand"
 //   specify the angular rate in [radians/second] that will be requested from the
 //   PID controllers running in the Crazyflie 2.0 firmware.
@@ -159,7 +159,7 @@
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 
 
 
@@ -1089,7 +1089,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 }
 
@@ -1110,7 +1110,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float computeMotorPolyBackward(float thrust)
 {
 	// Compute the 16-bit command signal that generates the "thrust" force
@@ -1146,7 +1146,7 @@ float computeMotorPolyBackward(float thrust)
 //     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void setpointCallback(const Setpoint& newSetpoint)
 {
     setpoint[0] = newSetpoint.x;
@@ -1211,7 +1211,7 @@ void setpointCallback(const Setpoint& newSetpoint)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 {
 	// Extract from the "msg" for which controller the and from where to fetch the YAML
@@ -1257,7 +1257,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters fetched from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void fetchYamlParameters(ros::NodeHandle& nodeHandle)
@@ -1385,7 +1385,7 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters loaded from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void processFetchedParameters()
@@ -1426,7 +1426,7 @@ void processFetchedParameters()
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
 {
     float val;
@@ -1436,7 +1436,7 @@ float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1446,7 +1446,7 @@ void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std:
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
 {
     int val;
@@ -1456,7 +1456,7 @@ int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1466,7 +1466,7 @@ void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::stri
         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
     }
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
 {
     if(!nodeHandle.getParam(name, val)){
@@ -1474,7 +1474,7 @@ int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::str
     }
     return val.size();
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 {
     bool val;
@@ -1484,7 +1484,7 @@ bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
     }
     return val;
 }
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 std::string getParameterString(ros::NodeHandle& nodeHandle, std::string name)
 {
 	std::string val;
@@ -1506,7 +1506,7 @@ std::string getParameterString(ros::NodeHandle& nodeHandle, std::string name)
 //    M   M  A   A  III  N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int main(int argc, char* argv[]) {
     
     // Starting the ROS-node
@@ -1526,16 +1526,16 @@ int main(int argc, char* argv[]) {
     // > If you look at the "Student.launch" file in the "launch" folder, you will see
     //   the following line of code:
     //   <param name="studentID" value="$(optenv ROS_NAMESPACE)" />
-    //   This line of code adds a parameter named "studentID" to the "PPSClient"
+    //   This line of code adds a parameter named "studentID" to the "FlyingAgentClient"
     // > Thus, to get access to this "studentID" paremeter, we first need to get a handle
-    //   to the "PPSClient" node within which this controller service is nested.
-    // Get the handle to the "PPSClient" node
-    ros::NodeHandle PPSClient_nodeHandle(m_namespace + "/PPSClient");
+    //   to the "FlyingAgentClient" node within which this controller service is nested.
+    // Get the handle to the "FlyingAgentClient" node
+    ros::NodeHandle FlyingAgentClient_nodeHandle(m_namespace + "/FlyingAgentClient");
     // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
+    if(!FlyingAgentClient_nodeHandle.getParam("agentID", my_agentID))
     {
     	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[REMOTE CONTROLLER] Failed to get agentID from PPSClient");
+		ROS_ERROR("[REMOTE CONTROLLER] Failed to get agentID from FlyingAgentClient");
 	}
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
index 968ecc3a..d1934a0f 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
@@ -232,7 +232,7 @@ void estimateState(Controller::Request &request, float (&est)[9])
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 {
     // Extract from the "msg" for which controller the and from where to fetch the YAML
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index 67ac27e2..f7d7eb78 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -170,7 +170,7 @@
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
 {
 
@@ -214,7 +214,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	float stateErrorBody[9];
 	convertIntoBodyFrame(stateErrorInertial, stateErrorBody, request.ownCrazyflie.yaw);
 
@@ -464,7 +464,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 // This is the yaw component of the intrinsic Euler angles in [radians] as measured by
 // the Vicon motion capture system
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
 {
 	// Fill in the (x,y,z) position estimates to be returned
@@ -847,14 +847,14 @@ int main(int argc, char* argv[]) {
 	//   you will see the following line of code:
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
-	//   "PPSClient" node.
+	//   "FlyingAgentClient" node.
 	// > Thus, to get access to this "agentID" paremeter, we first
-	//   need to get a handle to the "PPSClient" node within which this
+	//   need to get a handle to the "FlyingAgentClient" node within which this
 	//   controller service is nested.
 
 
 	// Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
index d62e2260..e20ab24b 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
@@ -115,7 +115,7 @@
 // IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
 // > The allowed values for "onboardControllerType" are in the "Defines" section at the
 //   top of this file, they are MOTOR_MODE, RATE_MODE, OR ANGLE_MODE.
-// > In the PPS exercise we will only use the RATE_MODE.
+// > In the classroom exercise we will only use the RATE_MODE.
 // > In RATE_MODE the ".roll", ".ptich", and ".yaw" properties of "response.ControlCommand"
 //   specify the angular rate in [radians/second] that will be requested from the
 //   PID controllers running in the Crazyflie 2.0 firmware.
@@ -159,7 +159,7 @@
 //
 //
 //
-// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+// This function WILL NEED TO BE edited for successful completion of the classroom exercise
 
 
 
@@ -1197,7 +1197,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	// > Note: the function "convertIntoBodyFrame" is implemented in this file
 	//   and by default does not perform any conversion. The equations to convert
 	//   the state error into the body frame should be implemented in that function
-	//   for successful completion of the PPS exercise
+	//   for successful completion of the classroom exercise
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 }
 
@@ -1218,7 +1218,7 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 float computeMotorPolyBackward(float thrust)
 {
 	// Compute the 16-bit command signal that generates the "thrust" force
@@ -1254,7 +1254,7 @@ float computeMotorPolyBackward(float thrust)
 //     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 // void setpointCallback(const Setpoint& newSetpoint)
 // {
 //     setpoint[0] = newSetpoint.x;
@@ -1402,7 +1402,7 @@ void isReadyTuningControllerYamlCallback(const IntWithHeader & msg)
 }
 
 
-// This function CAN BE edited for successful completion of the PPS exercise, and the
+// This function CAN BE edited for successful completion of the classroom exercise, and the
 // use of parameters fetched from the YAML file is highly recommended to make tuning of
 // your controller easier and quicker.
 void fetchTuningControllerYamlParameters(ros::NodeHandle& nodeHandle)
@@ -1564,7 +1564,7 @@ void fetchTuningControllerYamlParameters(ros::NodeHandle& nodeHandle)
 //    M   M  A   A  III  N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// This function DOES NOT NEED TO BE edited for successful completion of the classroom exercise
 int main(int argc, char* argv[]) {
     
     // Starting the ROS-node
@@ -1586,14 +1586,14 @@ int main(int argc, char* argv[]) {
 	//   you will see the following line of code:
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
-	//   "PPSClient" node.
+	//   "FlyingAgentClient" node.
 	// > Thus, to get access to this "agentID" paremeter, we first
-	//   need to get a handle to the "PPSClient" node within which this
+	//   need to get a handle to the "FlyingAgentClient" node within which this
 	//   controller service is nested.
 
 
 	// Get the ID of the agent and its coordinator
-	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
-- 
GitLab