From 50bb61edbfecca61d4e1c39400aba3ac26947fd9 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 5 Dec 2018 16:50:37 +0100
Subject: [PATCH 01/87] Started with add a Battery Monitor node

---
 .../d_fall_pps/include/nodes/BatteryMonitor.h | 161 ++++++++++
 .../src/d_fall_pps/param/BatteryMonitor.yaml  |  10 +
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   | 277 ++++++++++++++++++
 3 files changed, 448 insertions(+)
 create mode 100644 pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
 create mode 100755 pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
 create mode 100644 pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp

diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
new file mode 100644
index 00000000..7ee4abd0
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -0,0 +1,161 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The service that manages the loading of YAML parameters
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  N   N   CCCC  L      U   U  DDDD   EEEEE   SSSS
+//     I   NN  N  C      L      U   U  D   D  E      S
+//     I   N N N  C      L      U   U  D   D  EEE     SSS
+//     I   N  NN  C      L      U   U  D   D  E          S
+//    III  N   N   CCCC  LLLLL   UUU   DDDD   EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+#include <stdlib.h>
+#include <string>
+
+#include <ros/ros.h>
+#include <ros/package.h>
+#include <ros/network.h>
+#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+#include "d_fall_pps/Controller.h"
+#include "d_fall_pps/LoadYamlFiles.h"
+
+// Include the shared definitions
+#include "nodes/ParameterServiceDefinitions.h"
+
+
+//    ----------------------------------------------------------------------------------
+//    DDDD   EEEEE  FFFFF  III  N   N  EEEEE   SSSS
+//    D   D  E      F       I   NN  N  E      S
+//    D   D  EEE    FFF     I   N N N  EEE     SSS
+//    D   D  E      F       I   N  NN  E          S
+//    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// Battery states
+#define BATTERY_LEVEL_000            0
+#define BATTERY_LEVEL_010            1
+#define BATTERY_LEVEL_020            2
+#define BATTERY_LEVEL_030            3
+#define BATTERY_LEVEL_040            4
+#define BATTERY_LEVEL_050            5
+#define BATTERY_LEVEL_060            6
+#define BATTERY_LEVEL_070            7
+#define BATTERY_LEVEL_080            8
+#define BATTERY_LEVEL_090            9
+#define BATTERY_LEVEL_100           10
+#define BATTERY_LEVEL_UNAVAILABLE   -1
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+// CrazyRadio states:
+#define CRAZY_RADIO_STATE_CONNECTED      0
+#define CRAZY_RADIO_STATE_CONNECTING     1
+#define CRAZY_RADIO_STATE_DISCONNECTED   2
+
+
+// Flying states
+#define AGENT_OPERATING_STATE_MOTORS_OFF 1
+#define AGENT_OPERATING_STATE_TAKE_OFF   2
+#define AGENT_OPERATING_STATE_FLYING     3
+#define AGENT_OPERATING_STATE_LAND       4
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    V   V    A    RRRR   III    A    BBBB   L      EEEEE   SSSS
+//    V   V   A A   R   R   I    A A   B   B  L      E      S
+//    V   V  A   A  RRRR    I   A   A  BBBB   L      EEE     SSS
+//     V V   AAAAA  R  R    I   AAAAA  B   B  L      E          S
+//      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// The level of the battery
+int m_battery_level;
+
+// The status of the crazyradio as received via messages
+//int m_crazyradio_status;
+
+// The flying state of the agent, as received via messages
+int m_agent_operating_state;
+
+// Publisher for the filtered battery voltage
+ros::Publisher filteredBatteryVoltagePublisher;
+
+// Publisher for the battery state
+ros::Publisher batteryLevelPublisher;
+
+
+
+// VARIABLES THAT ARE LOADED FROM THE YAML FILE
+
+// Battery thresholds while in the "motors off" state, in [Volts]
+float m_battery_threshold_lower_while_standby = 3.30f;
+float m_battery_threshold_upper_while_standby = 4.20f;
+
+// Battery thresholds while in the "flying" state, in [Volts]
+float m_battery_threshold_lower_while_flying = 2.60f;
+float m_battery_threshold_upper_while_flying = 3.70f;
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    PPPP   RRRR    OOO   TTTTT   OOO   TTTTT  Y   Y  PPPP   EEEEE   SSSS
+//    P   P  R   R  O   O    T    O   O    T     Y Y   P   P  E      S
+//    PPPP   RRRR   O   O    T    O   O    T      Y    PPPP   EEE     SSS
+//    P      R  R   O   O    T    O   O    T      Y    P      E          S
+//    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+void newBatteryVoltageCallback(const std_msgs::Float32& msg);
+
+float fromVoltageToPercent(float voltage , float operating_state);
+
+int level convertVoltageToLevel(float voltage , float operating_state);
+
+
diff --git a/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml b/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
new file mode 100755
index 00000000..86b384ec
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
@@ -0,0 +1,10 @@
+# Battery thresholds while in the "motors off" state, in [Volts]
+battery_threshold_lower_while_standby: 3.30
+battery_threshold_upper_while_standby: 4.20
+
+# Battery thresholds while in the "flying" state, in [Volts]
+battery_threshold_lower_while_flying: 2.60
+battery_threshold_upper_while_flying: 3.70
+
+# Frequency of requesting the battery voltage, in [milliseconds]
+battery_polling_period: 200
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
new file mode 100644
index 00000000..b3bb4d0c
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -0,0 +1,277 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The service that manages the loading of YAML parameters
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// SPECIFY THE PACKAGE NAMESPACE
+using namespace d_fall_pps;
+//using namespace std;
+
+
+
+
+
+// INCLUDE THE HEADER
+#include "nodes/BatteryMonitor.h"
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    III M   M PPPP  L     EEEEE M   M EEEEE N   N TTTTT   A   TTTTT III  OOO  N   N
+//     I  MM MM P   P L     E     MM MM E     NN  N   T    A A    T    I  O   O NN  N
+//     I  M M M PPPP  L     EEE   M M M EEE   N N N   T   A   A   T    I  O   O N N N
+//     I  M   M P     L     E     M   M E     N  NN   T   AAAAA   T    I  O   O N  NN
+//    III M   M P     LLLLL EEEEE M   M EEEEE N   N   T   A   A   T   III  OOO  N   N
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
+//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
+//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
+//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
+//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+
+void crazyRadioStatusCallback(const std_msgs::Int32& msg)
+{
+	// Extract the data
+	int crazyradio_status = msg.data;
+
+	// I the Crazyradio DISCONNECTED
+	if (crazyradio_status == DISCONNECTED)
+	{
+		// Then publish that the battery level is unavailable
+		std_msgs::Int32 battery_level_msg;
+		battery_level_msg.data = BATTERY_LEVEL_UNAVAILABLE;
+		batteryLevelPublisher.publish(battery_level_msg);
+	}
+}
+
+
+
+void newBatteryVoltageCallback(const std_msgs::Float32& msg)
+{
+	// Extract the data
+	m_battery_voltage = msg.data;
+
+	// Provide the new measurement to the filter
+	float filtered_battery_voltage = newBatteryVoltageForFilter(m_battery_voltage); //need to perform filtering here
+
+	// Convert the filtered voltage to a percentage
+	// > Note that this depending on the operating state
+	float filtered_battery_voltage_as_percentage = convertVoltageToLevel(filtered_battery_voltage,m_agent_operating_state);
+
+	// Convert the battery percentage to a level
+	int filtered_battery_voltage_as_level = convertPercentageToLevel(filtered_battery_voltage_as_percentage);
+
+	// Then publish that the battery level is unavailable
+	std_msgs::Int32 battery_level_msg;
+	battery_level_msg.data = BATTERY_LEVEL_UNAVAILABLE;
+	batteryLevelPublisher.publish(battery_level_msg);
+
+	// ROS_INFO_STREAM("filtered data: " << filtered_battery_voltage);
+	if(
+		(flying_state != STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_flying))
+		||
+		(flying_state == STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_motors_off))
+	)
+	{
+		if(getBatteryState() != BATTERY_STATE_LOW)
+		{
+		setBatteryStateTo(BATTERY_STATE_LOW);
+		ROS_INFO("[PPS CLIENT] low level battery triggered");
+		}
+
+	}
+	else
+	{
+	// TO AVOID BEING ABLE TO IMMEDIATELY TAKE-OFF AFTER A
+	// "BATTERY LOW" EVENT IS TRIGGERED, WE DO NOT SET THE
+	// BATTERY STATE BACK TO NORMAL
+	// if(getBatteryState() != BATTERY_STATE_NORMAL)
+	// {
+	//     setBatteryStateTo(BATTERY_STATE_NORMAL);
+	// }
+	}
+}
+
+
+
+void agentOperatingStateCallback(const std_msgs::Int32& msg)
+{
+	// Extract the data
+	m_agent_operating_state = msg.data;
+}
+
+
+int convertPercentageToLevel(float percentage)
+{
+	// Iterate through the levels
+	for (i_level=0;i_level<10;i++)
+	{
+		// Compute the threshold for this level
+		float threshold = float(i_level) * 10.0f;
+		// Add a buffer to the threshold to prevent
+		// high frequency changes to the level
+		if (m_battery_level==i_level)
+		{
+			threshold += 2.0f;
+		}
+		// Return the current index if appropriate
+		if (percentage <= threshold)
+		{
+			return i_level;
+		}
+	}
+	// If the function made it to this point without
+	// returning, then the percentage is at or above
+	// the maximum level
+	return BATTERY_LEVEL_100;
+
+}
+
+
+// > For converting a voltage to a percentage, depending on the current "my_flying_state" value
+float fromVoltageToPercent(float voltage , float operating_state )
+{
+	// INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
+	float voltage_when_full;
+	float voltage_when_empty;
+
+	// COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
+	// THE CURRENT FLYING STATE
+	if (operating_state == STATE_MOTORS_OFF)
+	{
+		// Voltage limits for a "standby" type of state
+		voltage_when_empty = m_battery_threshold_lower_while_standby;
+		voltage_when_full  = m_battery_threshold_upper_while_standby;
+	}
+	else
+	{
+		// Voltage limits for a "flying" type of state
+		voltage_when_empty = m_battery_threshold_lower_while_flying;
+		voltage_when_full  = m_battery_threshold_upper_while_flying;
+	}
+
+	// COMPUTE THE PERCENTAGE
+	float percentage = 100.0f * (voltage-voltage_when_empty)/(voltage_when_full-voltage_when_empty);
+
+	// CLIP THE PERCENTAGE TO BE BETWEEN [0,100]
+	// > This should not happen to often
+	if(percentage > 100.0f)
+	{
+		percentage = 100.0f;
+	}
+	if(percentage < 0.0f)
+	{
+		percentage = 0.0f;
+	}
+
+	// RETURN THE PERCENTAGE
+	return percentage;
+}
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M    A    III  N   N
+//    MM MM   A A    I   NN  N
+//    M M M  A   A   I   N N N
+//    M   M  AAAAA   I   N  NN
+//    M   M  A   A  III  N   N
+//    ----------------------------------------------------------------------------------
+
+int main(int argc, char* argv[])
+{
+	// Starting the ROS-node
+	ros::init(argc, argv, "BatteryMonitor");
+
+	// 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 "ParameterService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[BATTERY MONITOR] ros::this_node::getNamespace() =  " << m_namespace);
+
+
+
+
+
+	// Advertise the service for loading Yaml Files
+	ros::ServiceServer service = nodeHandle.advertiseService("LoadYamlFiles", loadYamlFiles);
+
+	// Publish the battery level
+	batteryLevelPublisher = nodeHandle.advertise<std_msgs::Int32>("BatteryLevel",1);
+
+	// Subscribe to the voltage of the battery
+	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, newBatteryVoltageCallback);
+
+	// Subscribe to the status of the Crazyradio: connected, connecting or disconnected
+	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
+
+	// Subscribe to the flying state of the agent
+	ros::Subscriber agentOperatingStateSubscriber = nodeHandle.subscribe("PPS_Client/flyingState", 1, agentOperatingStateCallback);
+
+	// Initialise the battery level
+	m_battery_level = BATTERY_LEVEL_UNAVAILABLE;
+
+	// Initialise the operating state
+	m_agent_operating_state = AGENT_OPERATING_STATE_MOTORS_OFF;
+
+
+	ROS_INFO("[BATTERY MONITOR] Ready :-)");
+	ros::spin();
+
+	return 0;
+}
-- 
GitLab


From 4e14772df54d241e5cdfb34827502d69b5e43b29 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Thu, 6 Dec 2018 09:54:30 +0100
Subject: [PATCH 02/87] Continued developing the battery monitor

---
 .../d_fall_pps/include/nodes/BatteryMonitor.h |  26 ++-
 .../src/d_fall_pps/param/BatteryMonitor.yaml  |  16 +-
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   | 193 +++++++++++-------
 3 files changed, 144 insertions(+), 91 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index 7ee4abd0..7f4a1efc 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -66,7 +66,7 @@
 //    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// Battery states
+// Battery levels
 #define BATTERY_LEVEL_000            0
 #define BATTERY_LEVEL_010            1
 #define BATTERY_LEVEL_020            2
@@ -80,6 +80,10 @@
 #define BATTERY_LEVEL_100           10
 #define BATTERY_LEVEL_UNAVAILABLE   -1
 
+// Battery states
+#define BATTERY_STATE_NORMAL         0
+#define BATTERY_STATE_LOW            1
+
 // The types, i.e., agent or coordinator
 #define TYPE_INVALID      -1
 #define TYPE_COORDINATOR   1
@@ -109,9 +113,6 @@
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// The level of the battery
-int m_battery_level;
-
 // The status of the crazyradio as received via messages
 //int m_crazyradio_status;
 
@@ -121,20 +122,27 @@ int m_agent_operating_state;
 // Publisher for the filtered battery voltage
 ros::Publisher filteredBatteryVoltagePublisher;
 
-// Publisher for the battery state
+// Publisher for the battery level
 ros::Publisher batteryLevelPublisher;
 
+// Publisher for changes in the battery state
+ros::Publisher batteryStateChangedPublisher;
+
 
 
 // VARIABLES THAT ARE LOADED FROM THE YAML FILE
 
 // Battery thresholds while in the "motors off" state, in [Volts]
-float m_battery_threshold_lower_while_standby = 3.30f;
-float m_battery_threshold_upper_while_standby = 4.20f;
+float yaml_battery_voltage_threshold_lower_while_standby = 3.30f;
+float yaml_battery_voltage_threshold_upper_while_standby = 4.20f;
 
 // Battery thresholds while in the "flying" state, in [Volts]
-float m_battery_threshold_lower_while_flying = 2.60f;
-float m_battery_threshold_upper_while_flying = 3.70f;
+float yaml_battery_voltage_threshold_lower_while_flying = 2.60f;
+float yaml_battery_voltage_threshold_upper_while_flying = 3.70f;
+
+// Delay before changing the state of the battery, in [number of measurements]
+// > Note that the delay in seconds therefore depends on the polling period
+int yaml_battery_delay_threshold_to_change_state = 5;
 
 
 
diff --git a/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml b/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
index 86b384ec..3aeb5976 100755
--- a/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
+++ b/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
@@ -1,10 +1,14 @@
+# Frequency of requesting the battery voltage, in [milliseconds]
+battery_polling_period: 200
+
 # Battery thresholds while in the "motors off" state, in [Volts]
-battery_threshold_lower_while_standby: 3.30
-battery_threshold_upper_while_standby: 4.20
+battery_voltage_threshold_lower_while_standby: 3.30
+battery_voltage_threshold_upper_while_standby: 4.20
 
 # Battery thresholds while in the "flying" state, in [Volts]
-battery_threshold_lower_while_flying: 2.60
-battery_threshold_upper_while_flying: 3.70
+battery_voltage_threshold_lower_while_flying: 2.60
+battery_voltage_threshold_upper_while_flying: 3.70
 
-# Frequency of requesting the battery voltage, in [milliseconds]
-battery_polling_period: 200
\ No newline at end of file
+# Delay before changing the state of the battery, in [number of measurements]
+# > Note that the delay in seconds therefore depends on the polling period
+battery_delay_threshold_to_change_state: 5
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
index b3bb4d0c..53384c11 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -64,22 +64,13 @@ using namespace d_fall_pps;
 
 
 
+void agentOperatingStateCallback(const std_msgs::Int32& msg)
+{
+	// Extract the data
+	m_agent_operating_state = msg.data;
+}
 
 
-//    ----------------------------------------------------------------------------------
-//    L       OOO     A    DDDD
-//    L      O   O   A A   D   D
-//    L      O   O  A   A  D   D
-//    L      O   O  AAAAA  D   D
-//    LLLLL   OOO   A   A  DDDD
-//
-//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
-//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
-//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
-//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
-//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
-//    ----------------------------------------------------------------------------------
-
 
 
 
@@ -100,6 +91,8 @@ void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 
 
 
+
+
 void newBatteryVoltageCallback(const std_msgs::Float32& msg)
 {
 	// Extract the data
@@ -115,48 +108,75 @@ void newBatteryVoltageCallback(const std_msgs::Float32& msg)
 	// Convert the battery percentage to a level
 	int filtered_battery_voltage_as_level = convertPercentageToLevel(filtered_battery_voltage_as_percentage);
 
-	// Then publish that the battery level is unavailable
+	// Publish that the battery voltage
+	std_msgs::Float32 filtered_battery_voltage_msg;
+	filtered_battery_voltage_msg.data = filtered_battery_voltage;
+	filteredBatteryVoltagePublisher.publish(filtered_battery_voltage_msg);
+
+	// Publish that the battery level
 	std_msgs::Int32 battery_level_msg;
-	battery_level_msg.data = BATTERY_LEVEL_UNAVAILABLE;
+	battery_level_msg.data = filtered_battery_voltage_as_level;
 	batteryLevelPublisher.publish(battery_level_msg);
 
-	// ROS_INFO_STREAM("filtered data: " << filtered_battery_voltage);
-	if(
-		(flying_state != STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_flying))
-		||
-		(flying_state == STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_motors_off))
-	)
-	{
-		if(getBatteryState() != BATTERY_STATE_LOW)
-		{
-		setBatteryStateTo(BATTERY_STATE_LOW);
-		ROS_INFO("[PPS CLIENT] low level battery triggered");
-		}
+	// Update the battery state using the level
+	// > Note that the function called sends a message
+	//   only if the battery state changes
+	updateBatteryStateBasedOnLevel(filtered_battery_voltage_as_level);
+}
+
+
+
+
+
+// > For converting a voltage to a percentage, depending on the current "my_flying_state" value
+float fromVoltageToPercent(float voltage , float operating_state )
+{
+	// INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
+	float voltage_when_full;
+	float voltage_when_empty;
 
+	// COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
+	// THE CURRENT FLYING STATE
+	if (operating_state == STATE_MOTORS_OFF)
+	{
+		// Voltage limits for a "standby" type of state
+		voltage_when_empty = yaml_battery_voltage_threshold_lower_while_standby;
+		voltage_when_full  = yaml_battery_voltage_threshold_upper_while_standby;
 	}
 	else
 	{
-	// TO AVOID BEING ABLE TO IMMEDIATELY TAKE-OFF AFTER A
-	// "BATTERY LOW" EVENT IS TRIGGERED, WE DO NOT SET THE
-	// BATTERY STATE BACK TO NORMAL
-	// if(getBatteryState() != BATTERY_STATE_NORMAL)
-	// {
-	//     setBatteryStateTo(BATTERY_STATE_NORMAL);
-	// }
+		// Voltage limits for a "flying" type of state
+		voltage_when_empty = yaml_battery_voltage_threshold_lower_while_flying;
+		voltage_when_full  = yaml_battery_voltage_threshold_upper_while_flying;
 	}
-}
 
+	// COMPUTE THE PERCENTAGE
+	float percentage = 100.0f * (voltage-voltage_when_empty)/(voltage_when_full-voltage_when_empty);
 
+	// CLIP THE PERCENTAGE TO BE BETWEEN [0,100]
+	// > This should not happen to often
+	if(percentage > 100.0f)
+	{
+		percentage = 100.0f;
+	}
+	if(percentage < 0.0f)
+	{
+		percentage = 0.0f;
+	}
 
-void agentOperatingStateCallback(const std_msgs::Int32& msg)
-{
-	// Extract the data
-	m_agent_operating_state = msg.data;
+	// RETURN THE PERCENTAGE
+	return percentage;
 }
 
 
+
+
+
 int convertPercentageToLevel(float percentage)
 {
+	// Initialise the battery level
+	static int battery_level = BATTERY_LEVEL_UNAVAILABLE;
+
 	// Iterate through the levels
 	for (i_level=0;i_level<10;i++)
 	{
@@ -164,7 +184,7 @@ int convertPercentageToLevel(float percentage)
 		float threshold = float(i_level) * 10.0f;
 		// Add a buffer to the threshold to prevent
 		// high frequency changes to the level
-		if (m_battery_level==i_level)
+		if (battery_level==i_level)
 		{
 			threshold += 2.0f;
 		}
@@ -178,51 +198,66 @@ int convertPercentageToLevel(float percentage)
 	// returning, then the percentage is at or above
 	// the maximum level
 	return BATTERY_LEVEL_100;
-
 }
 
 
-// > For converting a voltage to a percentage, depending on the current "my_flying_state" value
-float fromVoltageToPercent(float voltage , float operating_state )
+
+
+
+void updateBatteryStateBasedOnLevel(level)
 {
-	// INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
-	float voltage_when_full;
-	float voltage_when_empty;
+	// Initialise the battery state
+	static int battery_state = BATTERY_STATE_NORMAL;
 
-	// COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
-	// THE CURRENT FLYING STATE
-	if (operating_state == STATE_MOTORS_OFF)
+	// Initialise a counter for delaying a change of state
+	static int num_since_change = 0;
+
+	if (level == 0)
 	{
-		// Voltage limits for a "standby" type of state
-		voltage_when_empty = m_battery_threshold_lower_while_standby;
-		voltage_when_full  = m_battery_threshold_upper_while_standby;
+		if (battery_state == BATTERY_STATE_NORMAL)
+		{
+			num_since_change++;
+		}
+		else
+		{
+			num_since_change = 0;
+		}
 	}
-	else
+	else if (level >= 1)
 	{
-		// Voltage limits for a "flying" type of state
-		voltage_when_empty = m_battery_threshold_lower_while_flying;
-		voltage_when_full  = m_battery_threshold_upper_while_flying;
+		if (battery_state == BATTERY_STATE_LOW)
+		{
+			num_since_change++;
+		}
+		else
+		{
+			num_since_change = 0;
+		}
 	}
 
-	// COMPUTE THE PERCENTAGE
-	float percentage = 100.0f * (voltage-voltage_when_empty)/(voltage_when_full-voltage_when_empty);
-
-	// CLIP THE PERCENTAGE TO BE BETWEEN [0,100]
-	// > This should not happen to often
-	if(percentage > 100.0f)
-	{
-		percentage = 100.0f;
-	}
-	if(percentage < 0.0f)
+	// Check if the "delay-to-change" threshold is reached
+	if (num_since_change >= yaml_battery_delay_threshold_to_change_state)
 	{
-		percentage = 0.0f;
+		if (battery_state == BATTERY_STATE_NORMAL)
+		{
+			battery_state = BATTERY_STATE_LOW;
+		}
+		else
+		{
+			battery_state = BATTERY_STATE_NORMAL;
+		}
+		// Publish the change
+		std_msgs::Int32 battery_state_msg;
+		battery_state_msg.data = battery_state;
+		batteryStateChangedPublisher.publish(battery_state_msg);
 	}
-
-	// RETURN THE PERCENTAGE
-	return percentage;
 }
 
 
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    M   M    A    III  N   N
 //    MM MM   A A    I   NN  N
@@ -251,9 +286,18 @@ int main(int argc, char* argv[])
 	// Advertise the service for loading Yaml Files
 	ros::ServiceServer service = nodeHandle.advertiseService("LoadYamlFiles", loadYamlFiles);
 
-	// Publish the battery level
-	batteryLevelPublisher = nodeHandle.advertise<std_msgs::Int32>("BatteryLevel",1);
+	// PUBLISHERS
+	// Publisher for the filtered battery voltage
+	ros::Publisher filteredBatteryVoltagePublisher = nodeHandle.advertise<std_msgs::Float32>("FilteredVoltage",1);
+
+	// Publisher for the battery level
+	batteryLevelPublisher = nodeHandle.advertise<std_msgs::Int32>("Level",1);
+
+	// Publisher for changes in the battery state
+	ros::Publisher batteryStateChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("ChangedStateTo",1);
 
+
+	// SUBSCRIBERS
 	// Subscribe to the voltage of the battery
 	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, newBatteryVoltageCallback);
 
@@ -263,9 +307,6 @@ int main(int argc, char* argv[])
 	// Subscribe to the flying state of the agent
 	ros::Subscriber agentOperatingStateSubscriber = nodeHandle.subscribe("PPS_Client/flyingState", 1, agentOperatingStateCallback);
 
-	// Initialise the battery level
-	m_battery_level = BATTERY_LEVEL_UNAVAILABLE;
-
 	// Initialise the operating state
 	m_agent_operating_state = AGENT_OPERATING_STATE_MOTORS_OFF;
 
-- 
GitLab


From 3dfa2b1d5e17c8babe36c3d0cedc4ce733a46e2b Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 6 Dec 2018 17:15:08 +0100
Subject: [PATCH 03/87] Battery monitor connected to new style of parameter
 service interface. Compiles by is not able to call the service client.

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   3 +
 .../d_fall_pps/include/nodes/BatteryMonitor.h |  43 ++-
 pps_ws/src/d_fall_pps/launch/Agent.launch     |   9 +
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   | 316 +++++++++++++++++-
 .../d_fall_pps/src/nodes/ParameterService.cpp |  35 +-
 .../src/nodes/StudentControllerService.cpp    |   2 +-
 pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv   |   2 +-
 7 files changed, 371 insertions(+), 39 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 222de5fa..452128a2 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -318,6 +318,7 @@ if(VICON_LIBRARY)
 endif()
 
 add_executable(PPSClient                src/nodes/PPSClient.cpp)
+add_executable(BatteryMonitor           src/nodes/BatteryMonitor.cpp)
 add_executable(SafeControllerService    src/nodes/SafeControllerService.cpp)
 add_executable(DemoControllerService    src/nodes/DemoControllerService.cpp)
 add_executable(StudentControllerService src/nodes/StudentControllerService.cpp)
@@ -401,6 +402,7 @@ if(VICON_LIBRARY)
 endif()
 
 add_dependencies(PPSClient                d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(BatteryMonitor           d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(SafeControllerService    d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(DemoControllerService    d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(StudentControllerService d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
@@ -451,6 +453,7 @@ if(VICON_LIBRARY)
 endif()
 
 target_link_libraries(PPSClient                ${catkin_LIBRARIES})
+target_link_libraries(BatteryMonitor           ${catkin_LIBRARIES})
 target_link_libraries(SafeControllerService    ${catkin_LIBRARIES})
 target_link_libraries(DemoControllerService    ${catkin_LIBRARIES})
 target_link_libraries(StudentControllerService ${catkin_LIBRARIES})
diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index 7f4a1efc..705382ff 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -48,7 +48,7 @@
 #include <ros/package.h>
 #include <ros/network.h>
 #include "std_msgs/Int32.h"
-//#include "std_msgs/Float32.h"
+#include "std_msgs/Float32.h"
 //#include <std_msgs/String.h>
 
 #include "d_fall_pps/Controller.h"
@@ -113,6 +113,25 @@
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
+// SERVICE CLIENTS FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+ros::ServiceClient m_own_agent_parameter_service_client;
+// > For the parameter service of the coordinator
+ros::ServiceClient m_coordinator_parameter_service_client;
+
+
+
+
 // The status of the crazyradio as received via messages
 //int m_crazyradio_status;
 
@@ -132,6 +151,9 @@ ros::Publisher batteryStateChangedPublisher;
 
 // VARIABLES THAT ARE LOADED FROM THE YAML FILE
 
+// Frequency of requesting the battery voltage, in [milliseconds]
+//float battery_polling_period = 200.0f;
+
 // Battery thresholds while in the "motors off" state, in [Volts]
 float yaml_battery_voltage_threshold_lower_while_standby = 3.30f;
 float yaml_battery_voltage_threshold_upper_while_standby = 4.20f;
@@ -162,8 +184,19 @@ int yaml_battery_delay_threshold_to_change_state = 5;
 
 void newBatteryVoltageCallback(const std_msgs::Float32& msg);
 
+float newBatteryVoltageForFilter(float new_value);
+// > For converting a voltage to a percentage,
+//   depending on the current "my_flying_state" value
 float fromVoltageToPercent(float voltage , float operating_state);
-
-int level convertVoltageToLevel(float voltage , float operating_state);
-
-
+// > For converting the percentage to a level
+int convertPercentageToLevel(float percentage);
+// > For updating the battery state based on the battery level
+//   Possible states are {normal,low}, and changes are delayed
+void updateBatteryStateBasedOnLevel(int level);
+
+
+// LOAD YAML PARAMETER FUNCTIONS
+void fetchYamlParameters(ros::NodeHandle& nodeHandle);
+void processFetchedParameters();
+float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
+int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index a24b9ad1..7d83cb92 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -35,6 +35,15 @@
 			<param name="agentID" value="$(arg agentID)" />
 		</node>
 
+		<!-- BATTERY MONITOR -->
+		<node
+			pkg    = "d_fall_pps"
+			name   = "BatteryMonitor"
+			output = "screen"
+			type   = "BatteryMonitor"
+			>
+		</node>
+
 		<!-- SAFE CONTROLLER -->
 		<node
 			pkg    = "d_fall_pps"
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
index 53384c11..a2f02eb0 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -33,16 +33,16 @@
 
 
 
-// SPECIFY THE PACKAGE NAMESPACE
-using namespace d_fall_pps;
-//using namespace std;
+// INCLUDE THE HEADER
+#include "nodes/BatteryMonitor.h"
 
 
 
 
 
-// INCLUDE THE HEADER
-#include "nodes/BatteryMonitor.h"
+// SPECIFY THE PACKAGE NAMESPACE
+using namespace d_fall_pps;
+//using namespace std;
 
 
 
@@ -80,7 +80,7 @@ void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 	int crazyradio_status = msg.data;
 
 	// I the Crazyradio DISCONNECTED
-	if (crazyradio_status == DISCONNECTED)
+	if (crazyradio_status == CRAZY_RADIO_STATE_DISCONNECTED)
 	{
 		// Then publish that the battery level is unavailable
 		std_msgs::Int32 battery_level_msg;
@@ -96,14 +96,14 @@ void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 void newBatteryVoltageCallback(const std_msgs::Float32& msg)
 {
 	// Extract the data
-	m_battery_voltage = msg.data;
+	float battery_voltage = msg.data;
 
 	// Provide the new measurement to the filter
-	float filtered_battery_voltage = newBatteryVoltageForFilter(m_battery_voltage); //need to perform filtering here
+	float filtered_battery_voltage = newBatteryVoltageForFilter(battery_voltage);
 
 	// Convert the filtered voltage to a percentage
 	// > Note that this depending on the operating state
-	float filtered_battery_voltage_as_percentage = convertVoltageToLevel(filtered_battery_voltage,m_agent_operating_state);
+	float filtered_battery_voltage_as_percentage = fromVoltageToPercent(filtered_battery_voltage,m_agent_operating_state);
 
 	// Convert the battery percentage to a level
 	int filtered_battery_voltage_as_level = convertPercentageToLevel(filtered_battery_voltage_as_percentage);
@@ -127,6 +127,15 @@ void newBatteryVoltageCallback(const std_msgs::Float32& msg)
 
 
 
+// > For filtering the battery voltage
+float newBatteryVoltageForFilter(float new_value)
+{
+	return 0.0f;
+}
+
+
+
+
 
 // > For converting a voltage to a percentage, depending on the current "my_flying_state" value
 float fromVoltageToPercent(float voltage , float operating_state )
@@ -137,7 +146,7 @@ float fromVoltageToPercent(float voltage , float operating_state )
 
 	// COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
 	// THE CURRENT FLYING STATE
-	if (operating_state == STATE_MOTORS_OFF)
+	if (operating_state == AGENT_OPERATING_STATE_MOTORS_OFF)
 	{
 		// Voltage limits for a "standby" type of state
 		voltage_when_empty = yaml_battery_voltage_threshold_lower_while_standby;
@@ -171,14 +180,14 @@ float fromVoltageToPercent(float voltage , float operating_state )
 
 
 
-
+// > For converting the percentage to a level
 int convertPercentageToLevel(float percentage)
 {
 	// Initialise the battery level
 	static int battery_level = BATTERY_LEVEL_UNAVAILABLE;
 
 	// Iterate through the levels
-	for (i_level=0;i_level<10;i++)
+	for (int i_level=0 ; i_level<10 ; i_level++)
 	{
 		// Compute the threshold for this level
 		float threshold = float(i_level) * 10.0f;
@@ -203,8 +212,9 @@ int convertPercentageToLevel(float percentage)
 
 
 
-
-void updateBatteryStateBasedOnLevel(level)
+// > For updating the battery state based on the battery level
+//   Possible states are {normal,low}, and changes are delayed
+void updateBatteryStateBasedOnLevel(int level)
 {
 	// Initialise the battery state
 	static int battery_state = BATTERY_STATE_NORMAL;
@@ -258,6 +268,163 @@ void updateBatteryStateBasedOnLevel(level)
 
 
 
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
+//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
+//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
+//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
+//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+{
+	// Extract from the "msg" for which controller the and from where to fetch the YAML
+	// parameters
+	int controller_to_fetch_yaml = msg.data;
+
+	// Switch between fetching for the different controllers and from different locations
+	switch(controller_to_fetch_yaml)
+	{
+
+		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+		case FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT:
+		{
+			// Let the user know that this message was received
+			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
+			// Create a node handle to the parameter service running on this agent's machine
+			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+			// Call the function that fetches the parameters
+			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+			break;
+		}
+
+		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+		case FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR:
+		{
+			// Let the user know that this message was received
+			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
+			// Create a node handle to the parameter service running on the coordinator machine
+			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+			// Call the function that fetches the parameters
+			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+			break;
+		}
+
+		default:
+		{
+			// Let the user know that the command was not relevant
+			//ROS_INFO("The StudentControllerService received the message that YAML parameters were (re-)loaded");
+			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
+			break;
+		}
+	}
+}
+
+
+
+
+
+
+// This function CAN BE edited for successful completion of the PPS 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)
+{
+	// Here we load the parameters that are specified in the StudentController.yaml file
+
+	// Add the "StudentController" namespace to the "nodeHandle"
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "BatteryMonitor");
+
+
+
+	// Frequency of requesting the battery voltage, in [milliseconds]
+	//yaml_battery_polling_period = getParameterFloat(nodeHandle_for_paramaters,"battery_polling_period");
+
+	// Battery thresholds while in the "motors off" state, in [Volts]
+	yaml_battery_voltage_threshold_lower_while_standby = getParameterFloat(nodeHandle_for_paramaters,"battery_voltage_threshold_lower_while_standby");
+	yaml_battery_voltage_threshold_upper_while_standby = getParameterFloat(nodeHandle_for_paramaters,"battery_voltage_threshold_upper_while_standby");
+
+	// Battery thresholds while in the "flying" state, in [Volts]
+	yaml_battery_voltage_threshold_lower_while_flying = getParameterFloat(nodeHandle_for_paramaters,"battery_voltage_threshold_lower_while_flying");
+	yaml_battery_voltage_threshold_upper_while_flying = getParameterFloat(nodeHandle_for_paramaters,"battery_voltage_threshold_upper_while_flying");
+
+	// Delay before changing the state of the battery, in [number of measurements]
+	// > Note that the delay in seconds therefore depends on the polling period
+	yaml_battery_delay_threshold_to_change_state = getParameterInt(nodeHandle_for_paramaters,"battery_delay_threshold_to_change_state");
+
+
+
+	// DEBUGGING: Print out one of the parameters that was loaded
+	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUGGING: the fetched BatteryMonitor/battery_polling_period = " << yaml_battery_voltage_threshold_lower_while_flying);
+
+	// Call the function that computes details an values that are needed from these
+	// parameters loaded above
+	processFetchedParameters();
+}
+
+
+
+
+
+// This function CAN BE edited for successful completion of the PPS 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()
+{
+    // Compute the feed-forward force that we need to counteract gravity (i.e., mg)
+    // > in units of [Newtons]
+    //cf_weight_in_newtons = cf_mass_in_grams * 9.81/1000.0;
+    
+    // DEBUGGING: Print out one of the computed quantities
+	//ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << cf_weight_in_newtons);
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
+//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
+//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
+//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
+//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
+//    ----------------------------------------------------------------------------------
+
+
+// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
+{
+    float val;
+    if(!nodeHandle.getParam(name, val))
+    {
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val;
+}
+// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
+{
+    int val;
+    if(!nodeHandle.getParam(name, val))
+    {
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val;
+}
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    M   M    A    III  N   N
 //    MM MM   A A    I   NN  N
@@ -279,12 +446,127 @@ int main(int argc, char* argv[])
 	std::string m_namespace = ros::this_node::getNamespace();
 	ROS_INFO_STREAM("[BATTERY MONITOR] ros::this_node::getNamespace() =  " << m_namespace);
 
+	// Get the agent ID as the "ROS_NAMESPACE" this computer.
+    // 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 "PPSClient"
+    // > Thus, to get access to the "agentID" paremeter, we first need to get
+    //   a handle to the "PPSClient" node with which this battery monitor
+    //   was created.
+    // Get the handle to the "PPSClient" node
+    ros::NodeHandle PPSClient_nodeHandle(m_namespace + "/PPSClient");
+    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
+    if(!PPSClient_nodeHandle.getParam("agentID", m_agentID))
+    {
+    	// Throw an error if the student ID parameter could not be obtained
+		ROS_ERROR("[BATTERY MONITOR] Failed to get agentID from PPSClient");
+	}
+	else
+	{
+		// Let the user know what agentID was loaded
+		ROS_INFO_STREAM("[BATTERY MONITOR] loaded agentID = " << m_agentID);
+	}
+
+
+
+
+
+	// *********************************************************************************
+	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
+
+
+	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+
+	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
+	// namespace string for the parameter service that is running on the machine of this
+	// agent
+	m_namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
+
+	// Create a node handle to the parameter service running on this agent's machine
+	ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+
+	// Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
+	// "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
+	// and calls the class function "yamlReadyForFetchCallback" each time a message is
+	// received on this topic and the message is passed as an input argument to the
+	// "yamlReadyForFetchCallback" class function.
+	ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+
+
+	// EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
+
+	// Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
+	// for the parameter service that is running on the coordinate machine
+	// NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
+	//       is very important because it specifies that the name is global
+	m_namespace_to_coordinator_parameter_service = "/ParameterService";
+
+	// Create a node handle to the parameter service running on the coordinator machine
+	ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
+	//ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+
+
+	// Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
+	// "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
+	// and calls the class function "yamlReadyForFetchCallback" each time a message is
+	// received on this topic and the message is passed as an input argument to the
+	// "yamlReadyForFetchCallback" class function.
+	ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+	//ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+
+
+	// Set the class variable "m_own_agent_parameter_service_client"
+	// for making requests to the "LoadYamlFiles" service that is advertised
+	// by the "ParameterService" nodes
+	std::string own_agent_parameter_service_client_string = m_namespace_to_own_agent_parameter_service + "/LoadYamlFiles";
+	m_own_agent_parameter_service_client = ros::service::createClient<LoadYamlFiles>(own_agent_parameter_service_client_string, true);
+	ROS_INFO_STREAM("[BATTERY MONITOR] Loaded parameter service client: " << m_own_agent_parameter_service_client.getService());
+	
+	// PRINT OUT SOME INFORMATION
+
+	// Let the user know what namespaces are being used for linking to the parameter service
+	ROS_INFO_STREAM("[BATTERY MONITOR] The namespace string for accessing the Paramter Services are:");
+	ROS_INFO_STREAM("[BATTERY MONITOR] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[BATTERY MONITOR] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
+
+
+	// FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
+
+	// Call the class function that loads the parameters for this class.
+	//fetchYamlParameters(m_nodeHandle_to_own_agent_parameter_service);
+
+	// Load the yaml paramters
+	ros::Duration(2.0).sleep();
+	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 1");
+	// Prepare the service call
+	LoadYamlFiles load_yaml_files_service_call;
+	std::string yaml_file_name_to_request = "BatteryMonitor";
+	load_yaml_files_service_call.request.yamlFileName = yaml_file_name_to_request;
+	// Call on the service
+	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 2");
+	bool success = m_own_agent_parameter_service_client.call(load_yaml_files_service_call);
+	if (success)
+	{
+		// Extract the data from the response
+		float wait_time_for_yaml = load_yaml_files_service_call.response.waitTime;
+		// Wait for the specified time
+		ros::Duration(wait_time_for_yaml).sleep();
+		// Call the function that loads the yaml paramters
+		fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+		ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 3");
+	}
+	else
+	{
+		ROS_INFO("[BATTERY MONITOR] The load yaml file service call was NOT successful.");
+	}
+
+	// *********************************************************************************
 
 
 
 
-	// Advertise the service for loading Yaml Files
-	ros::ServiceServer service = nodeHandle.advertiseService("LoadYamlFiles", loadYamlFiles);
 
 	// PUBLISHERS
 	// Publisher for the filtered battery voltage
@@ -311,6 +593,8 @@ int main(int argc, char* argv[])
 	m_agent_operating_state = AGENT_OPERATING_STATE_MOTORS_OFF;
 
 
+
+
 	ROS_INFO("[BATTERY MONITOR] Ready :-)");
 	ros::spin();
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 976274ba..536629ad 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -241,22 +241,21 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
 
 bool loadYamlFiles(LoadYamlFiles::Request &request, LoadYamlFiles::Response &response)
 {
-
-    std::string yamlFileName_toLoad = request.yamlFileNames[0];
-
+    ROS_INFO_STREAM("[PARAMETER SERVICE] DEBUG 1");
+    // Get the yaml file name requested
+    std::string yamlFileName_toLoad = request.yamlFileName;
+    // Get the node handle to this parameter service
     ros::NodeHandle nodeHandle("~");
 
-    std::string yamlFileNamesParamters_basenamespace = "YamlFileNames/dictionary";
-
-    std::string paramterName = yamlFileNamesParamters_basenamespace + "/" + yamlFileName_toLoad;
-
-    std::string yamlFileName_from_dictionary;
-
-    if(!nodeHandle.getParam(paramterName, yamlFileName_from_dictionary))
-    {
-        ROS_ERROR_STREAM("[PARAMETER SERVICE] Missing parameter: '" << paramterName << "'");
-        return false;
-    }
+    // OLD: Get the yaml namespace from a yaml dictionary
+    //std::string yamlFileNamesParamters_basenamespace = "YamlFileNames/dictionary";
+    //std::string paramterName = yamlFileNamesParamters_basenamespace + "/" + yamlFileName_toLoad;
+    //std::string yamlFileName_from_dictionary;
+    //if(!nodeHandle.getParam(paramterName, yamlFileName_from_dictionary))
+    //{
+    //    ROS_ERROR_STREAM("[PARAMETER SERVICE] Missing parameter: '" << paramterName << "'");
+    //    return false;
+    //}
 
     // Instantiate a local variable for the command string that will be passed to the "system":
     std::string cmd;
@@ -265,7 +264,7 @@ bool loadYamlFiles(LoadYamlFiles::Request &request, LoadYamlFiles::Response &res
     std::string d_fall_pps_path = ros::package::getPath("d_fall_pps");
 
     // Construct the system command string for (re-)loading the parameters:
-    cmd = "rosparam load " + d_fall_pps_path + "/param" + "/" + yamlFileName_from_dictionary + ".yaml " + m_base_namespace + "/" + yamlFileName_from_dictionary;
+    cmd = "rosparam load " + d_fall_pps_path + "/param" + "/" + yamlFileName_toLoad + ".yaml " + m_base_namespace + "/" + yamlFileName_toLoad;
 
     // Let the user know what is about to happen
     ROS_INFO_STREAM("[PARAMETER SERVICE] The following path will be used for locating the .yaml file: " << d_fall_pps_path  << " The comand line string sent to the 'system' is: " << cmd );
@@ -273,7 +272,11 @@ bool loadYamlFiles(LoadYamlFiles::Request &request, LoadYamlFiles::Response &res
     system(cmd.c_str());
 
     // Pause breifly to ensure that the yaml file is fully loaded
-    ros::Duration(0.5).sleep();
+    //ros::Duration(0.5).sleep();
+
+    // Set the response wait time
+    response.waitTime = 2.0f;
+    ROS_INFO_STREAM("[PARAMETER SERVICE] DEBUG 2");
 
     return true;
 }
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 4ec1acc3..7f2098be 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -804,7 +804,7 @@ int main(int argc, char* argv[]) {
 
     // Get the agent ID as the "ROS_NAMESPACE" this computer.
     // NOTES:
-    // > If you look at the "Student.launch" file in the "launch" folder, you will see
+    // > If you look at the "Agent.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"
diff --git a/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv b/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv
index f51e1852..fc7c7120 100644
--- a/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv
+++ b/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv
@@ -1,3 +1,3 @@
-string[] yamlFileNames
+string yamlFileName
 ---
 float64 waitTime
-- 
GitLab


From d03f76cc1334f92268a1e4bc41c9016903b942e3 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 8 Dec 2018 15:49:09 +0100
Subject: [PATCH 04/87] Finished setting up the Battery monitoring node and new
 parameter service style to match. Needs a GUI reload Yaml to be added and
 needs to be tested.

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   7 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |   2 +-
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      |   4 +-
 .../d_fall_pps/include/nodes/BatteryMonitor.h |  49 ++-
 ...ameterServiceDefinitions.h => Constants.h} |  61 +++-
 .../include/nodes/DemoControllerService.h     |   2 +-
 .../src/d_fall_pps/include/nodes/PPSClient.h  |   2 +-
 .../include/nodes/ParameterService.h          |  29 +-
 .../include/nodes/PickerControllerService.h   |   2 +-
 .../include/nodes/RemoteControllerService.h   |   2 +-
 .../include/nodes/SafeControllerService.h     |   2 +-
 .../include/nodes/StudentControllerService.h  |   2 +-
 .../include/nodes/TuningControllerService.h   |   2 +-
 pps_ws/src/d_fall_pps/launch/Agent.launch     |   8 +-
 pps_ws/src/d_fall_pps/launch/Config.sh        |   7 +-
 .../src/d_fall_pps/launch/Coordinator.launch  |  69 +++-
 pps_ws/src/d_fall_pps/launch/Teacher.launch   |   8 -
 pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg |   3 +
 pps_ws/src/d_fall_pps/msg/IntWithHeader.msg   |   3 +
 .../src/d_fall_pps/msg/StringWithHeader.msg   |   3 +
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   | 297 +++++++++---------
 .../src/nodes/MpcControllerService.cpp        |   2 +-
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp |   4 +-
 .../d_fall_pps/src/nodes/ParameterService.cpp | 294 +++++++++--------
 pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv   |   3 -
 25 files changed, 540 insertions(+), 327 deletions(-)
 rename pps_ws/src/d_fall_pps/include/nodes/{ParameterServiceDefinitions.h => Constants.h} (68%)
 create mode 100755 pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
 create mode 100755 pps_ws/src/d_fall_pps/msg/IntWithHeader.msg
 create mode 100755 pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
 delete mode 100644 pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 452128a2..84a1ade4 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -205,7 +205,11 @@ add_message_files(
   SetpointV2.msg
   CrazyflieEntry.msg
   CrazyflieDB.msg
-  #----------------------------------------------------------------------
+  #------------------------
+  IntWithHeader.msg
+  FloatWithHeader.msg
+  StringWithHeader.msg
+  #------------------------
   DebugMsg.msg
   CustomButton.msg
   ViconSubscribeObjectName.msg
@@ -219,7 +223,6 @@ add_message_files(
 # )
 add_service_files(
   FILES
-  LoadYamlFiles.srv
   Controller.srv
   CMRead.srv
   CMQuery.srv
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 0a4414f3..1f073f9b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -130,7 +130,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/flyingState", 1, &CoordinatorRow::flyingStateChangedCallback, this);
     // > For changes in the database that defines {agentID,cfID,flying zone} links
     databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("/my_GUI/DBChanged", 1, &CoordinatorRow::databaseChangedCallback, this);;
-    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<CMQuery>("/CentralManagerService/Query", false);
+    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
     // > For updating the controller that is currently operating
     controllerUsedSubscriber = base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
index a1822cb3..ce661742 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
@@ -192,7 +192,9 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
 	}
 
     // Then, Central manager
-    centralManager = nodeHandle.serviceClient<CMQuery>("/CentralManagerService/Query", false);
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle dfall_root_nodeHandle("/dfall");
+    centralManager = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
     loadCrazyflieContext();
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index 705382ff..d7eff9d1 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -42,20 +42,28 @@
 //    ----------------------------------------------------------------------------------
 
 #include <stdlib.h>
+#include <iostream>
 #include <string>
 
 #include <ros/ros.h>
 #include <ros/package.h>
 #include <ros/network.h>
+
+// Include the standard message types
 #include "std_msgs/Int32.h"
 #include "std_msgs/Float32.h"
 //#include <std_msgs/String.h>
 
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/LoadYamlFiles.h"
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
 
 // Include the shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+using namespace d_fall_pps;
+//using namespace std;
+
 
 
 //    ----------------------------------------------------------------------------------
@@ -117,18 +125,15 @@
 // The ID of the agent that this node is monitoring
 int m_agentID;
 
+// The ID of the agent that can coordinate this node
+int m_coordID;
+
 // NAMESPACES FOR THE PARAMETER SERVICES
 // > For the paramter service of this agent
 std::string m_namespace_to_own_agent_parameter_service;
 // > For the parameter service of the coordinator
 std::string m_namespace_to_coordinator_parameter_service;
 
-// SERVICE CLIENTS FOR THE PARAMETER SERVICES
-// > For the paramter service of this agent
-ros::ServiceClient m_own_agent_parameter_service_client;
-// > For the parameter service of the coordinator
-ros::ServiceClient m_coordinator_parameter_service_client;
-
 
 
 
@@ -198,5 +203,29 @@ void updateBatteryStateBasedOnLevel(int level);
 // LOAD YAML PARAMETER FUNCTIONS
 void fetchYamlParameters(ros::NodeHandle& nodeHandle);
 void processFetchedParameters();
+
+void yamlReadyForFetchCallback(const IntWithHeader & msg);
+
+
+
 float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
\ No newline at end of file
+int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
+
+
+
+
+
+
+
+
+
+// FUNCTIONS FOR TEMPLATING A GET STUFF CLASS
+
+// Get the "agentID" and "coordID" from the client node
+bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref);
+
+// Construct the namespaces for the parameter services
+void getConstructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace );
+
+// Check the header of a message for whether it is relevant
+bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs );
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/ParameterServiceDefinitions.h b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
similarity index 68%
rename from pps_ws/src/d_fall_pps/include/nodes/ParameterServiceDefinitions.h
rename to pps_ws/src/d_fall_pps/include/nodes/Constants.h
index 9801abf3..91e1f664 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/ParameterServiceDefinitions.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
@@ -25,15 +25,72 @@
 //
 //
 //    DESCRIPTION:
-//    The service that manages the loading of YAML parameters
+//    Constants that are used across multiple files
 //
 //    ----------------------------------------------------------------------------------
 
 
 
 
-// DEFINES THAT ARE SHARED WITH OTHER FILES
 
+//    ----------------------------------------------------------------------------------
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
+//    ----------------------------------------------------------------------------------
+
+// Battery levels
+#define BATTERY_LEVEL_000            0
+#define BATTERY_LEVEL_010            1
+#define BATTERY_LEVEL_020            2
+#define BATTERY_LEVEL_030            3
+#define BATTERY_LEVEL_040            4
+#define BATTERY_LEVEL_050            5
+#define BATTERY_LEVEL_060            6
+#define BATTERY_LEVEL_070            7
+#define BATTERY_LEVEL_080            8
+#define BATTERY_LEVEL_090            9
+#define BATTERY_LEVEL_100           10
+#define BATTERY_LEVEL_UNAVAILABLE   -1
+
+// Battery states
+#define BATTERY_STATE_NORMAL         0
+#define BATTERY_STATE_LOW            1
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    Y   Y    A    M   M  L
+//     Y Y    A A   MM MM  L
+//      Y    A   A  M M M  L
+//      Y    AAAAA  M   M  L
+//      Y    A   A  M   M  LLLLL
+//    ----------------------------------------------------------------------------------
+
+// For where to load the yaml file from
+#define LOAD_YAML_FROM_AGENT             1
+#define LOAD_YAML_FROM_COORDINATOR       2
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// OLD STUFF FOR LOADING YAML FILES
 // For which controller parameters to load from file
 #define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
 #define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
index 7c0f469f..9441c08c 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
@@ -59,7 +59,7 @@
 #include "d_fall_pps/CustomButton.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
index aac50d36..f9baaca8 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -58,7 +58,7 @@
 #include "std_msgs/Float32.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 // Need for having a ROS "bag" to store data for post-analysis
 //#include <rosbag/bag.h>
diff --git a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
index 36153c11..66507144 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
@@ -47,15 +47,19 @@
 #include <ros/ros.h>
 #include <ros/package.h>
 #include <ros/network.h>
+
+// Include the standard message types
 #include "std_msgs/Int32.h"
 //#include "std_msgs/Float32.h"
-//#include <std_msgs/String.h>
+#include <std_msgs/String.h>
 
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/LoadYamlFiles.h"
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+//#include "d_fall_pps/FloatWithHeader.h"
+#include "d_fall_pps/StringWithHeader.h"
 
 // Include the shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 
 //    ----------------------------------------------------------------------------------
@@ -89,20 +93,17 @@ using namespace d_fall_pps;
 
 // The type of this node, i.e., agent or a coordinator, specified as a parameter in the
 // "*.launch" file
-int my_type = 0;
+int m_type = 0;
 
 // The ID of this agent, i.e., the ID of this computer in the case that this computer is
 // and agent
-std::string my_agentID = "000";
+int m_ID = 0;
 
-// Publisher that notifies the relevant nodes when the YAML paramters have been loaded
-// from file into ram/cache, and hence are ready to be fetched
-ros::Publisher controllerYamlReadyForFetchPublisher;
+// The namespace into which this parameter service loads yaml parameters
+std::string m_base_namespace;
 
 
-std::string m_base_namespace;
 
-ros::Subscriber requestLoadControllerYamlSubscriber_agent_to_self;
 
 
 //    ----------------------------------------------------------------------------------
@@ -121,4 +122,8 @@ ros::Subscriber requestLoadControllerYamlSubscriber_agent_to_self;
 
 void requestLoadControllerYamlCallback(const std_msgs::Int32& msg);
 
-bool loadYamlFiles(LoadYamlFiles::Request &request, LoadYamlFiles::Response &response);
+void requestLoadYamlFilenameCallback(const StringWithHeader& yamlFilenameToLoad);
+
+bool getTypeAndIDParameters();
+
+bool constructNamespaces();
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index 60ad9e02..8b51e35e 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -60,7 +60,7 @@
 #include "d_fall_pps/CustomButton.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 #include <std_msgs/Float32.h>
diff --git a/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
index a8adb305..33d91be9 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
@@ -65,7 +65,7 @@
 #include "d_fall_pps/ViconSubscribeObjectName.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
index 19a1a90d..684b8134 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
@@ -59,7 +59,7 @@
 #include <std_msgs/Int32.h>
 
 // Include the shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 818993f0..478c94ff 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -59,7 +59,7 @@
 #include "d_fall_pps/CustomButton.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
index 9866bdbe..1b950747 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
@@ -65,7 +65,7 @@
 #include "d_fall_pps/ViconSubscribeObjectName.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index 7d83cb92..f4d2d83d 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -3,6 +3,9 @@
 	<!-- INPUT ARGUMENT OF THE AGENT's ID -->
 	<arg name="agentID" default="$(optenv DFALL_DEFAULT_AGENT_ID)" />
 
+	<!-- INPUT ARGUMENT OF THE COORDINATOR's ID -->
+	<arg name="coordID" default="$(optenv DFALL_DEFAULT_COORD_ID)" />
+
 	<!-- INPUT ARGUMENT FOR LAUNCHING A GUI OR NOT -->
 	<arg name="withGUI" default="true" />
 
@@ -33,6 +36,7 @@
 			>
 			<rosparam command="load" file="$(find d_fall_pps)/param/ClientConfig.yaml" />
 			<param name="agentID" value="$(arg agentID)" />
+			<param name="coordID" value="$(arg coordID)" />
 		</node>
 
 		<!-- BATTERY MONITOR -->
@@ -118,8 +122,8 @@
 			<param name="agentID"  type="str"  value="$(arg agentID)" />
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/YamlFileNames.yaml"
-				ns      = "YamlFileNames"
+				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
+				ns      = "BatteryMonitor"
 			/>
 			<rosparam
 				command = "load"
diff --git a/pps_ws/src/d_fall_pps/launch/Config.sh b/pps_ws/src/d_fall_pps/launch/Config.sh
index 48d929ff..3a8fb387 100755
--- a/pps_ws/src/d_fall_pps/launch/Config.sh
+++ b/pps_ws/src/d_fall_pps/launch/Config.sh
@@ -1,6 +1,9 @@
+# TO RUN THE SYSTEM FULLY ON THE LOCAL COMPUTER:
+# export ROS_MASTER_URI=http://localhost:11311
+# TO RUN THE SYSTEM ON A DEFAULT CONFIGURATION OF THE NETWROK:
 export ROS_MASTER_URI=http://teacher:11311
+# OTHER NECESSARY ENVIRONMENT VARIABLES:
 export ROS_IP=$(hostname -I | awk '{print $1;}')
 export DFALL_DEFAULT_AGENT_ID=$(cat /etc/dfall_default_agent_id)
 export DFALL_DEFAULT_COORD_ID=$(cat /etc/dfall_default_coord_id)
-export ROS_NAMESPACE='dfall'
-
+export ROS_NAMESPACE='dfall'
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/launch/Coordinator.launch b/pps_ws/src/d_fall_pps/launch/Coordinator.launch
index c77f5104..59b08530 100755
--- a/pps_ws/src/d_fall_pps/launch/Coordinator.launch
+++ b/pps_ws/src/d_fall_pps/launch/Coordinator.launch
@@ -1,8 +1,11 @@
 <launch>
 
-	<!-- INPUT ARGUMENT OF THE AGENT's ID -->
+	<!-- INPUT ARGUMENT OF THE COORDINATOR's ID -->
 	<arg name="coordID" default="$(optenv DFALL_DEFAULT_COORD_ID)" />
 
+	<!-- INPUT ARGUMENT FOR LAUNCHING A GUI OR NOT -->
+	<arg name="withGUI" default="true" />
+
 	<!-- Example of how to use the value in coordID -->
 	<!-- <param name="param" value="$(arg coordID)"/> -->
 
@@ -12,14 +15,68 @@
 	<group ns="coord$(arg coordID)">
 
 		<!-- COORDINATOR GUI -->
+		<group if="$(arg withGUI)">
+			<node
+				pkg="d_fall_pps"
+				name="flyingAgentGUI"
+				output="screen"
+				type="flyingAgentGUI"
+				>
+				<param name="type"     type="str"  value="coordinator" />
+				<param name="coordID"  value="$(arg coordID)" />
+			</node>
+		</group>
+
+
+		<!-- PARAMETER SERVICE -->
 		<node
-			pkg="d_fall_pps"
-			name="flyingAgentGUI"
-			output="screen"
-			type="flyingAgentGUI"
+			pkg    = "d_fall_pps"
+			name   = "ParameterService"
+			output = "screen"
+			type   = "ParameterService"
 			>
 			<param name="type"     type="str"  value="coordinator" />
-			<param name="coordID"  type="str"  value="$(arg coordID)" />
+			<param name="coordID"  value="$(arg coordID)" />
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/YamlFileNames.yaml"
+				ns      = "YamlFileNames"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/SafeController.yaml"
+				ns      = "SafeController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/DemoController.yaml"
+				ns      = "DemoController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/StudentController.yaml"
+				ns      = "StudentController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/MpcController.yaml"
+				ns      = "MpcController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/RemoteController.yaml"
+				ns      = "RemoteController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/TuningController.yaml"
+				ns      = "TuningController"
+			/>
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/PickerController.yaml"
+				ns      = "PickerController"
+			/>
 		</node>
 
 	</group>
diff --git a/pps_ws/src/d_fall_pps/launch/Teacher.launch b/pps_ws/src/d_fall_pps/launch/Teacher.launch
index ef7b20a7..21028d0c 100755
--- a/pps_ws/src/d_fall_pps/launch/Teacher.launch
+++ b/pps_ws/src/d_fall_pps/launch/Teacher.launch
@@ -10,12 +10,4 @@
 	<node pkg="d_fall_pps" name="my_GUI" output="screen" type="my_GUI">
 	</node>
 
-	<!-- PARAMETER SERVICE -->
-	<node pkg="d_fall_pps" name="ParameterService" output="screen" type="ParameterService">
-		<param name="type" type="str" value="coordinator" />
-		<param name="agentID" value="0" />
-		<rosparam command="load" file="$(find d_fall_pps)/param/SafeController.yaml" ns="SafeController" />
-		<rosparam command="load" file="$(find d_fall_pps)/param/DemoController.yaml" ns="CustomController" />
-	</node>
-
 </launch>
diff --git a/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg b/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
new file mode 100755
index 00000000..a5802e7e
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
@@ -0,0 +1,3 @@
+float32 data
+bool shouldCheckForID
+uint8[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/msg/IntWithHeader.msg b/pps_ws/src/d_fall_pps/msg/IntWithHeader.msg
new file mode 100755
index 00000000..64cbfd8c
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/msg/IntWithHeader.msg
@@ -0,0 +1,3 @@
+uint32 data
+bool shouldCheckForID
+uint32[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg b/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
new file mode 100755
index 00000000..97b64956
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
@@ -0,0 +1,3 @@
+string data
+bool shouldCheckForID
+uint8[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
index a2f02eb0..15deb2f6 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -40,9 +40,7 @@
 
 
 
-// SPECIFY THE PACKAGE NAMESPACE
-using namespace d_fall_pps;
-//using namespace std;
+
 
 
 
@@ -284,52 +282,82 @@ void updateBatteryStateBasedOnLevel(int level)
 
 
 // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+void yamlReadyForFetchCallback(const IntWithHeader & msg)
 {
-	// Extract from the "msg" for which controller the and from where to fetch the YAML
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
+	// Continue if the message is relevant
+	if  (isRevelant)
 	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR:
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Load from the respective parameter service
+		// Switch between fetching for the different controllers and from different locations
+		switch(parameter_service_to_load_from)
 		{
-			// Let the user know that this message was received
-			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
 
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The StudentControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				// Let the user know that this message was received
+				ROS_INFO("[BATTERY MONITOR] Now fetching the YAML parameter values from this agent.");
+				// Create a node handle to the parameter service of this agent
+				ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+				// Call the function that fetches the parameters
+				fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+				break;
+			}
+
+			// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+			case LOAD_YAML_FROM_COORDINATOR:
+			{
+				// Let the user know that this message was received
+				ROS_INFO("[BATTERY MONITOR] Now fetching the YAML parameter values from this agent's coordinator.");
+				// Create a node handle to the parameter service of this agent's coordinator
+				ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+				// Call the function that fetches the parameters
+				fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+				break;
+			}
+
+			default:
+			{
+				// Let the user know that the command was not relevant
+				//ROS_INFO("The StudentControllerService received the message that YAML parameters were (re-)loaded");
+				//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
+				break;
+			}
 		}
 	}
 }
 
 
 
+// Check the header of a message for whether it is relevant
+bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs )
+{
+	// The messag is by default relevant if the "shouldCheckForID"
+	// flag is false
+	if (!shouldCheckForID)
+	{
+		return true;
+	}
+	else
+	{
+		// Iterate through the vector of IDs
+		for ( int i_ID=0 ; i_ID < agentIDs.size() ; i_ID++ )
+		{
+			if ( agentIDs[i_ID] == agentID )
+			{
+				return true;
+			}
+		}
+	}
+	// If the function made it to here, then the message is
+	// NOT relevant, hence return false
+	return false;
+}
 
 
 
@@ -424,6 +452,55 @@ int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
 
 
 
+bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref)
+{
+	// Initialise the return variable as success
+	bool return_was_successful = true;
+
+	// Create a node handle to the client
+	ros::NodeHandle client_nodeHandle(client_namespace);
+
+	// Get the value of the "agentID" parameter
+	int agentID_fetched;
+	if(!client_nodeHandle.getParam("agentID", agentID_fetched))
+	{
+		return_was_successful = false;
+	}
+	else
+	{
+		*agentID_ref = agentID_fetched;
+	}
+
+	// Get the value of the "coordID" parameter
+	int coordID_fetched;
+	if(!client_nodeHandle.getParam("coordID", coordID_fetched))
+	{
+		return_was_successful = false;
+	}
+	else
+	{
+		*coordID_ref = coordID_fetched;
+	}
+
+	// Return
+	return return_was_successful;
+}
+
+
+
+void getConstructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace )
+{
+	// Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
+	// for the parameter service that is running on the coordinate machine
+	// NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
+	//       is very important because it specifies that the name is global
+	// Convert the agent ID to a zero padded string
+	std::ostringstream str_stream;
+	str_stream << std::setw(3) << std::setfill('0') << coordID;
+	std::string coordID_as_string(str_stream.str());
+	coord_param_service_namespace = "/dfall/coord" + coordID_as_string + "/ParameterService";
+}
+
 
 //    ----------------------------------------------------------------------------------
 //    M   M    A    III  N   N
@@ -438,137 +515,72 @@ int main(int argc, char* argv[])
 	// Starting the ROS-node
 	ros::init(argc, argv, "BatteryMonitor");
 
-	// Create a "ros::NodeHandle" type local variable "nodeHandle" as the current node,
-	// the "~" indcates that "self" is the node handle assigned to this variable.
+	// Create a "ros::NodeHandle" type local variable named "nodeHandle",
+	// the "~" indcates that "self" is the node handle assigned.
 	ros::NodeHandle nodeHandle("~");
 
-	// Get the namespace of this "ParameterService" node
+	// Get the namespace of this node
 	std::string m_namespace = ros::this_node::getNamespace();
 	ROS_INFO_STREAM("[BATTERY MONITOR] ros::this_node::getNamespace() =  " << m_namespace);
 
-	// Get the agent ID as the "ROS_NAMESPACE" this computer.
-    // 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 "PPSClient"
-    // > Thus, to get access to the "agentID" paremeter, we first need to get
-    //   a handle to the "PPSClient" node with which this battery monitor
-    //   was created.
-    // Get the handle to the "PPSClient" node
-    ros::NodeHandle PPSClient_nodeHandle(m_namespace + "/PPSClient");
-    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", m_agentID))
-    {
-    	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[BATTERY MONITOR] Failed to get agentID from PPSClient");
-	}
-	else
-	{
-		// Let the user know what agentID was loaded
-		ROS_INFO_STREAM("[BATTERY MONITOR] loaded agentID = " << m_agentID);
-	}
 
 
+	// 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);
 
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[BATTERY SERVICE] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[BATTERY MONITOR] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+	}
 
-	// *********************************************************************************
-	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
 
 
-	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+	// PARAMETER SERVICE NAMESPACE AND NODEHANDLES:
 
-	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-	// namespace string for the parameter service that is running on the machine of this
-	// agent
+	// 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";
 
-	// Create a node handle to the parameter service running on this agent's machine
-	ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-
-	// Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-	// "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-	// and calls the class function "yamlReadyForFetchCallback" each time a message is
-	// received on this topic and the message is passed as an input argument to the
-	// "yamlReadyForFetchCallback" class function.
-	ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-
-
-	// EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
-
-	// Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-	// for the parameter service that is running on the coordinate machine
-	// NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-	//       is very important because it specifies that the name is global
-	m_namespace_to_coordinator_parameter_service = "/ParameterService";
-
-	// Create a node handle to the parameter service running on the coordinator machine
-	ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-	//ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-
-
-	// Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-	// "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-	// and calls the class function "yamlReadyForFetchCallback" each time a message is
-	// received on this topic and the message is passed as an input argument to the
-	// "yamlReadyForFetchCallback" class function.
-	ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-	//ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	getConstructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
-	// Set the class variable "m_own_agent_parameter_service_client"
-	// for making requests to the "LoadYamlFiles" service that is advertised
-	// by the "ParameterService" nodes
-	std::string own_agent_parameter_service_client_string = m_namespace_to_own_agent_parameter_service + "/LoadYamlFiles";
-	m_own_agent_parameter_service_client = ros::service::createClient<LoadYamlFiles>(own_agent_parameter_service_client_string, true);
-	ROS_INFO_STREAM("[BATTERY MONITOR] Loaded parameter service client: " << m_own_agent_parameter_service_client.getService());
-	
-	// PRINT OUT SOME INFORMATION
-
-	// Let the user know what namespaces are being used for linking to the parameter service
+	// Inform the user of what namespaces are being used
 	ROS_INFO_STREAM("[BATTERY MONITOR] The namespace string for accessing the Paramter Services are:");
 	ROS_INFO_STREAM("[BATTERY MONITOR] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
 	ROS_INFO_STREAM("[BATTERY MONITOR] 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
 
-	// FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
 
-	// Call the class function that loads the parameters for this class.
-	//fetchYamlParameters(m_nodeHandle_to_own_agent_parameter_service);
-
-	// Load the yaml paramters
-	ros::Duration(2.0).sleep();
-	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 1");
-	// Prepare the service call
-	LoadYamlFiles load_yaml_files_service_call;
-	std::string yaml_file_name_to_request = "BatteryMonitor";
-	load_yaml_files_service_call.request.yamlFileName = yaml_file_name_to_request;
-	// Call on the service
-	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 2");
-	bool success = m_own_agent_parameter_service_client.call(load_yaml_files_service_call);
-	if (success)
-	{
-		// Extract the data from the response
-		float wait_time_for_yaml = load_yaml_files_service_call.response.waitTime;
-		// Wait for the specified time
-		ros::Duration(wait_time_for_yaml).sleep();
-		// Call the function that loads the yaml paramters
-		fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-		ROS_INFO_STREAM("[BATTERY MONITOR] DEBUG 3");
-	}
-	else
-	{
-		ROS_INFO("[BATTERY MONITOR] The load yaml file service call was NOT successful.");
-	}
 
-	// *********************************************************************************
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+	// The parameters service publish 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, yamlReadyForFetchCallback);
+	ros::Subscriber batteryMonitor_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("BatteryMonitor", 1, yamlReadyForFetchCallback);
+
 
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
+	// Call the class function that loads the parameters for this class.
+	fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
 
 
 	// PUBLISHERS
+
 	// Publisher for the filtered battery voltage
 	ros::Publisher filteredBatteryVoltagePublisher = nodeHandle.advertise<std_msgs::Float32>("FilteredVoltage",1);
 
@@ -579,7 +591,9 @@ int main(int argc, char* argv[])
 	ros::Publisher batteryStateChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("ChangedStateTo",1);
 
 
+
 	// SUBSCRIBERS
+
 	// Subscribe to the voltage of the battery
 	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, newBatteryVoltageCallback);
 
@@ -594,8 +608,9 @@ int main(int argc, char* argv[])
 
 
 
-
+	// Inform the user the this node is ready
 	ROS_INFO("[BATTERY MONITOR] Ready :-)");
+	// Spin as a single-thread node
 	ros::spin();
 
 	return 0;
diff --git a/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
index 9195d629..031d7bdd 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
@@ -58,7 +58,7 @@
 #include "d_fall_pps/DebugMsg.h"
 
 // Include the Parameter Service shared definitions
-#include "nodes/ParameterServiceDefinitions.h"
+#include "nodes/Constants.h"
 
 #include <std_msgs/Int32.h>
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 144ddd19..2d656f30 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -1048,7 +1048,9 @@ int main(int argc, char* argv[])
     controller_setpoint.yaw = default_setpoint[3];
 
 	//ros::service::waitForService("/CentralManagerService/CentralManager");
-	centralManager = nodeHandle.serviceClient<CMQuery>("/CentralManagerService/Query", false);
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle dfall_root_nodeHandle("/dfall");
+	centralManager = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
 	loadCrazyflieContext();
 
 	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 536629ad..934e978d 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -74,7 +74,7 @@
 
 
 
-
+/*
 void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
 {
     // Extract from the "msg" for which controller the YAML
@@ -98,9 +98,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE SAFE CONTROLLER
     if (
-        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the safe controller:
@@ -109,9 +109,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE DEMO CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -120,9 +120,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE STUDENT CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -131,9 +131,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE MPC CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -142,9 +142,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE REMOTE CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -153,9 +153,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE TUNING CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -164,9 +164,9 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
     //    ----------------------------------------
     // FOR THE PICKER CONTROLLER
     else if (
-        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_COORDINATOR) && (my_type==TYPE_COORDINATOR))
+        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
         ||
-        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_AGENT)       && (my_type==TYPE_AGENT))
+        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
     )
     {
         // Re-load the parameters of the demo controller:
@@ -177,7 +177,7 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
         // Let the user know that the command was not recognised
         ROS_INFO_STREAM("[PARAMETER SERVICE] > Nothing to load for this parameter service with.");
         ROS_INFO_STREAM("[PARAMETER SERVICE] > The message received has 'controller_to_load_yaml'   =  " << controller_to_load_yaml);
-        ROS_INFO_STREAM("[PARAMETER SERVICE] > And the type of this Parameter Service is 'my_type'  =  " << my_type);
+        ROS_INFO_STREAM("[PARAMETER SERVICE] > And the type of this Parameter Service is 'm_type'  =  " << m_type);
         // Set the boolean that prevents the fetch message from being sent
         isValidToAttemptLoad = false;
     }
@@ -235,126 +235,131 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
         }
     }
 }
+*/
 
 
 
-
-bool loadYamlFiles(LoadYamlFiles::Request &request, LoadYamlFiles::Response &response)
+void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_load_with_header)
 {
-    ROS_INFO_STREAM("[PARAMETER SERVICE] DEBUG 1");
+    // LOAD THE YAML FILE
+
     // Get the yaml file name requested
-    std::string yamlFileName_toLoad = request.yamlFileName;
+    std::string yaml_filename_to_load = yaml_filename_to_load_with_header.data;
     // Get the node handle to this parameter service
     ros::NodeHandle nodeHandle("~");
-
-    // OLD: Get the yaml namespace from a yaml dictionary
-    //std::string yamlFileNamesParamters_basenamespace = "YamlFileNames/dictionary";
-    //std::string paramterName = yamlFileNamesParamters_basenamespace + "/" + yamlFileName_toLoad;
-    //std::string yamlFileName_from_dictionary;
-    //if(!nodeHandle.getParam(paramterName, yamlFileName_from_dictionary))
-    //{
-    //    ROS_ERROR_STREAM("[PARAMETER SERVICE] Missing parameter: '" << paramterName << "'");
-    //    return false;
-    //}
-
     // Instantiate a local variable for the command string that will be passed to the "system":
     std::string cmd;
-
     // Get the abolute path to "d_fall_pps":
     std::string d_fall_pps_path = ros::package::getPath("d_fall_pps");
-
     // Construct the system command string for (re-)loading the parameters:
-    cmd = "rosparam load " + d_fall_pps_path + "/param" + "/" + yamlFileName_toLoad + ".yaml " + m_base_namespace + "/" + yamlFileName_toLoad;
-
+    cmd = "rosparam load " + d_fall_pps_path + "/param" + "/" + yaml_filename_to_load + ".yaml " + m_base_namespace + "/" + yaml_filename_to_load;
     // Let the user know what is about to happen
     ROS_INFO_STREAM("[PARAMETER SERVICE] The following path will be used for locating the .yaml file: " << d_fall_pps_path  << " The comand line string sent to the 'system' is: " << cmd );
-
+    // Send the "load yaml" command to the system
     system(cmd.c_str());
 
-    // Pause breifly to ensure that the yaml file is fully loaded
-    //ros::Duration(0.5).sleep();
 
-    // Set the response wait time
-    response.waitTime = 2.0f;
-    ROS_INFO_STREAM("[PARAMETER SERVICE] DEBUG 2");
 
-    return true;
-}
+    // PUBLISH A MESSAGE THAT THE YAML FILE WAS LOADED
 
+    // Create publisher as a local variable, using the filename
+    // as the name of the message
+    ros::Publisher yamlParametersReadyForFetchPublisher = nodeHandle.advertise<StringWithHeader>(yaml_filename_to_load, 1);
+    // Create a local variable for the message
+    IntWithHeader yaml_ready_msg;
+    // Specify with the data the "type" of this parameter service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            yaml_ready_msg.data = LOAD_YAML_FROM_AGENT;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            yaml_ready_msg.data = LOAD_YAML_FROM_AGENT;
+            break;
+        }
+        default:
+        {
+            // Throw an error if the type is not recognised
+            ROS_ERROR("[PARAMETER SERVICE] The 'm_type' variable was not recognised.");
+            // Specify to load from the agent by default
+            yaml_ready_msg.data = LOAD_YAML_FROM_AGENT;
+            break;
+        }
+    }
+    // Copy across the boolean field
+    yaml_ready_msg.shouldCheckForID = yaml_filename_to_load_with_header.shouldCheckForID;
+    // Copy across the vector of IDs
+    if (yaml_filename_to_load_with_header.shouldCheckForID)
+    {
+        int length_of_IDs = yaml_filename_to_load_with_header.agentIDs.size();
+        for ( int i_ID=0 ; i_ID<length_of_IDs ; i_ID++ )
+        {
+            yaml_ready_msg.agentIDs.push_back(yaml_filename_to_load_with_header.agentIDs[i_ID]);
+        }
+    }
+    // Send the message
+    yamlParametersReadyForFetchPublisher.publish(yaml_ready_msg);
+}
 
 
 
 
-//    ----------------------------------------------------------------------------------
-//    M   M    A    III  N   N
-//    MM MM   A A    I   NN  N
-//    M M M  A   A   I   N N N
-//    M   M  AAAAA   I   N  NN
-//    M   M  A   A  III  N   N
-//    ----------------------------------------------------------------------------------
 
-int main(int argc, char* argv[])
+bool getTypeAndIDParameters()
 {
-    // Starting the ROS-node
-    ros::init(argc, argv, "ParameterService");
+    // Initialise the return variable as success
+    bool return_was_successful = true;
 
     // 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 "ParameterService" node
-    std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[PARAMETER SERVICE] ros::this_node::getNamespace() =  " << m_namespace);
-
-
-
     // Get the value of the "type" parameter into a local string variable
     std::string type_string;
     if(!nodeHandle.getParam("type", type_string))
     {
         // Throw an error if the agent ID parameter could not be obtained
-        ROS_ERROR("[PARAMETER SERVICE] Failed to get type from ParameterService");
+        ROS_ERROR("[PARAMETER SERVICE] Failed to get type");
     }
 
-    // Set the "my_type" instance variable based on this string loaded
+    // Set the "m_type" class variable based on this string loaded
     if ((!type_string.compare("coordinator")))
     {
-        my_type = TYPE_COORDINATOR;
+        m_type = TYPE_COORDINATOR;
     }
     else if ((!type_string.compare("agent")))
     {
-        my_type = TYPE_AGENT;
+        m_type = TYPE_AGENT;
     }
     else
     {
-        // Set "my_type" to the value indicating that it is invlid
-        my_type = TYPE_INVALID;
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
         ROS_ERROR("[PARAMETER SERVICE] The 'type' parameter retrieved was not recognised.");
     }
 
 
-    // Get the value of the "agentID" parameter into the instance variable "my_agentID"
-    if(!nodeHandle.getParam("agentID", my_agentID))
-    {
-        // Throw an error if the agent ID parameter could not be obtained
-        ROS_ERROR("[PARAMETER SERVICE] Failed to get agentID from ParameterService");
-    }
-
-
-    // Publisher that notifies the relevant nodes when the YAML paramters have been loaded
-    // from file into ram/cache, and hence are ready to be fetched
-    controllerYamlReadyForFetchPublisher = nodeHandle.advertise<std_msgs::Int32>("controllerYamlReadyForFetch", 1);
-    
-
     // Construct the string to the namespace of this Paramater Service
-    switch (my_type)
+    switch (m_type)
     {
         case TYPE_AGENT:
         {
-            //m_base_namespace = ros::this_node::getNamespace();
-            //m_base_namespace = "/agent" + my_agentID + '/' + "ParameterService";
-            m_base_namespace = m_namespace + '/' + "ParameterService";
-            ROS_INFO_STREAM("[PARAMETER SERVICE] .yaml file parameters will be loaded into the 'base' namespace: " << m_base_namespace);
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[PARAMETER SERVICE] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[PARAMETER SERVICE] Is of type AGENT with ID = " << m_ID);
+            }
             break;
         }
 
@@ -362,54 +367,56 @@ int main(int argc, char* argv[])
         // > The master GUI
         case TYPE_COORDINATOR:
         {
-            //m_base_namespace = ros::this_node::getNamespace();
-            //m_base_namespace = "/ParameterService";
-            m_base_namespace = m_namespace + '/' + "ParameterService";
-            ROS_INFO_STREAM("[PARAMETER SERVICE] .yaml file parameters will be loaded into the 'base' namespace: " << m_base_namespace);
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[PARAMETER SERVICE] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[PARAMETER SERVICE] Is of type COORDINATOR with ID = " << m_ID);
+            }
             break;
         }
 
         default:
         {
-            ROS_ERROR("[PARAMETER SERVICE] The 'my_type' type parameter was not recognised.");
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[PARAMETER SERVICE] The 'm_type' variable was not recognised.");
             break;
         }
     }
 
-    
+    // Return
+    return return_was_successful;
+}
+
 
 
-    // SUBSCRIBE TO THE APPROPRIATE "request" MESSAGES DEPENDING ON THE "my_type"
-    // Delare the subscribers as local variables here so that they persist for the life
-    // time of this main() function. The varaibles will be assigned in the switch case below
-    // > Subscribers for when this Parameter Service node is: TYPE_AGENT
-    ros::Subscriber requestLoadControllerYamlSubscriber_agent_to_self;
-    ros::Subscriber requestLoadControllerYamlSubscriber_agent_to_coordinator;
-    // > Subscribers for when this Parameter Service node is: TYPE_COORDINATOR
-    ros::Subscriber requestLoadControllerYamlSubscriber_coordinator_to_self;
 
-    // SUBSCRIBE TO THE APPROPRIATE "request" MESSAGES DEPENDING ON THE "my_type"
-    switch (my_type)
+
+bool constructNamespaces()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // Get the namespace of this "ParameterService" node
+    std::string this_node_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[PARAMETER SERVICE] ros::this_node::getNamespace() =  " << this_node_namespace);
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
     {
-        // AN AGENT TYPE PARAMETER SERVICE IS REQUESTED FROM:
-        // > The master GUI
-        // > The agent's own "PPSClient" node
         case TYPE_AGENT:
         {
-            // Subscribing to the agent's own PPSclient
-            // > First: Construct a node handle to the PPSclient
-            ros::NodeHandle nh_PPSClient_for_this_agent("PPSClient");
-            // > Second: Subscribe to the "requestLoadControllerYaml" topic
-            requestLoadControllerYamlSubscriber_agent_to_self = nh_PPSClient_for_this_agent.subscribe("requestLoadControllerYaml", 1, requestLoadControllerYamlCallback);
-
-            // Subscribing to the coordinator
-            // > First: construct a node handle to the coordinator
-            ros::NodeHandle nh_coordinator_for_this_agent = ros::NodeHandle();
-            // > Second: Subscribe to the "requestLoadControllerYaml" topic
-            requestLoadControllerYamlSubscriber_agent_to_coordinator = nh_coordinator_for_this_agent.subscribe("/my_GUI/requestLoadControllerYaml", 1, requestLoadControllerYamlCallback);            
-
-            // Inform the user what was subscribed to:
-            ROS_INFO_STREAM("[PARAMETER SERVICE] Subscribed to 'requestLoadControllerYaml' messages from both the 'my_GUI' and the 'PPSClient'");
+            //m_base_namespace = ros::this_node::getNamespace();
+            //m_base_namespace = "/agent" + m_Id + '/' + "ParameterService";
+            m_base_namespace = this_node_namespace + '/' + "ParameterService";
+            ROS_INFO_STREAM("[PARAMETER SERVICE] .yaml file parameters will be loaded into the 'base' namespace: " << m_base_namespace);
             break;
         }
 
@@ -417,36 +424,67 @@ int main(int argc, char* argv[])
         // > The master GUI
         case TYPE_COORDINATOR:
         {
-            // Subscribing to the coordinator's own "my_GUI" 
-            // > First: Get the node handle required
-            ros::NodeHandle nh_coordinator_for_this_coordinator = ros::NodeHandle();
-            // > Second: Subscribe to requests from: the master GUI
-            requestLoadControllerYamlSubscriber_coordinator_to_self = nh_coordinator_for_this_coordinator.subscribe("/my_GUI/requestLoadControllerYaml", 1, requestLoadControllerYamlCallback);
-
-            // Inform the user what was subscribed to:
-            ROS_INFO_STREAM("[PARAMETER SERVICE] Subscribed to 'requestLoadControllerYaml' messages from 'my_GUI'");
+            //m_base_namespace = ros::this_node::getNamespace();
+            //m_base_namespace = "/ParameterService";
+            m_base_namespace = this_node_namespace + '/' + "ParameterService";
+            ROS_INFO_STREAM("[PARAMETER SERVICE] .yaml file parameters will be loaded into the 'base' namespace: " << m_base_namespace);
             break;
         }
 
         default:
         {
-            ROS_ERROR("[PARAMETER SERVICE] The 'my_type' type parameter was not recognised.");
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[PARAMETER SERVICE] The 'm_type' type parameter was not recognised.");
             break;
         }
     }
 
+    // Return
+    return return_was_successful;
+}
+
+
+
+
 
-    // Advertise the service for loading Yaml Files
-    ros::ServiceServer service = nodeHandle.advertiseService("LoadYamlFiles", loadYamlFiles);
+//    ----------------------------------------------------------------------------------
+//    M   M    A    III  N   N
+//    MM MM   A A    I   NN  N
+//    M M M  A   A   I   N N N
+//    M   M  AAAAA   I   N  NN
+//    M   M  A   A  III  N   N
+//    ----------------------------------------------------------------------------------
 
+int main(int argc, char* argv[])
+{
+    // Starting the ROS-node
+    ros::init(argc, argv, "ParameterService");
 
+    // 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("~");
 
-    // LOAD THE LIST OF YAML FILE NAMES
+    // Get the type and ID of this parameter service
+    bool isValid_type_and_ID = getTypeAndIDParameters();
 
+    // Construct the namespace into which this parameter service
+    // loads yaml parameters
+    bool isValid_namespaces = constructNamespaces();
 
+    // Stall the parameter service is the TYPE and ID are not valid
+    if ( !( isValid_type_and_ID && isValid_namespaces ) )
+    {
+        ROS_ERROR("[PARAMETER SERVICE] Service NOT FUNCTIONING :-)");
+        ros::spin();
+    }
 
+    // Subscribe to the messages that request loading a yaml file
+    ros::Subscriber requestLoadYamlFilenameSubscriber = nodeHandle.subscribe("requestLoadYamlFilename", 1, requestLoadYamlFilenameCallback);
 
+    // Inform the user the this node is ready
     ROS_INFO("[PARAMETER SERVICE] Service ready :-)");
+    // Spin as a single-thread node
     ros::spin();
 
     return 0;
diff --git a/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv b/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv
deleted file mode 100644
index fc7c7120..00000000
--- a/pps_ws/src/d_fall_pps/srv/LoadYamlFiles.srv
+++ /dev/null
@@ -1,3 +0,0 @@
-string yamlFileName
----
-float64 waitTime
-- 
GitLab


From 1f3225f7530ae4dbe1509758c4ed8565d82bd661 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 8 Dec 2018 16:09:34 +0100
Subject: [PATCH 05/87] Added load yaml drop down menu to flying agent GUI

---
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui | 20 ++++++++++++++++++-
 .../flyingAgentGUI/include/mainwindow.h       |  2 ++
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  | 18 +++++++++++++++++
 3 files changed, 39 insertions(+), 1 deletion(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index 9c03449c..e35441f9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -151,7 +151,7 @@
      <x>0</x>
      <y>0</y>
      <width>1862</width>
-     <height>25</height>
+     <height>40</height>
     </rect>
    </property>
    <widget class="QMenu" name="menuFile">
@@ -160,7 +160,15 @@
     </property>
     <addaction name="actionShowHide_Coordinator"/>
    </widget>
+   <widget class="QMenu" name="menuLoad_YAML">
+    <property name="title">
+     <string>LoadYAML</string>
+    </property>
+    <addaction name="action_LoadYAML_BatteryMonitor"/>
+    <addaction name="action_LoadYAML_ClientConfig"/>
+   </widget>
    <addaction name="menuFile"/>
+   <addaction name="menuLoad_YAML"/>
   </widget>
   <widget class="QToolBar" name="mainToolBar">
    <attribute name="toolBarArea">
@@ -176,6 +184,16 @@
     <string>Hide Coordinator</string>
    </property>
   </action>
+  <action name="action_LoadYAML_BatteryMonitor">
+   <property name="text">
+    <string>BatteryMonitor</string>
+   </property>
+  </action>
+  <action name="action_LoadYAML_ClientConfig">
+   <property name="text">
+    <string>ClientConfig</string>
+   </property>
+  </action>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <customwidgets>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 124eda80..f61703c4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -58,6 +58,8 @@ public:
 
 private slots:
     void on_actionShowHide_Coordinator_triggered();
+    void on_action_LoadYAML_BatteryMonitor_triggered();
+    void on_action_LoadYAML_ClientConfig_triggered();
 
 private:
     Ui::MainWindow *ui;
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 13382717..544d3ab3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -76,3 +76,21 @@ void MainWindow::on_actionShowHide_Coordinator_triggered()
         ui->actionShowHide_Coordinator->setText(qstr);
     }
 }
+
+
+void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
+{
+#ifdef CATKIN_MAKE
+    // Send a message that the "BatteryMonitor" Yaml should be loaded
+    // by the appropriate Parameter Service
+#endif
+}
+
+
+void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
+{
+#ifdef CATKIN_MAKE
+    // Send a message that the "ClientConfig" Yaml should be loaded
+    // by the appropriate Parameter Service
+#endif
+}
-- 
GitLab


From c61f7547eb86b544670fbaf31dc839fd5ac7c392 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 00:06:20 +0100
Subject: [PATCH 06/87] Have setup the basic framework of the coordinator
 connections. Next step to connect all GUI buttons for (dis-)connect,
 start,stop,off,and select controller. And then test.

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   66 +-
 .../CrazyFlyGUI/include/mainguiwindow.h       |   13 +-
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  |   20 +-
 .../flyingAgentGUI/include/coordinatorrow.h   |   12 +-
 .../include/enablecontrollerloadyamlbar.h     |   38 +-
 .../flyingAgentGUI/include/mainwindow.h       |   28 +
 .../flyingAgentGUI/src/coordinatorrow.cpp     |   11 +-
 .../src/enablecontrollerloadyamlbar.cpp       |  157 ++-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  124 +-
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   |   25 +-
 .../classes/GetParamtersAndNamespaces.h       |  132 +++
 .../d_fall_pps/include/nodes/BatteryMonitor.h |   69 +-
 .../include/nodes/CentralManagerService.h     |   11 +
 .../src/d_fall_pps/include/nodes/Constants.h  |   96 ++
 .../include/nodes/DemoControllerService.h     |    3 -
 .../src/d_fall_pps/include/nodes/PPSClient.h  |  150 ++-
 .../include/nodes/ParameterService.h          |    9 +-
 .../include/nodes/PickerControllerService.h   |    8 -
 .../include/nodes/RemoteControllerService.h   |    3 -
 .../include/nodes/SafeControllerService.h     |    3 -
 .../include/nodes/StudentControllerService.h  |    3 -
 .../include/nodes/TuningControllerService.h   |    3 -
 pps_ws/src/d_fall_pps/launch/Agent.launch     |    9 +-
 pps_ws/src/d_fall_pps/launch/Config.sh        |    4 +-
 .../src/d_fall_pps/launch/Coordinator.launch  |   34 +-
 pps_ws/src/d_fall_pps/param/ClientConfig.yaml |    1 +
 .../src/classes/GetParamtersAndNamespaces.cpp |  234 ++++
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   |  215 +---
 .../src/nodes/CentralManagerService.cpp       |   16 +-
 .../src/nodes/MpcControllerService.cpp        |    3 -
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp | 1001 ++++++++++-------
 .../d_fall_pps/src/nodes/ParameterService.cpp |   15 +-
 32 files changed, 1678 insertions(+), 838 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
 create mode 100644 pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 84a1ade4..294a21b8 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -320,17 +320,19 @@ if(VICON_LIBRARY)
 	add_executable(ViconDataPublisher       src/nodes/ViconDataPublisher.cpp)
 endif()
 
-add_executable(PPSClient                src/nodes/PPSClient.cpp)
-add_executable(BatteryMonitor           src/nodes/BatteryMonitor.cpp)
-add_executable(SafeControllerService    src/nodes/SafeControllerService.cpp)
-add_executable(DemoControllerService    src/nodes/DemoControllerService.cpp)
-add_executable(StudentControllerService src/nodes/StudentControllerService.cpp)
-add_executable(MpcControllerService     src/nodes/MpcControllerService.cpp)
-add_executable(RemoteControllerService  src/nodes/RemoteControllerService.cpp)
-add_executable(TuningControllerService  src/nodes/TuningControllerService.cpp)
-add_executable(PickerControllerService  src/nodes/PickerControllerService.cpp)
-add_executable(CentralManagerService    src/nodes/CentralManagerService.cpp src/CrazyflieIO.cpp)
-add_executable(ParameterService         src/nodes/ParameterService.cpp)
+add_executable(PPSClient                 src/nodes/PPSClient.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
+add_executable(BatteryMonitor            src/nodes/BatteryMonitor.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
+add_executable(SafeControllerService     src/nodes/SafeControllerService.cpp)
+add_executable(DemoControllerService     src/nodes/DemoControllerService.cpp)
+add_executable(StudentControllerService  src/nodes/StudentControllerService.cpp)
+add_executable(MpcControllerService      src/nodes/MpcControllerService.cpp)
+add_executable(RemoteControllerService   src/nodes/RemoteControllerService.cpp)
+add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp)
+add_executable(PickerControllerService   src/nodes/PickerControllerService.cpp)
+add_executable(CentralManagerService     src/nodes/CentralManagerService.cpp src/CrazyflieIO.cpp)
+add_executable(ParameterService          src/nodes/ParameterService.cpp)
 
 
 
@@ -404,17 +406,17 @@ if(VICON_LIBRARY)
 	add_dependencies(ViconDataPublisher       d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 endif()
 
-add_dependencies(PPSClient                d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(BatteryMonitor           d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(SafeControllerService    d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(DemoControllerService    d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(StudentControllerService d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(MpcControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(RemoteControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(TuningControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(PickerControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(CentralManagerService    d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(ParameterService         d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(PPSClient                 d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(BatteryMonitor            d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(SafeControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(DemoControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(StudentControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(MpcControllerService      d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(RemoteControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(TuningControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(PickerControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(CentralManagerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(ParameterService          d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
@@ -455,21 +457,21 @@ if(VICON_LIBRARY)
 	target_link_libraries(ViconDataPublisher ${VICON_LIBRARY})
 endif()
 
-target_link_libraries(PPSClient                ${catkin_LIBRARIES})
-target_link_libraries(BatteryMonitor           ${catkin_LIBRARIES})
-target_link_libraries(SafeControllerService    ${catkin_LIBRARIES})
-target_link_libraries(DemoControllerService    ${catkin_LIBRARIES})
-target_link_libraries(StudentControllerService ${catkin_LIBRARIES})
+target_link_libraries(PPSClient                 ${catkin_LIBRARIES})
+target_link_libraries(BatteryMonitor            ${catkin_LIBRARIES})
+target_link_libraries(SafeControllerService     ${catkin_LIBRARIES})
+target_link_libraries(DemoControllerService     ${catkin_LIBRARIES})
+target_link_libraries(StudentControllerService  ${catkin_LIBRARIES})
 if(Eigen3_FOUND)
   target_link_libraries(MpcControllerService     ${catkin_LIBRARIES} Eigen3::Eigen)
 else()
   target_link_libraries(MpcControllerService     ${catkin_LIBRARIES})
 endif()
-target_link_libraries(RemoteControllerService  ${catkin_LIBRARIES})
-target_link_libraries(TuningControllerService  ${catkin_LIBRARIES})
-target_link_libraries(PickerControllerService  ${catkin_LIBRARIES})
-target_link_libraries(CentralManagerService    ${catkin_LIBRARIES})
-target_link_libraries(ParameterService         ${catkin_LIBRARIES})
+target_link_libraries(RemoteControllerService   ${catkin_LIBRARIES})
+target_link_libraries(TuningControllerService   ${catkin_LIBRARIES})
+target_link_libraries(PickerControllerService   ${catkin_LIBRARIES})
+target_link_libraries(CentralManagerService     ${catkin_LIBRARIES})
+target_link_libraries(ParameterService          ${catkin_LIBRARIES})
 
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
index 96a9f12b..ef7d7920 100755
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
@@ -42,15 +42,22 @@
 
 #ifdef CATKIN_MAKE
 #include "rosNodeThread_for_managerGUI.h"
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
 #include "marker.h"
 #include "crazyFly.h"
 #include "CFLinker.h"
 
+// Include the DFALL service types
 #include "d_fall_pps/CrazyflieDB.h"
 #include "d_fall_pps/CrazyflieEntry.h"
 
-#include <std_msgs/Int32.h>
-
 
 // The constants that are sent to the agents in order to
 // "command" changes in their operation state
@@ -235,7 +242,7 @@ private:
 
     std::string ros_namespace;
 
-    ros::Publisher DBChangedPublisher;
+    //ros::Publisher DBChangedPublisher;
     ros::Publisher emergencyStopPublisher;
 
     // Publsher for sending "commands" from here (the master) to all
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
index 8cd1e74c..2f790f7e 100755
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
@@ -275,8 +275,11 @@ void MainGUIWindow::_init()
     ros_namespace = ros::this_node::getNamespace();
 
     ros::NodeHandle nodeHandle("~");
-    DBChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("DBChanged", 1);
-    emergencyStopPublisher = nodeHandle.advertise<std_msgs::Int32>("emergencyStop", 1);
+    //DBChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("DBChanged", 1);
+
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle nodeHandle_dfall_root("/dfall");
+    emergencyStopPublisher = nodeHandle_dfall_root.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
 
     // Initialise the publisher for sending "commands" from here (the master)
     // to all of the agent nodes
@@ -883,9 +886,9 @@ void MainGUIWindow::on_save_in_DB_button_clicked()
     fill_database_file();
 
     // Now also publish a ROS message stating that we changed the DB, so the nodes can update it
-    std_msgs::Int32 msg;
-    msg.data = 1;
-    this->DBChangedPublisher.publish(msg);
+    //std_msgs::Int32 msg;
+    //msg.data = 1;
+    //this->DBChangedPublisher.publish(msg);
 }
 
 void MainGUIWindow::clear_database_file()
@@ -1105,10 +1108,11 @@ void MainGUIWindow::on_all_land_button_clicked()
 // > MOTORS OFF
 void MainGUIWindow::on_all_motors_off_button_clicked()
 {
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-    commandAllAgentsPublisher.publish(msg);
-    //emergencyStopPublisher.publish(msg);
+    msg.shouldCheckForID = false;
+    //commandAllAgentsPublisher.publish(msg);
+    emergencyStopPublisher.publish(msg);
 }
 // > ENABLE SAFE CONTROLLER
 void MainGUIWindow::on_all_enable_safe_controller_button_clicked()
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 8e5ef664..75410c45 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -38,17 +38,23 @@
 #include <QMutex>
 
 #ifdef CATKIN_MAKE
-#include <std_msgs/Int32.h>
-#include <std_msgs/Float32.h>
-
 #include <ros/ros.h>
 #include <ros/network.h>
 #include <ros/package.h>
 
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/AreaBounds.h"
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/CMQuery.h"
 
+
+
 using namespace d_fall_pps;
 #endif
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 147dec5b..1d757b1c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -4,17 +4,26 @@
 #include <QWidget>
 
 #ifdef CATKIN_MAKE
-#include <std_msgs/Int32.h>
-#include <std_msgs/Float32.h>
-
 #include <ros/ros.h>
 #include <ros/network.h>
 #include <ros/package.h>
 
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+
+// Include the DFALL service types
 // #include "d_fall_pps/AreaBounds.h"
 // #include "d_fall_pps/CrazyflieContext.h"
 // #include "d_fall_pps/CMQuery.h"
 
+// Include the shared definitions
+#include "nodes/Constants.h"
+
 // using namespace d_fall_pps;
 #endif
 
@@ -65,9 +74,28 @@ private:
     // --------------------------------------------------- //
     // PRIVATE VARIABLES FOR ROS
 
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
     // PUBLISHERS AND SUBSRIBERS
-    // > For Crazyradio commands based on button clicks
-    ros::Publisher commandAllPublisher;
+    // > For {take-off,land,motors-off} and controller selection
+    ros::Publisher commandPublisher;
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS FOR ROS
+
+    // Fill the head for a message
+    void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
+
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
+
+
+
 #endif
 };
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index f61703c4..8281e486 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -41,6 +41,21 @@
 #include <ros/network.h>
 #include <ros/package.h>
 #include "rosNodeThread_for_flyingAgentGUI.h"
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/StringWithHeader.h"
+
+#include "nodes/Constants.h"
+
+// Namespacing the package
+using namespace d_fall_pps;
+//using namespace std;
+
 #endif
 
 
@@ -68,6 +83,19 @@ private:
 
 #ifdef CATKIN_MAKE
     rosNodeThread* m_rosNodeThread;
+
+    // Variables for the type and ID
+    // The type of this node, i.e., agent or a coordinator, 
+    // specififed as a parameter in the "*.launch" file
+	int m_type = 0;
+
+	// The ID of this node
+	int m_ID = 0;
+
+	// The namespace into which this parameter service loads yaml parameters
+	std::string m_parameter_service_namespace;
+
+	ros::Publisher m_requestLoadYamlFilenamePublisher;
 #endif
 
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 1f073f9b..68c7e58c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -125,7 +125,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     // > For updating the current battery state
     batteryStateSubscriber = base_nodeHandle.subscribe("PPSClient/batteryState", 1, &CoordinatorRow::batteryStateChangedCallback, this);
     // > For Flying state commands based on button clicks
-    flyingStateCommandPublisher = base_nodeHandle.advertise<std_msgs::Int32>("PPSClient/Command", 1);
+    flyingStateCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
     // > For updating the "flying_state_label" picture
     flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/flyingState", 1, &CoordinatorRow::flyingStateChangedCallback, this);
     // > For changes in the database that defines {agentID,cfID,flying zone} links
@@ -712,7 +712,8 @@ void CoordinatorRow::on_rf_disconnect_button_clicked()
 void CoordinatorRow::on_enable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
 #endif
@@ -721,7 +722,8 @@ void CoordinatorRow::on_enable_flying_button_clicked()
 void CoordinatorRow::on_disable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
 #endif
@@ -730,7 +732,8 @@ void CoordinatorRow::on_disable_flying_button_clicked()
 void CoordinatorRow::on_motors_off_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
 #endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index e844d060..14df7d63 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -10,10 +10,27 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
 
 #ifdef CATKIN_MAKE
     //ros::init();
-    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
-    ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
-    commandAllPublisher = dfall_root_nodeHandle.advertise<std_msgs::Int32>("/my_GUI/commandAllAgents", 1);
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[FLYING AGENT GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[FLYING AGENT GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE COMMAND PUBLISHER
+    commandPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
 #endif
 
 }
@@ -31,9 +48,10 @@ EnableControllerLoadYamlBar::~EnableControllerLoadYamlBar()
 void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
     msg.data = CMD_USE_SAFE_CONTROLLER;
-    this->commandAllPublisher.publish(msg);
+    this->commandPublisher.publish(msg);
     ROS_INFO("[FLYING AGENT GUI] Enable Safe Controller");
 #endif
 }
@@ -41,9 +59,10 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_demo_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
     msg.data = CMD_USE_DEMO_CONTROLLER;
-    this->commandAllPublisher.publish(msg);
+    this->commandPublisher.publish(msg);
     ROS_INFO("[FLYING AGENT GUI] Enable Demo Controller");
 #endif
 }
@@ -51,9 +70,10 @@ void EnableControllerLoadYamlBar::on_enable_demo_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
     msg.data = CMD_USE_STUDENT_CONTROLLER;
-    this->commandAllPublisher.publish(msg);
+    this->commandPublisher.publish(msg);
     ROS_INFO("[FLYING AGENT GUI] Enable Student Controller");
 #endif
 }
@@ -85,3 +105,122 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 {
 
 }
+
+
+#ifdef CATKIN_MAKE
+// Fill the head for a message
+void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            msg.shouldCheckForID = true;
+            msg.agentIDs.push_back(7);
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForID = true;
+            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+#ifdef CATKIN_MAKE
+bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[FLYING AGENT GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[FLYING AGENT GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[FLYING AGENT GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[FLYING AGENT GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 544d3ab3..a0e08224 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -50,7 +50,105 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     // > For "kill GUI node", press "CTRL+C" while the GUI window is the focus
     m_close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close()));
 
+#ifdef CATKIN_MAKE
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[FLYING AGENT GUI] Failed to get type");
+    }
+
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        ROS_ERROR("[FLYING AGENT GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                ROS_ERROR("[FLYING AGENT GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
 
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                ROS_ERROR("[FLYING AGENT GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+
+
+    // Get the namespace of this "ParameterService" node
+    std::string this_node_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[FLYING AGENT GUI] ros::this_node::getNamespace() =  " << this_node_namespace);
+
+    // Construct the string to the namespace of this Paramater Service
+    m_parameter_service_namespace = this_node_namespace + '/' + "ParameterService";
+    ROS_INFO_STREAM("[FLYING AGENT GUI] parameter service is: " << m_parameter_service_namespace);
+
+    // Get the node handle to this parameter service
+    ros::NodeHandle nodeHandle_to_parameter_service(m_parameter_service_namespace);
+    m_requestLoadYamlFilenamePublisher = nodeHandle_to_parameter_service.advertise<StringWithHeader>("requestLoadYamlFilename", 1);
+
+    // Remove the show/hide coordinator menu item if launch as an agent
+    if (m_type==TYPE_AGENT)
+    {
+        // Hide the coordinator part of the GUI
+        ui->customWidget_coordinator->hide();
+        // And make the menu item unavailable
+        ui->actionShowHide_Coordinator->setEnabled(false);
+
+    }
+#endif
 
 }
 
@@ -81,8 +179,17 @@ void MainWindow::on_actionShowHide_Coordinator_triggered()
 void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
 {
 #ifdef CATKIN_MAKE
-    // Send a message that the "BatteryMonitor" Yaml should be loaded
-    // by the appropriate Parameter Service
+    // Inform the user that the menu item was selected
+    ROS_INFO("[FLYING AGENT GUI] Load Battery Monitor YAML was clicked.");
+
+    // Create a local variable for the message
+    StringWithHeader yaml_filename_msg;
+    // Specify the data
+    yaml_filename_msg.data = "BatteryMonitor";
+    // Set for whom this applies to
+    yaml_filename_msg.shouldCheckForID = false;
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 #endif
 }
 
@@ -90,7 +197,16 @@ void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
 void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
 {
 #ifdef CATKIN_MAKE
-    // Send a message that the "ClientConfig" Yaml should be loaded
-    // by the appropriate Parameter Service
+    // Inform the user that the menu item was selected
+    ROS_INFO("[FLYING AGENT GUI] Load Client Config YAML was clicked.");
+
+    // Create a local variable for the message
+    StringWithHeader yaml_filename_msg;
+    // Specify the data
+    yaml_filename_msg.data = "ClientConfig";
+    // Set for whom this applies to
+    yaml_filename_msg.shouldCheckForID = false;
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 #endif
 }
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index 8562b558..d12f08d2 100755
--- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -35,8 +35,9 @@
 
 import roslib; roslib.load_manifest('d_fall_pps')
 import rospy
-from d_fall_pps.msg import ControlCommand
 from std_msgs.msg import Int32
+from d_fall_pps.msg import ControlCommand
+from d_fall_pps.msg import IntWithHeader
 
 
 # General import
@@ -124,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', Int32, queue_size=1)
+        self.PPSClient_command_pub = rospy.Publisher('PPSClient/Command', IntWithHeader, queue_size=1)
         time.sleep(1.0)
 
         # Initialize the CrazyFlie and add callbacks
@@ -168,7 +169,10 @@ class PPSRadioClient:
         print "Motors OFF"
         self._send_to_commander_motor(0, 0, 0, 0)
         # change state to motors OFF
-        self.PPSClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
+        msg = IntWithHeader()
+        msg.shouldCheckForID = False
+        msg.data = CMD_CRAZYFLY_MOTORS_OFF
+        self.PPSClient_command_pub.publish(msg)
         time.sleep(0.1)
         print "Disconnecting from %s" % self.link_uri
         self._cf.close_link()
@@ -225,7 +229,10 @@ class PPSRadioClient:
         """
         self.change_status_to(CONNECTED)
         # change state to motors OFF
-        cf_client.PPSClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
+        msg = IntWithHeader()
+        msg.shouldCheckForID = False
+        msg.data = CMD_CRAZYFLY_MOTORS_OFF
+        cf_client.PPSClient_command_pub.publish(msg)
 
         rospy.loginfo("Connection to %s successful: " % link_uri)
         # Config for Logging
@@ -252,7 +259,10 @@ class PPSRadioClient:
         rospy.logwarn("Disconnected from %s" % link_uri)
 
         # change state to motors OFF
-        self.PPSClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
+        msg = IntWithHeader()
+        msg.shouldCheckForID = False
+        msg.data = CMD_CRAZYFLY_MOTORS_OFF
+        self.PPSClient_command_pub.publish(msg)
 
         self.logconf.stop()
         rospy.loginfo("logconf stopped")
@@ -359,7 +369,10 @@ if __name__ == '__main__':
 
     cf_client._send_to_commander_motor(0, 0, 0, 0)
     # change state to motors OFF
-    cf_client.PPSClient_command_pub.publish(CMD_CRAZYFLY_MOTORS_OFF)
+    msg = IntWithHeader()
+    msg.shouldCheckForID = False
+    msg.data = CMD_CRAZYFLY_MOTORS_OFF
+    cf_client.PPSClient_command_pub.publish(msg)
     #wait for client to send its commands
     time.sleep(1.0)
 
diff --git a/pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h b/pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
new file mode 100644
index 00000000..f92f393d
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
@@ -0,0 +1,132 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The service that manages the loading of YAML parameters
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  N   N   CCCC  L      U   U  DDDD   EEEEE   SSSS
+//     I   NN  N  C      L      U   U  D   D  E      S
+//     I   N N N  C      L      U   U  D   D  EEE     SSS
+//     I   N  NN  C      L      U   U  D   D  E          S
+//    III  N   N   CCCC  LLLLL   UUU   DDDD   EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+#include <stdlib.h>
+#include <iostream>
+#include <string>
+
+#include <ros/ros.h>
+#include <ros/package.h>
+#include <ros/network.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+using namespace d_fall_pps;
+//using namespace std;
+
+
+
+//    ----------------------------------------------------------------------------------
+//    DDDD   EEEEE  FFFFF  III  N   N  EEEEE   SSSS
+//    D   D  E      F       I   NN  N  E      S
+//    D   D  EEE    FFF     I   N N N  EEE     SSS
+//    D   D  E      F       I   N  NN  E          S
+//    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    V   V    A    RRRR   III    A    BBBB   L      EEEEE   SSSS
+//    V   V   A A   R   R   I    A A   B   B  L      E      S
+//    V   V  A   A  RRRR    I   A   A  BBBB   L      EEE     SSS
+//     V V   AAAAA  R  R    I   AAAAA  B   B  L      E          S
+//      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    PPPP   RRRR    OOO   TTTTT   OOO   TTTTT  Y   Y  PPPP   EEEEE   SSSS
+//    P   P  R   R  O   O    T    O   O    T     Y Y   P   P  E      S
+//    PPPP   RRRR   O   O    T    O   O    T      Y    PPPP   EEE     SSS
+//    P      R  R   O   O    T    O   O    T      Y    P      E          S
+//    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+// GET YAML PARAMETER FUNCTIONS
+float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
+int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
+bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
+
+void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
+void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
+int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
+
+
+
+// FUNCTIONS FOR GETTING IDs AND NAMESPACES
+
+// Get the "agentID" and "coordID" from the client node
+bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref);
+
+// Construct the namespaces for the coordinator
+void constructNamespaceForCoordinator( int coordID, std::string & coord_namespace );
+
+// Construct the namespaces for the coordinator's parameter services
+void constructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace );
+
+// Check the header of a message for whether it is relevant
+bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs );
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index d7eff9d1..1739c05b 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -59,6 +59,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
+#include "classes/GetParamtersAndNamespaces.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
 using namespace d_fall_pps;
@@ -75,18 +76,18 @@ using namespace d_fall_pps;
 //    ----------------------------------------------------------------------------------
 
 // Battery levels
-#define BATTERY_LEVEL_000            0
-#define BATTERY_LEVEL_010            1
-#define BATTERY_LEVEL_020            2
-#define BATTERY_LEVEL_030            3
-#define BATTERY_LEVEL_040            4
-#define BATTERY_LEVEL_050            5
-#define BATTERY_LEVEL_060            6
-#define BATTERY_LEVEL_070            7
-#define BATTERY_LEVEL_080            8
-#define BATTERY_LEVEL_090            9
-#define BATTERY_LEVEL_100           10
-#define BATTERY_LEVEL_UNAVAILABLE   -1
+// #define BATTERY_LEVEL_000            0
+// #define BATTERY_LEVEL_010            1
+// #define BATTERY_LEVEL_020            2
+// #define BATTERY_LEVEL_030            3
+// #define BATTERY_LEVEL_040            4
+// #define BATTERY_LEVEL_050            5
+// #define BATTERY_LEVEL_060            6
+// #define BATTERY_LEVEL_070            7
+// #define BATTERY_LEVEL_080            8
+// #define BATTERY_LEVEL_090            9
+// #define BATTERY_LEVEL_100           10
+// #define BATTERY_LEVEL_UNAVAILABLE   -1
 
 // Battery states
 #define BATTERY_STATE_NORMAL         0
@@ -97,13 +98,6 @@ using namespace d_fall_pps;
 #define TYPE_COORDINATOR   1
 #define TYPE_AGENT         2
 
-
-// CrazyRadio states:
-#define CRAZY_RADIO_STATE_CONNECTED      0
-#define CRAZY_RADIO_STATE_CONNECTING     1
-#define CRAZY_RADIO_STATE_DISCONNECTED   2
-
-
 // Flying states
 #define AGENT_OPERATING_STATE_MOTORS_OFF 1
 #define AGENT_OPERATING_STATE_TAKE_OFF   2
@@ -187,9 +181,14 @@ int yaml_battery_delay_threshold_to_change_state = 5;
 //    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+// Callback for the raw voltage data
 void newBatteryVoltageCallback(const std_msgs::Float32& msg);
-
+// The selector for the filter
 float newBatteryVoltageForFilter(float new_value);
+// Moving average filter
+float movingAverageBatteryFilter(float new_input);
+
+
 // > For converting a voltage to a percentage,
 //   depending on the current "my_flying_state" value
 float fromVoltageToPercent(float voltage , float operating_state);
@@ -201,31 +200,5 @@ void updateBatteryStateBasedOnLevel(int level);
 
 
 // LOAD YAML PARAMETER FUNCTIONS
-void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-void processFetchedParameters();
-
-void yamlReadyForFetchCallback(const IntWithHeader & msg);
-
-
-
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-
-
-
-
-
-
-
-
-
-// FUNCTIONS FOR TEMPLATING A GET STUFF CLASS
-
-// Get the "agentID" and "coordID" from the client node
-bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref);
-
-// Construct the namespaces for the parameter services
-void getConstructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace );
-
-// Check the header of a message for whether it is relevant
-bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs );
\ No newline at end of file
+void isReadyBatteryMonitorYamlCallback(const IntWithHeader & msg);
+void fetchBatteryMonitorYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h b/pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
index 9d7f81e8..db93514f 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
@@ -43,14 +43,23 @@
 
 #include <stdlib.h>
 #include <ros/ros.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/CrazyflieDB.h"
 
+// Include the DFALL service types
 #include "d_fall_pps/CMRead.h"
 #include "d_fall_pps/CMQuery.h"
 #include "d_fall_pps/CMUpdate.h"
 #include "d_fall_pps/CMCommand.h"
 
+// Include other classes
 #include "CrazyflieIO.h"
 
 
@@ -103,6 +112,8 @@ using namespace std;
 
 CrazyflieDB crazyflieDB;
 
+ros::Publisher m_databaseChangedPublisher;
+
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/Constants.h b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
index 91e1f664..ac3ecb91 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/Constants.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
@@ -30,6 +30,71 @@
 //    ----------------------------------------------------------------------------------
 
 
+//    ----------------------------------------------------------------------------------
+//    U   U
+//    U   U
+//    U   U
+//    U   U
+//     UUU
+//    ----------------------------------------------------------------------------------
+
+
+// Conversions between degrees and radians
+#define RAD2DEG 180.0/PI
+#define DEG2RAD PI/180.0
+
+// PI
+#define PI 3.141592653589
+
+
+
+
+// Types PPS firmware
+#define CF_COMMAND_TYPE_MOTORS 6
+#define CF_COMMAND_TYPE_RATE   7
+#define CF_COMMAND_TYPE_ANGLE  8
+
+// Types of controllers being used:
+#define SAFE_CONTROLLER      1
+#define DEMO_CONTROLLER      2
+#define STUDENT_CONTROLLER   3
+#define MPC_CONTROLLER       4
+#define REMOTE_CONTROLLER    5
+#define TUNING_CONTROLLER    6
+#define PICKER_CONTROLLER    7
+
+// The constants that "command" changes in the
+// operation state of this agent
+#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEMO_CONTROLLER      2
+#define CMD_USE_STUDENT_CONTROLLER   3
+#define CMD_USE_MPC_CONTROLLER       4
+#define CMD_USE_REMOTE_CONTROLLER    5
+#define CMD_USE_TUNING_CONTROLLER    6
+#define CMD_USE_PICKER_CONTROLLER    7
+
+
+#define CMD_CRAZYFLY_TAKE_OFF        11
+#define CMD_CRAZYFLY_LAND            12
+#define CMD_CRAZYFLY_MOTORS_OFF      13
+
+// Flying states
+#define STATE_MOTORS_OFF 1
+#define STATE_TAKE_OFF   2
+#define STATE_FLYING     3
+#define STATE_LAND       4
+
+
+// Commands for CrazyRadio
+#define CMD_RECONNECT  0
+#define CMD_DISCONNECT 1
+
+
+// CrazyRadio states:
+#define CRAZY_RADIO_STATE_CONNECTED      0
+#define CRAZY_RADIO_STATE_CONNECTING     1
+#define CRAZY_RADIO_STATE_DISCONNECTED   2
+
 
 
 
@@ -74,6 +139,37 @@
 // For where to load the yaml file from
 #define LOAD_YAML_FROM_AGENT             1
 #define LOAD_YAML_FROM_COORDINATOR       2
+
+
+
+
+
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
index 9441c08c..7d9f8254 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
@@ -77,9 +77,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
index f9baaca8..2ab71e04 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -46,20 +46,29 @@
 #include <std_msgs/String.h>
 #include <ros/package.h>
 
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/CMQuery.h"
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
 
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/ViconData.h"
 #include "d_fall_pps/CrazyflieData.h"
 #include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/Setpoint.h"
-#include "std_msgs/Int32.h"
-#include "std_msgs/Float32.h"
+
+// Include the DFALL service types
+#include "d_fall_pps/Controller.h"
+#include "d_fall_pps/CMQuery.h"
 
 // Include the Parameter Service shared definitions
 #include "nodes/Constants.h"
 
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
 // Need for having a ROS "bag" to store data for post-analysis
 //#include <rosbag/bag.h>
 
@@ -77,58 +86,7 @@
 //    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// Types PPS firmware
-#define CF_COMMAND_TYPE_MOTORS 6
-#define CF_COMMAND_TYPE_RATE   7
-#define CF_COMMAND_TYPE_ANGLE  8
-
-// Types of controllers being used:
-#define SAFE_CONTROLLER      1
-#define DEMO_CONTROLLER      2
-#define STUDENT_CONTROLLER   3
-#define MPC_CONTROLLER       4
-#define REMOTE_CONTROLLER    5
-#define TUNING_CONTROLLER    6
-#define PICKER_CONTROLLER    7
-
-// The constants that "command" changes in the
-// operation state of this agent
-#define CMD_USE_SAFE_CONTROLLER      1
-#define CMD_USE_DEMO_CONTROLLER      2
-#define CMD_USE_STUDENT_CONTROLLER   3
-#define CMD_USE_MPC_CONTROLLER       4
-#define CMD_USE_REMOTE_CONTROLLER    5
-#define CMD_USE_TUNING_CONTROLLER    6
-#define CMD_USE_PICKER_CONTROLLER    7
-
-
-#define CMD_CRAZYFLY_TAKE_OFF        11
-#define CMD_CRAZYFLY_LAND            12
-#define CMD_CRAZYFLY_MOTORS_OFF      13
 
-// Flying states
-#define STATE_MOTORS_OFF 1
-#define STATE_TAKE_OFF   2
-#define STATE_FLYING     3
-#define STATE_LAND       4
-
-// Battery states
-#define BATTERY_STATE_NORMAL 0
-#define BATTERY_STATE_LOW    1
-
-// Commands for CrazyRadio
-#define CMD_RECONNECT  0
-#define CMD_DISCONNECT 1
-
-
-// CrazyRadio states:
-#define CONNECTED        0
-#define CONNECTING       1
-#define DISCONNECTED     2
-
-
-// Universal constants
-#define PI 3.141592653589
 
 // Namespacing the package
 using namespace d_fall_pps;
@@ -145,8 +103,18 @@ using namespace d_fall_pps;
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// "agentID", gives namespace and identifier in CentralManagerService
-int agentID;
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// The ID of the agent that can coordinate this node
+int m_coordID;
+
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
 
 // The safe controller specified in the ClientConfig.yaml
 ros::ServiceClient safeController;
@@ -165,27 +133,36 @@ ros::ServiceClient pickerController;
 
 
 //values for safteyCheck
-bool strictSafety;
-float angleMargin;
+bool yaml_strictSafety;
+float yaml_angleMargin;
+
+
+
 
 // battery threshold
-float m_battery_threshold_while_flying;
-float m_battery_threshold_while_motors_off;
+//float m_battery_threshold_while_flying;
+//float m_battery_threshold_while_motors_off;
 
 
 // battery values
 
-int m_battery_state;
-float m_battery_voltage;
+//int m_battery_state;
+//float m_battery_voltage;
+
+
+
+
 
 Setpoint controller_setpoint;
 
+std::vector<float> yaml_default_setpoint = {0.0f, 0.0f, 0.0f, 0.0f};
+
 // variables for linear trayectory
 Setpoint current_safe_setpoint;
 double distance;
 double unit_vector[3];
 bool was_in_threshold = false;
-double distance_threshold;      //to be loaded from yaml
+double yaml_distance_threshold;      //to be loaded from yaml
 
 
 ros::ServiceClient centralManager;
@@ -232,12 +209,12 @@ int controller_used;
 
 ros::Publisher controllerUsedPublisher;
 
-std::string ros_namespace;
 
-float take_off_distance;
-float landing_distance;
-float duration_take_off;
-float duration_landing;
+
+float yaml_take_off_distance;
+float yaml_landing_distance;
+float yaml_duration_take_off;
+float yaml_duration_landing;
 
 bool finished_take_off = false;
 bool finished_land = false;
@@ -271,7 +248,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
 void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle);
 void fetchClientConfigParameters(ros::NodeHandle& nodeHandle);
 
-void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
+
 
 
 
@@ -279,26 +256,25 @@ void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
 
 void viconCallback(const ViconData& viconData);
 
-// > For the LOADING of YAML PARAMETERS
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle);
-void fetchClientConfigParameters(ros::NodeHandle& nodeHandle);
+
 
 
 
 // > For the {dis/re}-connect command received from the coordinator
+//void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
 void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
 
 
-// > For the BATTERY
-int getBatteryState();
-void setBatteryStateTo(int new_battery_state);
-float movingAverageBatteryFilter(float new_input);
-void CFBatteryCallback(const std_msgs::Float32& msg);
+
+
+void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
 
 
 
 
+void commandCallback(const IntWithHeader & commandMsg);
+
+
 
 
 void loadSafeController();
@@ -316,6 +292,22 @@ void setControllerUsed(int controller);
 int getControllerUsed();
 
 
+// > For the BATTERY
+//int getBatteryState();
+//void setBatteryStateTo(int new_battery_state);
+//float movingAverageBatteryFilter(float new_input);
+//void CFBatteryCallback(const std_msgs::Float32& msg);
+void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
+
+
+// > For the LOADING of YAML PARAMETERS
+void isReadySafeControllerYamlCallback(const IntWithHeader & msg);
+void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle);
+
+void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
+void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
+
+
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
index 66507144..011ff0c7 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
@@ -71,9 +71,9 @@
 //    ----------------------------------------------------------------------------------
 
 // The types, i.e., agent or coordinator
-#define TYPE_INVALID      -1
-#define TYPE_COORDINATOR   1
-#define TYPE_AGENT         2
+//#define TYPE_INVALID      -1
+//#define TYPE_COORDINATOR   1
+//#define TYPE_AGENT         2
 
 
 // Namespacing the package
@@ -95,8 +95,7 @@ using namespace d_fall_pps;
 // "*.launch" file
 int m_type = 0;
 
-// The ID of this agent, i.e., the ID of this computer in the case that this computer is
-// and agent
+// The ID of this node
 int m_ID = 0;
 
 // The namespace into which this parameter service loads yaml parameters
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index 8b51e35e..69647983 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -79,14 +79,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
-#define RAD2DEG 180.0/PI
-#define DEG2RAD PI/180.0
-
-
-
 // FOR WHICH BUTTON WAS PRESSED IN THE PICKER CONTOLLER
 #define PICKER_BUTTON_GOTOSTART     1
 #define PICKER_BUTTON_ATTACH        2
diff --git a/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
index 33d91be9..8e9f783c 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
@@ -82,9 +82,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
index 684b8134..6ead6b7f 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
@@ -73,9 +73,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // The constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 478c94ff..20368011 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -77,9 +77,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
index 1b950747..8701bc89 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
@@ -82,9 +82,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index f4d2d83d..868bb531 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -119,7 +119,7 @@
 			type   = "ParameterService"
 			>
 			<param name="type"     type="str"  value="agent" />
-			<param name="agentID"  type="str"  value="$(arg agentID)" />
+			<param name="agentID"  value="$(arg agentID)" />
 			<rosparam
 				command = "load"
 				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
@@ -167,9 +167,12 @@
 		<group if="$(arg withGUI)">
 			<node
 				pkg    = "d_fall_pps"
-				name   = "student_GUI"
+				name   = "flyingAgentGUI"
 				output = "screen"
-				type   = "student_GUI">
+				type   = "flyingAgentGUI"
+				>
+				<param name="type"     type="str"  value="agent" />
+				<param name="agentID"  value="$(arg agentID)" />
 			</node>
 		</group>
 		
diff --git a/pps_ws/src/d_fall_pps/launch/Config.sh b/pps_ws/src/d_fall_pps/launch/Config.sh
index 3a8fb387..26f36eae 100755
--- a/pps_ws/src/d_fall_pps/launch/Config.sh
+++ b/pps_ws/src/d_fall_pps/launch/Config.sh
@@ -1,7 +1,7 @@
 # TO RUN THE SYSTEM FULLY ON THE LOCAL COMPUTER:
-# export ROS_MASTER_URI=http://localhost:11311
+export ROS_MASTER_URI=http://localhost:11311
 # TO RUN THE SYSTEM ON A DEFAULT CONFIGURATION OF THE NETWROK:
-export ROS_MASTER_URI=http://teacher:11311
+# export ROS_MASTER_URI=http://teacher:11311
 # OTHER NECESSARY ENVIRONMENT VARIABLES:
 export ROS_IP=$(hostname -I | awk '{print $1;}')
 export DFALL_DEFAULT_AGENT_ID=$(cat /etc/dfall_default_agent_id)
diff --git a/pps_ws/src/d_fall_pps/launch/Coordinator.launch b/pps_ws/src/d_fall_pps/launch/Coordinator.launch
index 59b08530..290bd237 100755
--- a/pps_ws/src/d_fall_pps/launch/Coordinator.launch
+++ b/pps_ws/src/d_fall_pps/launch/Coordinator.launch
@@ -39,44 +39,14 @@
 			<param name="coordID"  value="$(arg coordID)" />
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/YamlFileNames.yaml"
+				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
 				ns      = "YamlFileNames"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/SafeController.yaml"
+				file    = "$(find d_fall_pps)/param/ClientConfig.yaml"
 				ns      = "SafeController"
 			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/DemoController.yaml"
-				ns      = "DemoController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/StudentController.yaml"
-				ns      = "StudentController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/MpcController.yaml"
-				ns      = "MpcController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/RemoteController.yaml"
-				ns      = "RemoteController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/TuningController.yaml"
-				ns      = "TuningController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/PickerController.yaml"
-				ns      = "PickerController"
-			/>
 		</node>
 
 	</group>
diff --git a/pps_ws/src/d_fall_pps/param/ClientConfig.yaml b/pps_ws/src/d_fall_pps/param/ClientConfig.yaml
index 8b15a220..d348c138 100755
--- a/pps_ws/src/d_fall_pps/param/ClientConfig.yaml
+++ b/pps_ws/src/d_fall_pps/param/ClientConfig.yaml
@@ -6,6 +6,7 @@ remoteController:  "RemoteControllerService/RemoteController"
 tuningController:  "TuningControllerService/TuningController"
 pickerController:  "PickerControllerService/PickerController"
 
+# Flag for whether to use angle for switching to the Safe Controller
 strictSafety: false
 angleMargin: 0.8
 
diff --git a/pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp b/pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
new file mode 100644
index 00000000..d8d7af9c
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
@@ -0,0 +1,234 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    A class for having the standard functions in one place
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// INCLUDE THE HEADER
+#include "classes/GetParamtersAndNamespaces.h"
+
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    III M   M PPPP  L     EEEEE M   M EEEEE N   N TTTTT   A   TTTTT III  OOO  N   N
+//     I  MM MM P   P L     E     MM MM E     NN  N   T    A A    T    I  O   O NN  N
+//     I  M M M PPPP  L     EEE   M M M EEE   N N N   T   A   A   T    I  O   O N N N
+//     I  M   M P     L     E     M   M E     N  NN   T   AAAAA   T    I  O   O N  NN
+//    III M   M P     LLLLL EEEEE M   M EEEEE N   N   T   A   A   T   III  OOO  N   N
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
+//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
+//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
+//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
+//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
+//    ----------------------------------------------------------------------------------
+
+
+
+float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
+{
+    float val;
+    if(!nodeHandle.getParam(name, val))
+    {
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val;
+}
+
+
+
+int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
+{
+    int val;
+    if(!nodeHandle.getParam(name, val))
+    {
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val;
+}
+
+
+
+bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
+{
+    bool val;
+    if(!nodeHandle.getParam(name, val))
+    {
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val;
+}
+
+
+
+void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
+{
+    if(!nodeHandle.getParam(name, val)){
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    if(val.size() != length) {
+        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
+    }
+}
+
+
+
+void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
+{
+    if(!nodeHandle.getParam(name, val)){
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    if(val.size() != length) {
+        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
+    }
+}
+
+
+
+int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
+{
+    if(!nodeHandle.getParam(name, val)){
+        ROS_ERROR_STREAM("missing parameter '" << name << "'");
+    }
+    return val.size();
+}
+
+
+
+
+bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref)
+{
+	// Initialise the return variable as success
+	bool return_was_successful = true;
+
+	// Create a node handle to the client
+	ros::NodeHandle client_nodeHandle(client_namespace);
+
+	// Get the value of the "agentID" parameter
+	int agentID_fetched;
+	if(!client_nodeHandle.getParam("agentID", agentID_fetched))
+	{
+		return_was_successful = false;
+	}
+	else
+	{
+		*agentID_ref = agentID_fetched;
+	}
+
+	// Get the value of the "coordID" parameter
+	int coordID_fetched;
+	if(!client_nodeHandle.getParam("coordID", coordID_fetched))
+	{
+		return_was_successful = false;
+	}
+	else
+	{
+		*coordID_ref = coordID_fetched;
+	}
+
+	// Return
+	return return_was_successful;
+}
+
+
+
+
+
+void constructNamespaceForCoordinator( int coordID, std::string & coord_namespace )
+{
+	// Convert the ID to a zero padded string
+	std::ostringstream str_stream;
+	str_stream << std::setw(3) << std::setfill('0') << coordID;
+	std::string coordID_as_string(str_stream.str());
+	// Construct the namespace
+	coord_namespace = "/dfall/coord" + coordID_as_string;
+}
+
+
+void constructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace )
+{
+	// Convert the ID to a zero padded string
+	std::ostringstream str_stream;
+	str_stream << std::setw(3) << std::setfill('0') << coordID;
+	std::string coordID_as_string(str_stream.str());
+	// Construct the namespace
+	coord_param_service_namespace = "/dfall/coord" + coordID_as_string + "/ParameterService";
+}
+
+
+
+
+
+// Check the header of a message for whether it is relevant
+bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs )
+{
+	// The messag is by default relevant if the "shouldCheckForID"
+	// flag is false
+	if (!shouldCheckForID)
+	{
+		return true;
+	}
+	else
+	{
+		// Iterate through the vector of IDs
+		for ( int i_ID=0 ; i_ID < agentIDs.size() ; i_ID++ )
+		{
+			if ( agentIDs[i_ID] == agentID )
+			{
+				return true;
+			}
+		}
+	}
+	// If the function made it to here, then the message is
+	// NOT relevant, hence return false
+	return false;
+}
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
index 15deb2f6..fbcf4cee 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -128,7 +128,32 @@ void newBatteryVoltageCallback(const std_msgs::Float32& msg)
 // > For filtering the battery voltage
 float newBatteryVoltageForFilter(float new_value)
 {
-	return 0.0f;
+	return movingAverageBatteryFilter( new_value);
+}
+
+float movingAverageBatteryFilter(float new_input)
+{
+    const int N = 7;
+    static float previous_output = 4.2f;
+    static float inputs[N] = {4.2f,4.2f,4.2f,4.2f,4.2f,4.2f,4.2f};
+
+
+    // imagine an array of an even number of samples, we will output the one
+    // in the middle averaged with information from all of them.
+    // For that, we only need to store some past of the signal
+    float output = previous_output + new_input/N - inputs[N-1]/N;
+
+    // update array of inputs
+    for(int i = N - 1; i > 0; i--)
+    {
+        inputs[i] = inputs[i-1];
+    }
+    inputs[0] = new_input;
+
+
+    // update previous output
+    previous_output = output;
+    return output;
 }
 
 
@@ -281,94 +306,62 @@ void updateBatteryStateBasedOnLevel(int level)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const IntWithHeader & msg)
+
+void isReadyBatteryMonitorYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
 	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
 	// Continue if the message is relevant
-	if  (isRevelant)
+	if (isRevelant)
 	{
 		// Extract the data
 		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
 		// Load from the respective parameter service
-		// Switch between fetching for the different controllers and from different locations
 		switch(parameter_service_to_load_from)
 		{
-
 			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
 			case LOAD_YAML_FROM_AGENT:
 			{
-				// Let the user know that this message was received
-				ROS_INFO("[BATTERY MONITOR] Now fetching the YAML parameter values from this agent.");
-				// Create a node handle to the parameter service of this agent
-				ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-				// Call the function that fetches the parameters
-				fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+				ROS_INFO("[BATTERY MONITOR] Now fetching the BatteryMonitor 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:
 			{
-				// Let the user know that this message was received
-				ROS_INFO("[BATTERY MONITOR] Now fetching the YAML parameter values from this agent's coordinator.");
-				// Create a node handle to the parameter service of this agent's coordinator
-				ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
-				// Call the function that fetches the parameters
-				fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+				ROS_INFO("[BATTERY MONITOR] Now fetching the BatteryMonitor YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
 				break;
 			}
 
 			default:
 			{
-				// Let the user know that the command was not relevant
-				//ROS_INFO("The StudentControllerService received the message that YAML parameters were (re-)loaded");
-				//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
+				ROS_ERROR("[BATTERY MONITOR] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
 				break;
 			}
 		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchBatteryMonitorYamlParameters(nodeHandle_to_use);
 	}
 }
 
 
 
-// Check the header of a message for whether it is relevant
-bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs )
-{
-	// The messag is by default relevant if the "shouldCheckForID"
-	// flag is false
-	if (!shouldCheckForID)
-	{
-		return true;
-	}
-	else
-	{
-		// Iterate through the vector of IDs
-		for ( int i_ID=0 ; i_ID < agentIDs.size() ; i_ID++ )
-		{
-			if ( agentIDs[i_ID] == agentID )
-			{
-				return true;
-			}
-		}
-	}
-	// If the function made it to here, then the message is
-	// NOT relevant, hence return false
-	return false;
-}
 
 
 
-// This function CAN BE edited for successful completion of the PPS 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)
+void fetchBatteryMonitorYamlParameters(ros::NodeHandle& nodeHandle)
 {
-	// Here we load the parameters that are specified in the StudentController.yaml file
+	// Here we load the parameters that are specified in the file:
+	// BatteryMonitor.yaml
 
-	// Add the "StudentController" namespace to the "nodeHandle"
+	// Add the "BatteryMonitor" namespace to the "nodeHandle"
 	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "BatteryMonitor");
 
 
@@ -391,114 +384,11 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
-	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUGGING: the fetched BatteryMonitor/battery_polling_period = " << yaml_battery_voltage_threshold_lower_while_flying);
-
-	// Call the function that computes details an values that are needed from these
-	// parameters loaded above
-	processFetchedParameters();
-}
-
+	ROS_INFO_STREAM("[BATTERY MONITOR] DEBUGGING: the fetched BatteryMonitor/battery_voltage_threshold_lower_while_flying = " << yaml_battery_voltage_threshold_lower_while_flying);
 
 
 
-
-// This function CAN BE edited for successful completion of the PPS 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()
-{
-    // Compute the feed-forward force that we need to counteract gravity (i.e., mg)
-    // > in units of [Newtons]
-    //cf_weight_in_newtons = cf_mass_in_grams * 9.81/1000.0;
-    
-    // DEBUGGING: Print out one of the computed quantities
-	//ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << cf_weight_in_newtons);
-}
-
-
-
-
-
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
-//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
-//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
-//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
-//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
-//    ----------------------------------------------------------------------------------
-
-
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-int getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-
-
-
-
-bool getAgentIDandCoordIDfromClientNode( std::string client_namespace , int * agentID_ref , int * coordID_ref)
-{
-	// Initialise the return variable as success
-	bool return_was_successful = true;
-
-	// Create a node handle to the client
-	ros::NodeHandle client_nodeHandle(client_namespace);
-
-	// Get the value of the "agentID" parameter
-	int agentID_fetched;
-	if(!client_nodeHandle.getParam("agentID", agentID_fetched))
-	{
-		return_was_successful = false;
-	}
-	else
-	{
-		*agentID_ref = agentID_fetched;
-	}
-
-	// Get the value of the "coordID" parameter
-	int coordID_fetched;
-	if(!client_nodeHandle.getParam("coordID", coordID_fetched))
-	{
-		return_was_successful = false;
-	}
-	else
-	{
-		*coordID_ref = coordID_fetched;
-	}
-
-	// Return
-	return return_was_successful;
-}
-
-
-
-void getConstructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace )
-{
-	// Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-	// for the parameter service that is running on the coordinate machine
-	// NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-	//       is very important because it specifies that the name is global
-	// Convert the agent ID to a zero padded string
-	std::ostringstream str_stream;
-	str_stream << std::setw(3) << std::setfill('0') << coordID;
-	std::string coordID_as_string(str_stream.str());
-	coord_param_service_namespace = "/dfall/coord" + coordID_as_string + "/ParameterService";
+	// PROCESS ANY OF THE FETCHED PARAMETERS AS NECESSARY
 }
 
 
@@ -533,7 +423,7 @@ int main(int argc, char* argv[])
 	// Stall the node IDs are not valid
 	if ( !isValid_IDs )
 	{
-		ROS_ERROR("[BATTERY SERVICE] Node NOT FUNCTIONING :-)");
+		ROS_ERROR("[BATTERY MONITOR] Node NOT FUNCTIONING :-)");
 		ros::spin();
 	}
 	else
@@ -551,10 +441,9 @@ int main(int argc, char* argv[])
 
 	// Set the class variable "m_namespace_to_coordinator_parameter_service",
 	// i.e., the namespace of parameter service for this agent's coordinator
-	getConstructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
 	// Inform the user of what namespaces are being used
-	ROS_INFO_STREAM("[BATTERY MONITOR] The namespace string for accessing the Paramter Services are:");
 	ROS_INFO_STREAM("[BATTERY MONITOR] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
 	ROS_INFO_STREAM("[BATTERY MONITOR] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
 
@@ -568,14 +457,14 @@ int main(int argc, char* argv[])
 
 	// The parameters service publish 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, yamlReadyForFetchCallback);
-	ros::Subscriber batteryMonitor_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("BatteryMonitor", 1, yamlReadyForFetchCallback);
+	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);
 
 
 	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
 	// Call the class function that loads the parameters for this class.
-	fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+	fetchBatteryMonitorYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
 
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
index 0034c54e..375766ad 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
@@ -157,6 +157,9 @@ bool cmCommand(CMCommand::Request &request, CMCommand::Response &response)
         case CMD_SAVE:
         {
             writeCrazyflieDB(crazyflieDB);
+            std_msgs::Int32 msg;
+            msg.data = 1;
+            m_databaseChangedPublisher.publish(msg);
             return true;
         }
 
@@ -164,6 +167,9 @@ bool cmCommand(CMCommand::Request &request, CMCommand::Response &response)
         {
             crazyflieDB.crazyflieEntries.clear();
             readCrazyflieDB(crazyflieDB);
+            std_msgs::Int32 msg;
+            msg.data = 1;
+            m_databaseChangedPublisher.publish(msg);
             return true;
         }
 
@@ -195,14 +201,8 @@ int main(int argc, char* argv[])
     ros::ServiceServer updateService = nodeHandle.advertiseService("Update", cmUpdate);
     ros::ServiceServer commandService = nodeHandle.advertiseService("Command", cmCommand);
 
-    // Get the handle to the namespace in which this coordinator is launched
-    //ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
-
-    // Subscriber for requests that the controller parameters should be re-loaded from
-    // the .YAML files on the coordinators machine, and then all the agents should be
-    // request to fetch the parameters from itself, i.e., fetch parameters from the
-    // coordinator.
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber = namespaceNodeHandle.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, controllerYamlReadyForFetchCallback);
+    // Publisher for when the database is saved
+    m_databaseChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("DBChanged", 1);
 
 
     ROS_INFO("CentralManagerService ready");
diff --git a/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
index 031d7bdd..eb5b88ce 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
@@ -76,9 +76,6 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// Universal constants
-#define PI 3.1415926535
-
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
 // the constants defined here need to be in agreement with those defined in the
 // firmware running on the Crazyflie 2.0.
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 2d656f30..0754860e 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -80,12 +80,12 @@ bool safetyCheck(CrazyflieData data, ControlCommand controlCommand) {
 	//attitude check
 	//if strictSafety is set to true in ClientConfig.yaml the SafeController takes also over if the roll and pitch angles get to large
 	//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(strictSafety){
-		if((data.roll > PI/2*angleMargin) or (data.roll < -PI/2*angleMargin)) {
+	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.");
 			return false;
 		}
-		if((data.pitch > PI/2*angleMargin) or (data.pitch < -PI/2*angleMargin)) {
+		if((data.pitch > PI/2*yaml_angleMargin) or (data.pitch < -PI/2*yaml_angleMargin)) {
 			ROS_INFO_STREAM("[PPS CLIENT] pitch too big.");
 			return false;
 		}
@@ -133,7 +133,7 @@ void takeOffCF(CrazyflieData& current_local_coordinates) //local because the set
     Setpoint setpoint_msg;
     setpoint_msg.x = current_local_coordinates.x;           // previous one
     setpoint_msg.y = current_local_coordinates.y;           //previous one
-    setpoint_msg.z = current_local_coordinates.z + take_off_distance;           //previous one plus some offset
+    setpoint_msg.z = current_local_coordinates.z + yaml_take_off_distance;           //previous one plus some offset
     // setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
     setpoint_msg.yaw = 0.0;
     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
@@ -158,7 +158,7 @@ void landCF(CrazyflieData& current_local_coordinates)
     Setpoint setpoint_msg;
     setpoint_msg.x = current_local_coordinates.x;           // previous one
     setpoint_msg.y = current_local_coordinates.y;           //previous one
-    setpoint_msg.z = landing_distance;           //previous one plus some offset
+    setpoint_msg.z = yaml_landing_distance;           //previous one plus some offset
     setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
 
@@ -170,7 +170,7 @@ void landCF(CrazyflieData& current_local_coordinates)
 
 void changeFlyingStateTo(int new_state)
 {
-    if(crazyradio_status == CONNECTED)
+    if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
     {
         ROS_INFO("[PPS CLIENT] Change state to: %d", new_state);
         flying_state = new_state;
@@ -236,7 +236,7 @@ void viconCallback(const ViconData& viconData)
                         takeOffCF(local);
                         finished_take_off = false;
                         ROS_INFO("[PPS CLIENT] STATE_TAKE_OFF");
-                        timer_takeoff = nodeHandle.createTimer(ros::Duration(duration_take_off), takeOffTimerCallback, true);
+                        timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_take_off), takeOffTimerCallback, true);
                     }
                     if(finished_take_off)
                     {
@@ -261,7 +261,7 @@ void viconCallback(const ViconData& viconData)
                         landCF(local);
                         finished_land = false;
                         ROS_INFO("[PPS CLIENT] STATE_LAND");
-                        timer_takeoff = nodeHandle.createTimer(ros::Duration(duration_landing), landTimerCallback, true);
+                        timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_landing), landTimerCallback, true);
                     }
                     if(finished_land)
                     {
@@ -334,16 +334,16 @@ void viconCallback(const ViconData& viconData)
                         calculateDistanceToCurrentSafeSetpoint(local); // update distance, it also updates the unit vector
                         // ROS_INFO_STREAM("distance: " << distance);
                         // here, detect if euclidean distance between setpoint and current position is higher than a threshold
-                        if(distance > distance_threshold)
+                        if(distance > yaml_distance_threshold)
                         {
                             // DEBUGGING: display a message that the crazyflie is inside the thresholds
                             //ROS_INFO("inside threshold");
                             // Declare a local variable for the "setpoint message" to be published
                             Setpoint setpoint_msg;
                             // here, where we are now, or where we were in the beginning?
-                            setpoint_msg.x = local.x + distance_threshold * unit_vector[0];
-                            setpoint_msg.y = local.y + distance_threshold * unit_vector[1];
-                            setpoint_msg.z = local.z + distance_threshold * unit_vector[2];
+                            setpoint_msg.x = local.x + yaml_distance_threshold * unit_vector[0];
+                            setpoint_msg.y = local.y + yaml_distance_threshold * unit_vector[1];
+                            setpoint_msg.z = local.z + yaml_distance_threshold * unit_vector[2];
 
                             // yaw is better divided by the number of steps?
                             setpoint_msg.yaw = current_safe_setpoint.yaw;
@@ -393,8 +393,8 @@ void viconCallback(const ViconData& viconData)
 
 void loadCrazyflieContext() {
 	CMQuery contextCall;
-	contextCall.request.studentID = agentID;
-	ROS_INFO_STREAM("[PPS CLIENT] AgentID:" << agentID);
+	contextCall.request.studentID = m_agentID;
+	ROS_INFO_STREAM("[PPS CLIENT] AgentID:" << m_agentID);
 
     CrazyflieContext new_context;
 
@@ -434,91 +434,100 @@ void loadCrazyflieContext() {
 
 
 
-void commandCallback(const std_msgs::Int32& commandMsg) {
-	int cmd = commandMsg.data;
+void commandCallback(const IntWithHeader & msg) {
 
-	switch(cmd) {
-    	case CMD_USE_SAFE_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_SAFE_CONTROLLER Command received");
-            setControllerUsed(SAFE_CONTROLLER);
-    		break;
+    // Check whether the message is relevant
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-    	case CMD_USE_DEMO_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_DEMO_CONTROLLER Command received");
-            setControllerUsed(DEMO_CONTROLLER);
-    		break;
-
-        case CMD_USE_STUDENT_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_STUDENT_CONTROLLER Command received");
-            setControllerUsed(STUDENT_CONTROLLER);
-            break;
-
-        case CMD_USE_MPC_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_MPC_CONTROLLER Command received");
-            setControllerUsed(MPC_CONTROLLER);
-            break;
-
-        case CMD_USE_REMOTE_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_REMOTE_CONTROLLER Command received");
-            setControllerUsed(REMOTE_CONTROLLER);
-            break;
-
-        case CMD_USE_TUNING_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_TUNING_CONTROLLER Command received");
-            setControllerUsed(TUNING_CONTROLLER);
-            break;
-
-        case CMD_USE_PICKER_CONTROLLER:
-            ROS_INFO("[PPS CLIENT] USE_PICKER_CONTROLLER Command received");
-            setControllerUsed(PICKER_CONTROLLER);
-            break;
-
-    	case CMD_CRAZYFLY_TAKE_OFF:
-            if(flying_state == STATE_MOTORS_OFF)
-            {
-                changeFlyingStateTo(STATE_TAKE_OFF);
-            }
-    		break;
-
-    	case CMD_CRAZYFLY_LAND:
-            if(flying_state != STATE_MOTORS_OFF)
-            {
-                changeFlyingStateTo(STATE_LAND);
-            }
-    		break;
-        case CMD_CRAZYFLY_MOTORS_OFF:
-            changeFlyingStateTo(STATE_MOTORS_OFF);
-            break;
+    // Continue if the message is relevant
+    if (isRevelant)
+    {
+        // Extract the data
+    	int cmd = msg.data;
+
+    	switch(cmd) {
+        	case CMD_USE_SAFE_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_SAFE_CONTROLLER Command received");
+                setControllerUsed(SAFE_CONTROLLER);
+        		break;
+
+        	case CMD_USE_DEMO_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_DEMO_CONTROLLER Command received");
+                setControllerUsed(DEMO_CONTROLLER);
+        		break;
+
+            case CMD_USE_STUDENT_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_STUDENT_CONTROLLER Command received");
+                setControllerUsed(STUDENT_CONTROLLER);
+                break;
+
+            case CMD_USE_MPC_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_MPC_CONTROLLER Command received");
+                setControllerUsed(MPC_CONTROLLER);
+                break;
+
+            case CMD_USE_REMOTE_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_REMOTE_CONTROLLER Command received");
+                setControllerUsed(REMOTE_CONTROLLER);
+                break;
+
+            case CMD_USE_TUNING_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_TUNING_CONTROLLER Command received");
+                setControllerUsed(TUNING_CONTROLLER);
+                break;
+
+            case CMD_USE_PICKER_CONTROLLER:
+                ROS_INFO("[PPS CLIENT] USE_PICKER_CONTROLLER Command received");
+                setControllerUsed(PICKER_CONTROLLER);
+                break;
+
+        	case CMD_CRAZYFLY_TAKE_OFF:
+                if(flying_state == STATE_MOTORS_OFF)
+                {
+                    changeFlyingStateTo(STATE_TAKE_OFF);
+                }
+        		break;
 
-    	default:
-    		ROS_ERROR_STREAM("[PPS CLIENT] unexpected command number: " << cmd);
-    		break;
-	}
+        	case CMD_CRAZYFLY_LAND:
+                if(flying_state != STATE_MOTORS_OFF)
+                {
+                    changeFlyingStateTo(STATE_LAND);
+                }
+        		break;
+            case CMD_CRAZYFLY_MOTORS_OFF:
+                changeFlyingStateTo(STATE_MOTORS_OFF);
+                break;
+
+        	default:
+        		ROS_ERROR_STREAM("[PPS CLIENT] unexpected command number: " << cmd);
+        		break;
+    	}
+    }
 }
 
-void DBChangedCallback(const std_msgs::Int32& msg)
+void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg)
 {
     loadCrazyflieContext();
 }
 
-void emergencyStopCallback(const std_msgs::Int32& msg)
+void emergencyStopCallback(const IntWithHeader & msg)
 {
     commandCallback(msg);
 }
 
-void commandAllAgentsCallback(const std_msgs::Int32& msg)
-{
-    commandCallback(msg);
-}
+//void commandAllAgentsCallback(const std_msgs::Int32& msg)
+//{
+//    commandCallback(msg);
+//}
 
 void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 {
     crazyradio_status = msg.data;
     // RESET THE BATTERY STATE IF DISCONNECTED
-    if (crazyradio_status == DISCONNECTED)
-    {
-        setBatteryStateTo(BATTERY_STATE_NORMAL);
-    }
+    //if (crazyradio_status == CRAZY_RADIO_STATE_DISCONNECTED)
+    //{
+    //    setBatteryStateTo(BATTERY_STATE_NORMAL);
+    //}
 }
 
 void controllerSetPointCallback(const Setpoint& newSetpoint)
@@ -540,125 +549,6 @@ void safeSetPointCallback(const Setpoint& newSetpoint)
 
 
 
-//    ----------------------------------------------------------------------------------
-//    L       OOO     A    DDDD
-//    L      O   O   A A   D   D
-//    L      O   O  A   A  D   D
-//    L      O   O  AAAAA  D   D
-//    LLLLL   OOO   A   A  DDDD
-//
-//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
-//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
-//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
-//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
-//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
-//    ----------------------------------------------------------------------------------
-
-
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
-{
-    // Extract from the "msg" for which controller the and from where to fetch the YAML
-    // parameters
-    int controller_to_fetch_yaml = msg.data;
-
-    // Switch between fetching for the different controllers and from different locations
-    switch(controller_to_fetch_yaml)
-    {
-        
-        // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-        case FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT:
-        {
-            // Let the user know that this message was received
-            ROS_INFO("[PPS CLIENT] Received the message that YAML parameters were (re-)loaded for the Safe Controller. > Now fetching the parameter values from this machine.");
-            // Create a node handle to the parameter service running on this agent's machine
-            ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-            // Call the function that fetches the parameters
-            fetchYamlParametersForSafeController(nodeHandle_to_own_agent_parameter_service);
-            break;
-        }
-
-        // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-        case FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR:
-        {
-            // Let the user know that this message was received
-            // > and also from where the paramters are being fetched
-            ROS_INFO("[PPS CLIENT] Received the message that YAML parameters were (re-)loaded for the Safe Controller. > Now fetching the parameter values from the coordinator.");
-            // Create a node handle to the parameter service running on the coordinator machine
-            ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-            // Call the function that fetches the parameters
-            fetchYamlParametersForSafeController(nodeHandle_to_coordinator_parameter_service);
-            break;
-        }
-
-        default:
-        {
-            // Let the user know that the command was not relevant
-            //ROS_INFO("The PPSClient received the message that YAML parameters were (re-)loaded.\r> However the parameters do not relate to this service, hence nothing will be fetched.");
-            break;
-        }
-    }
-}
-
-
-
-void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle)
-{
-    // Here we load the parameters that are specified in the SafeController.yaml file
-
-    // Add the "SafeController" namespace to the "nodeHandle"
-    ros::NodeHandle nodeHandle_for_safeController(nodeHandle, "SafeController");
-
-    if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
-    {
-        ROS_ERROR("[PPS CLIENT] Failed to get takeOffDistance");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
-    {
-        ROS_ERROR("[PPS 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");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
-    {
-        ROS_ERROR("[PPS CLIENT] Failed to get duration_landing");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
-    {
-        ROS_ERROR("[PPS CLIENT] Failed to get distance_threshold");
-    }
-}
-
-
-// > Load the paramters from the Client Config YAML file
-void fetchClientConfigParameters(ros::NodeHandle& nodeHandle)
-{
-    if(!nodeHandle.getParam("agentID", agentID)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get agentID");
-    }
-    if(!nodeHandle.getParam("strictSafety", strictSafety)) {
-        ROS_ERROR("[PPS CLIENT] Failed to get strictSafety param");
-        return;
-    }
-    if(!nodeHandle.getParam("angleMargin", angleMargin)) {
-        ROS_ERROR("[PPS 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");
-        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");
-        return;
-    }
-}
-
 
 
 
@@ -687,95 +577,6 @@ void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg)
 
 
 
-int getBatteryState()
-{
-    return m_battery_state;
-}
-
-
-void setBatteryStateTo(int new_battery_state)
-{
-    switch(new_battery_state)
-    {
-        case BATTERY_STATE_NORMAL:
-            m_battery_state = BATTERY_STATE_NORMAL;
-            ROS_INFO("[PPS 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");
-            if(flying_state != STATE_MOTORS_OFF)
-                changeFlyingStateTo(STATE_LAND);
-            break;
-        default:
-            ROS_INFO("[PPS CLIENT] Unknown battery state command, set to normal");
-            m_battery_state = BATTERY_STATE_NORMAL;
-            break;
-    }
-
-    std_msgs::Int32 battery_state_msg;
-    battery_state_msg.data = getBatteryState();
-    batteryStatePublisher.publish(battery_state_msg);
-}
-
-float movingAverageBatteryFilter(float new_input)
-{
-    const int N = 7;
-    static float previous_output = 4.2f;
-    static float inputs[N] = {4.2f,4.2f,4.2f,4.2f,4.2f,4.2f,4.2f};
-
-
-    // imagine an array of an even number of samples, we will output the one
-    // in the middle averaged with information from all of them.
-    // For that, we only need to store some past of the signal
-    float output = previous_output + new_input/N - inputs[N-1]/N;
-
-    // update array of inputs
-    for(int i = N - 1; i > 0; i--)
-    {
-        inputs[i] = inputs[i-1];
-    }
-    inputs[0] = new_input;
-
-
-    // update previous output
-    previous_output = output;
-    return output;
-}
-
-
-void CFBatteryCallback(const std_msgs::Float32& msg)
-{
-    m_battery_voltage = msg.data;
-    // filter and check if inside limits, and if, change status
-    // need to do the filtering first
-    float filtered_battery_voltage = movingAverageBatteryFilter(m_battery_voltage); //need to perform filtering here
-
-    // ROS_INFO_STREAM("filtered data: " << filtered_battery_voltage);
-    if(
-        (flying_state != STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_flying))
-        ||
-        (flying_state == STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_motors_off))
-    )
-    {
-        if(getBatteryState() != BATTERY_STATE_LOW)
-        {
-            setBatteryStateTo(BATTERY_STATE_LOW);
-            ROS_INFO("[PPS CLIENT] low level battery triggered");
-        }
-        
-    }
-    else
-    {
-        // TO AVOID BEING ABLE TO IMMEDIATELY TAKE-OFF AFTER A
-        // "BATTERY LOW" EVENT IS TRIGGERED, WE DO NOT SET THE
-        // BATTERY STATE BACK TO NORMAL
-        // if(getBatteryState() != BATTERY_STATE_NORMAL)
-        // {
-        //     setBatteryStateTo(BATTERY_STATE_NORMAL);
-        // }
-    }
-}
 
 
 
@@ -786,6 +587,13 @@ void CFBatteryCallback(const std_msgs::Float32& msg)
 
 
 
+//    ----------------------------------------------------------------------------------
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
+//    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
+//    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
+//    C      O   O  N  NN    T    R   R  O   O  L      L      E      R   R
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL  LLLLL  EEEEE  R   R
+//    ----------------------------------------------------------------------------------
 
 
 
@@ -959,110 +767,505 @@ int getControllerUsed()
 
 
 
-
-
-
 //    ----------------------------------------------------------------------------------
-//    M   M    A    III  N   N
-//    MM MM   A A    I   NN  N
-//    M M M  A   A   I   N N N
-//    M   M  AAAAA   I   N  NN
-//    M   M  A   A  III  N   N
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
 //    ----------------------------------------------------------------------------------
 
-int main(int argc, char* argv[])
-{
-	ros::init(argc, argv, "PPSClient");
-	ros::NodeHandle nodeHandle("~");
-    ros_namespace = ros::this_node::getNamespace();
-
-    // *********************************************************************************
-    // EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
-
-    // > Load the paramters from the Client Config YAML file
-    fetchClientConfigParameters(nodeHandle);
-
-    // Get the namespace of this "SafeControllerService" node
-    std::string m_namespace = ros::this_node::getNamespace();
-
-
-    // EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
-
-    // Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-    // namespace string for the parameter service that is running on the machine of this
-    // agent
-    namespace_to_own_agent_parameter_service = "ParameterService";
-    // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-
-
-    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
-
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-    //       is very important because it specifies that the name is global
-    namespace_to_coordinator_parameter_service = "/ParameterService";
-
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-
-
-    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
-
-    // Call the class function that loads the parameters for this class.
-    fetchYamlParametersForSafeController(nodeHandle_to_own_agent_parameter_service);
-
-    // *********************************************************************************
 
 
-    // Load default setpoint from the "SafeController" namespace of the "ParameterService"
-    std::vector<float> default_setpoint(4);
-    ros::NodeHandle nodeHandle_for_safeController(nodeHandle_to_own_agent_parameter_service, "SafeController");
+void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
+{
+    // Extract the data
+    int new_battery_state = msg.data;
 
-    if(!nodeHandle_for_safeController.getParam("defaultSetpoint", default_setpoint))
+    // Take action if changed to low battery state
+    if ((flying_state != STATE_MOTORS_OFF) && (new_battery_state == BATTERY_STATE_LOW))
+    {
+        ROS_INFO("[PPS CLIENT] low level battery triggered, now landing.");
+        changeFlyingStateTo(STATE_LAND);
+    }
+    else if ((flying_state == STATE_MOTORS_OFF) && (new_battery_state == BATTERY_STATE_LOW))
     {
-        ROS_ERROR_STREAM("[PPS CLIENT] Could not find parameter 'defaultSetpoint', as called from main(...)");
+        ROS_INFO("[PPS CLIENT] low level battery triggered, please turn off the Crazyflie.");
     }
+}
 
-    // Copy the default setpoint into the class variable
-    controller_setpoint.x = default_setpoint[0];
-    controller_setpoint.y = default_setpoint[1];
-    controller_setpoint.z = default_setpoint[2];
-    controller_setpoint.yaw = default_setpoint[3];
 
-	//ros::service::waitForService("/CentralManagerService/CentralManager");
-    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
-    ros::NodeHandle dfall_root_nodeHandle("/dfall");
-	centralManager = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
-	loadCrazyflieContext();
 
-	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
-	ros::Subscriber viconSubscriber = nodeHandle.subscribe("/ViconDataPublisher/ViconData", 100, viconCallback);
-	ROS_INFO_STREAM("[PPS CLIENT] successfully subscribed to ViconData");
+/*
+int getBatteryState()
+{
+    return m_battery_state;
+}
 
-	//ros::Publishers to advertise the control output
-	controlCommandPublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
+
+void setBatteryStateTo(int new_battery_state)
+{
+    switch(new_battery_state)
+    {
+        case BATTERY_STATE_NORMAL:
+            m_battery_state = BATTERY_STATE_NORMAL;
+            ROS_INFO("[PPS 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");
+            if(flying_state != STATE_MOTORS_OFF)
+                changeFlyingStateTo(STATE_LAND);
+            break;
+        default:
+            ROS_INFO("[PPS CLIENT] Unknown battery state command, set to normal");
+            m_battery_state = BATTERY_STATE_NORMAL;
+            break;
+    }
+
+    std_msgs::Int32 battery_state_msg;
+    battery_state_msg.data = getBatteryState();
+    batteryStatePublisher.publish(battery_state_msg);
+}
+
+float movingAverageBatteryFilter(float new_input)
+{
+    const int N = 7;
+    static float previous_output = 4.2f;
+    static float inputs[N] = {4.2f,4.2f,4.2f,4.2f,4.2f,4.2f,4.2f};
+
+
+    // imagine an array of an even number of samples, we will output the one
+    // in the middle averaged with information from all of them.
+    // For that, we only need to store some past of the signal
+    float output = previous_output + new_input/N - inputs[N-1]/N;
+
+    // update array of inputs
+    for(int i = N - 1; i > 0; i--)
+    {
+        inputs[i] = inputs[i-1];
+    }
+    inputs[0] = new_input;
+
+
+    // update previous output
+    previous_output = output;
+    return output;
+}
+
+
+void CFBatteryCallback(const std_msgs::Float32& msg)
+{
+    m_battery_voltage = msg.data;
+    // filter and check if inside limits, and if, change status
+    // need to do the filtering first
+    float filtered_battery_voltage = movingAverageBatteryFilter(m_battery_voltage); //need to perform filtering here
+
+    // ROS_INFO_STREAM("filtered data: " << filtered_battery_voltage);
+    if(
+        (flying_state != STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_flying))
+        ||
+        (flying_state == STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_motors_off))
+    )
+    {
+        if(getBatteryState() != BATTERY_STATE_LOW)
+        {
+            setBatteryStateTo(BATTERY_STATE_LOW);
+            ROS_INFO("[PPS CLIENT] low level battery triggered");
+        }
+        
+    }
+    else
+    {
+        // TO AVOID BEING ABLE TO IMMEDIATELY TAKE-OFF AFTER A
+        // "BATTERY LOW" EVENT IS TRIGGERED, WE DO NOT SET THE
+        // BATTERY STATE BACK TO NORMAL
+        // if(getBatteryState() != BATTERY_STATE_NORMAL)
+        // {
+        //     setBatteryStateTo(BATTERY_STATE_NORMAL);
+        // }
+    }
+}
+*/
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
+//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
+//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
+//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
+//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
+{
+    // Check whether the message is relevant
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+
+    // Continue if the message is relevant
+    if (isRevelant)
+    {
+        // Extract the data
+        int parameter_service_to_load_from = msg.data;
+        // Initialise a local variable for the namespace
+        std::string namespace_to_use;
+        // Load from the respective parameter service
+        switch(parameter_service_to_load_from)
+        {
+            // > 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.");
+                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.");
+                namespace_to_use = m_namespace_to_coordinator_parameter_service;
+                break;
+            }
+
+            default:
+            {
+                ROS_ERROR("[PPS CLIENT] Paramter service to load from was NOT recognised.");
+                namespace_to_use = m_namespace_to_own_agent_parameter_service;
+                break;
+            }
+        }
+        // Create a node handle to the selected parameter service
+        ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+        // Call the function that fetches the parameters
+        fetchSafeControllerYamlParameters(nodeHandle_to_use);
+    }
+}
+
+
+
+void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
+{
+    // Here we load the parameters that are specified in the file:
+    // SafeController.yaml
+
+    // Add the "SafeController" namespace to the "nodeHandle"
+    ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "SafeController");
+
+    // take off and landing parameters (in meters and seconds)
+    yaml_take_off_distance = getParameterFloat(nodeHandle_for_paramaters,"takeOffDistance");
+    yaml_landing_distance = getParameterFloat(nodeHandle_for_paramaters,"landingDistance");
+    yaml_duration_take_off = getParameterFloat(nodeHandle_for_paramaters,"durationTakeOff");
+    yaml_duration_landing = getParameterFloat(nodeHandle_for_paramaters,"durationLanding");
+    yaml_distance_threshold = getParameterFloat(nodeHandle_for_paramaters,"distanceThreshold");
+
+    // setpoint in meters (x, y, z, yaw)
+    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);
+
+    /*
+    // Here we load the parameters that are specified in the SafeController.yaml file
+
+    // Add the "SafeController" namespace to the "nodeHandle"
+    ros::NodeHandle nodeHandle_for_safeController(nodeHandle, "SafeController");
+
+    if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
+    {
+        ROS_ERROR("[PPS CLIENT] Failed to get takeOffDistance");
+    }
+
+    if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
+    {
+        ROS_ERROR("[PPS 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");
+    }
+
+    if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
+    {
+        ROS_ERROR("[PPS CLIENT] Failed to get duration_landing");
+    }
+
+    if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
+    {
+        ROS_ERROR("[PPS CLIENT] Failed to get distance_threshold");
+    }
+    */
+}
+
+
+
+
+void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
+{
+    // Check whether the message is relevant
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+
+    // Continue if the message is relevant
+    if (isRevelant)
+    {
+        // Extract the data
+        int parameter_service_to_load_from = msg.data;
+        // Initialise a local variable for the namespace
+        std::string namespace_to_use;
+        // Load from the respective parameter service
+        switch(parameter_service_to_load_from)
+        {
+            // > 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.");
+                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.");
+                namespace_to_use = m_namespace_to_coordinator_parameter_service;
+                break;
+            }
+
+            default:
+            {
+                ROS_ERROR("[PPS CLIENT] Paramter service to load from was NOT recognised.");
+                namespace_to_use = m_namespace_to_own_agent_parameter_service;
+                break;
+            }
+        }
+        // Create a node handle to the selected parameter service
+        ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+        // Call the function that fetches the parameters
+        fetchClientConfigYamlParameters(nodeHandle_to_use);
+    }
+}
+
+
+
+// > Load the paramters from the Client Config YAML file
+void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
+{
+    // Here we load the parameters that are specified in the file:
+    // ClientConfig.yaml
+
+    // Add the "ClientConfig" namespace to the "nodeHandle"
+    ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "ClientConfig");
+
+    // Flag for whether to use angle for switching to the Safe Controller
+    yaml_strictSafety = getParameterBool(nodeHandle_for_paramaters,"strictSafety");
+    yaml_angleMargin = getParameterFloat(nodeHandle_for_paramaters,"angleMargin");
+    
+
+
+    // DEBUGGING: Print out one of the parameters that was loaded
+    ROS_INFO_STREAM("[PPS CLIENT] DEBUGGING: the fetched ClientConfig/strictSafety = " << yaml_strictSafety);
+
+
+    /*
+    if(!nodeHandle.getParam("strictSafety", strictSafety)) {
+        ROS_ERROR("[PPS CLIENT] Failed to get strictSafety param");
+        return;
+    }
+    if(!nodeHandle.getParam("angleMargin", angleMargin)) {
+        ROS_ERROR("[PPS 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");
+        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");
+        return;
+    }
+    */
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M    A    III  N   N
+//    MM MM   A A    I   NN  N
+//    M M M  A   A   I   N N N
+//    M   M  AAAAA   I   N  NN
+//    M   M  A   A  III  N   N
+//    ----------------------------------------------------------------------------------
+
+int main(int argc, char* argv[])
+{
+    // Starting the ROS-node
+	ros::init(argc, argv, "PPSClient");
+
+    // Create a "ros::NodeHandle" type local variable named "nodeHandle",
+    // the "~" indcates that "self" is the node handle assigned.
+	ros::NodeHandle nodeHandle("~");
+
+    // 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);
+
+
+
+    // 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);
+
+    // Stall the node IDs are not valid
+    if ( !isValid_IDs )
+    {
+        ROS_ERROR("[PPS Client] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+    else
+    {
+        ROS_INFO_STREAM("[PPS Client] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+    }
+
+
+
+    // PARAMETER SERVICE NAMESPACE AND NODEHANDLES:
+
+    // 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";
+
+    // Set the class variable "m_namespace_to_coordinator_parameter_service",
+    // i.e., the namespace of parameter service for this agent's coordinator
+    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);
+
+    // 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);
+    ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+
+
+
+    // SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+    // The parameters service publish messages with names of the form:
+    // /dfall/.../ParameterService/<filename with .yaml extension>
+    ros::Subscriber clientConfig_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "ClientConfig", 1, isReadyClientConfigYamlCallback);
+    ros::Subscriber clientConfig_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("ClientConfig", 1, isReadyClientConfigYamlCallback);
+
+    ros::Subscriber safeController_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "SafeController", 1, isReadySafeControllerYamlCallback);
+    ros::Subscriber safeController_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("SafeController", 1, isReadySafeControllerYamlCallback);
+
+
+
+    // FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+    // Call the class function that loads the parameters for this class.
+    fetchClientConfigYamlParameters(nodeHandle_to_own_agent_parameter_service);
+    fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
+
+
+
+
+
+
+
+    // Copy the default setpoint into the class variable
+    controller_setpoint.x   = yaml_default_setpoint[0];
+    controller_setpoint.y   = yaml_default_setpoint[1];
+    controller_setpoint.z   = yaml_default_setpoint[2];
+    controller_setpoint.yaw = yaml_default_setpoint[3];
+
+
+
+
+
+
+	
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle nodeHandle_dfall_root("/dfall");
+
+
+
+
+
+    // SERVICE CLIENT FOR THE ALLOWED FLYING ZONE AND OTHER CONTEXT DETAILS
+
+    //ros::service::waitForService("/CentralManagerService/CentralManager");
+	centralManager = nodeHandle_dfall_root.serviceClient<CMQuery>("CentralManagerService/Query", false);
+	loadCrazyflieContext();
+
+    // Subscriber for when the Flying Zone Database changed
+    ros::Subscriber databaseChangedSubscriber = nodeHandle_dfall_root.subscribe("CentralManagerService/DBChanged", 1, crazyflieContextDatabaseChangedCallback);
+
+
+
+
+
+    // EMERGENCY STOP OF THE WHOLE "D-FaLL-System"
+    ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopCallback);
+
+
+
+
+
+    // LOCALISATION DATA FROM MOTION CAPTURE SYSTEM
+
+	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
+	ros::Subscriber viconSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, viconCallback);
+
+
+
+
+    // PUBLISHER FOR COMMANDING THE CRAZYFLIE
+    // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
+	//ros::Publishers to advertise the control output
+	controlCommandPublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
 	//this topic lets the PPSClient listen to the terminal commands
-    commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
-    ros::Subscriber commandSubscriber = nodeHandle.subscribe("Command", 1, commandCallback);
+    //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
+
+
+
+
+
+    // CREATE A NODE HANDLE TO THE COORDINATOR
+    std::string namespace_to_coordinator;
+    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+
+
+
+
+
+    // SUBSCRIBER FOR {TAKE-OFF,LAND,MOTORS-OFF} AND CONTROLLER SELECTION
+    // > 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);
+
+
+
+
 
     //this topic lets us use the terminal to communicate with crazyRadio node.
     crazyRadioCommandPublisher = nodeHandle.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
@@ -1070,13 +1273,14 @@ int main(int argc, char* argv[])
     // this topic will publish flying state whenever it changes.
     flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
 
-    // will publish battery state when it changes
-    batteryStatePublisher = nodeHandle.advertise<std_msgs::Int32>("batteryState", 1);
-
+    
     controllerUsedPublisher = nodeHandle.advertise<std_msgs::Int32>("controllerUsed", 1);
 
+
+
+
     // crazy radio status
-    crazyradio_status = DISCONNECTED;
+    crazyradio_status = CRAZY_RADIO_STATE_DISCONNECTED;
 
     // publish first flying state data
     std_msgs::Int32 flying_state_msg;
@@ -1089,14 +1293,11 @@ int main(int argc, char* argv[])
     ros::Subscriber controllerSetpointSubscriber = namespaceNodeHandle.subscribe("student_GUI/ControllerSetpoint", 1, controllerSetPointCallback);
     ros::Subscriber safeSetpointSubscriber = namespaceNodeHandle.subscribe("SafeControllerService/Setpoint", 1, safeSetPointCallback);
 
-    // subscriber for DBChanged
-    ros::Subscriber DBChangedSubscriber = namespaceNodeHandle.subscribe("/my_GUI/DBChanged", 1, DBChangedCallback);
-
-    // subscriber for emergencyStop
-    ros::Subscriber emergencyStopSubscriber = namespaceNodeHandle.subscribe("/my_GUI/emergencyStop", 1, emergencyStopCallback);
+    
 
+    
     // Subscriber for "commandAllAgents" commands that are sent from the coordinator node
-    ros::Subscriber commandAllAgentsSubscriber = namespaceNodeHandle.subscribe("/my_GUI/commandAllAgents", 1, commandAllAgentsCallback);
+    //ros::Subscriber commandAllAgentsSubscriber = namespaceNodeHandle.subscribe("/my_GUI/commandAllAgents", 1, commandAllAgentsCallback);
 
     // crazyradio status. Connected, connecting or disconnected
     ros::Subscriber crazyRadioStatusSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
@@ -1104,20 +1305,34 @@ int main(int argc, char* argv[])
     // Subscriber for "crazyRadioCommandAllAgents" commands that are sent from the coordinator node
     ros::Subscriber crazyRadioCommandAllAgentsSubscriber = namespaceNodeHandle.subscribe("/my_GUI/crazyRadioCommandAllAgents", 1, crazyRadioCommandAllAgentsCallback);
 
-    // know the battery level of the CF
-    ros::Subscriber CFBatterySubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CFBattery", 1, CFBatteryCallback);
+
+
+
+
+    // will publish battery state when it changes
+    //batteryStatePublisher = nodeHandle.advertise<std_msgs::Int32>("batteryState", 1);
 
     // INITIALISE THE BATTERY VOLTAGE TO SOMETHING CLOSE TO FULL
     // > This is used to prevent the "Low Battery" being trigged when the 
     //   first battery voltage data is received
-    m_battery_voltage = 4.2f;
+    //m_battery_voltage = 4.2f;
+    // know the battery level of the CF
+    //ros::Subscriber CFBatterySubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CFBattery", 1, CFBatteryCallback);
+
+    //setBatteryStateTo(BATTERY_STATE_NORMAL); //initialize battery state
+
+    // Subscribe to the battery state change message from the Battery Monitor node
+    std::string namespace_to_battery_monitor = m_namespace + "/BatteryMonitor";
+    ros::NodeHandle nodeHandle_to_battery_monitor(namespace_to_battery_monitor);
+    ros::Subscriber CFBatterySubscriber = nodeHandle_to_battery_monitor.subscribe("ChangedStateTo", 1, batteryMonitorStateChangedCallback);
+
 
 	//start with safe controller
     flying_state = STATE_MOTORS_OFF;
     setControllerUsed(SAFE_CONTROLLER);
     setInstantController(SAFE_CONTROLLER); //initialize this also, so we notify GUI
 
-    setBatteryStateTo(BATTERY_STATE_NORMAL); //initialize battery state
+    
 
     // Open a ROS "bag" to store data for post-analysis
 	// std::string package_path;
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 934e978d..0aa0aefe 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -264,7 +264,8 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
 
     // Create publisher as a local variable, using the filename
     // as the name of the message
-    ros::Publisher yamlParametersReadyForFetchPublisher = nodeHandle.advertise<StringWithHeader>(yaml_filename_to_load, 1);
+    ros::Publisher yamlParametersReadyForFetchPublisher = nodeHandle.advertise<IntWithHeader>(yaml_filename_to_load, 1);
+    //ros::spinOnce();
     // Create a local variable for the message
     IntWithHeader yaml_ready_msg;
     // Specify with the data the "type" of this parameter service
@@ -277,7 +278,7 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
         }
         case TYPE_COORDINATOR:
         {
-            yaml_ready_msg.data = LOAD_YAML_FROM_AGENT;
+            yaml_ready_msg.data = LOAD_YAML_FROM_COORDINATOR;
             break;
         }
         default:
@@ -294,14 +295,18 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
     // Copy across the vector of IDs
     if (yaml_filename_to_load_with_header.shouldCheckForID)
     {
-        int length_of_IDs = yaml_filename_to_load_with_header.agentIDs.size();
-        for ( int i_ID=0 ; i_ID<length_of_IDs ; i_ID++ )
+        for ( int i_ID=0 ; i_ID<yaml_filename_to_load_with_header.agentIDs.size() ; i_ID++ )
         {
             yaml_ready_msg.agentIDs.push_back(yaml_filename_to_load_with_header.agentIDs[i_ID]);
         }
     }
+    // Sleep to make the publisher known to ROS (in seconds)
+    ros::Duration(1.0).sleep();
     // Send the message
     yamlParametersReadyForFetchPublisher.publish(yaml_ready_msg);
+
+    // Inform the user that this was published
+    ROS_INFO_STREAM("[PARAMETER SERVICE] Published message that " << yaml_filename_to_load << " yaml parameters are ready." );
 }
 
 
@@ -472,7 +477,7 @@ int main(int argc, char* argv[])
     // loads yaml parameters
     bool isValid_namespaces = constructNamespaces();
 
-    // Stall the parameter service is the TYPE and ID are not valid
+    // Stall if the TYPE and ID are not valid
     if ( !( isValid_type_and_ID && isValid_namespaces ) )
     {
         ROS_ERROR("[PARAMETER SERVICE] Service NOT FUNCTIONING :-)");
-- 
GitLab


From 10a3a204fb2b98173e971f5a15b96c2c40316121 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 10:27:38 +0100
Subject: [PATCH 07/87] Adjusted location of enable and load yaml buttons, and
 added toggle detials to coordinator row

---
 .../flyingAgentGUI/forms/coordinator.ui       |  31 ++-
 .../flyingAgentGUI/forms/coordinatorrow.ui    |  10 +-
 .../forms/enablecontrollerloadyamlbar.ui      | 228 ++++++------------
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |  64 ++---
 .../GUI_Qt/flyingAgentGUI/forms/topbanner.ui  |   2 +-
 .../flyingAgentGUI/include/coordinator.h      |   6 +
 .../flyingAgentGUI/include/coordinatorrow.h   |   8 +-
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp |  40 +++
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  98 ++++++--
 9 files changed, 282 insertions(+), 205 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
index 13377061..855f9cec 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
@@ -21,6 +21,12 @@
   <layout class="QVBoxLayout" name="verticalLayout">
    <item>
     <widget class="QLabel" name="coordintor_title_label">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
      <property name="font">
       <font>
        <weight>75</weight>
@@ -37,6 +43,12 @@
    </item>
    <item>
     <widget class="QLabel" name="coordinator_id_label">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
      <property name="font">
       <font>
        <weight>75</weight>
@@ -58,10 +70,17 @@
      </property>
     </widget>
    </item>
+   <item>
+    <widget class="QPushButton" name="toggle_details_button">
+     <property name="text">
+      <string>Toggle Details</string>
+     </property>
+    </widget>
+   </item>
    <item>
     <widget class="QPushButton" name="delete_button">
      <property name="text">
-      <string>Delete</string>
+      <string>Remove All</string>
      </property>
     </widget>
    </item>
@@ -85,6 +104,12 @@
    </item>
    <item>
     <widget class="QScrollArea" name="coordinated_agents_scrollArea">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="Expanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
      <property name="widgetResizable">
       <bool>true</bool>
      </property>
@@ -93,8 +118,8 @@
        <rect>
         <x>0</x>
         <y>0</y>
-        <width>583</width>
-        <height>854</height>
+        <width>565</width>
+        <height>622</height>
        </rect>
       </property>
       <layout class="QVBoxLayout" name="verticalLayout_for_coordinatedAgentsScrollArea"/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
index 790ff9ce..06003ef3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
@@ -55,14 +55,14 @@
    <item>
     <widget class="QCheckBox" name="shouldCoordinate_checkBox">
      <property name="sizePolicy">
-      <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+      <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
        <horstretch>0</horstretch>
        <verstretch>0</verstretch>
       </sizepolicy>
      </property>
      <property name="minimumSize">
       <size>
-       <width>180</width>
+       <width>50</width>
        <height>35</height>
       </size>
      </property>
@@ -323,20 +323,20 @@
    <item>
     <widget class="QLabel" name="controller_enabled_label">
      <property name="sizePolicy">
-      <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+      <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
        <horstretch>0</horstretch>
        <verstretch>0</verstretch>
       </sizepolicy>
      </property>
      <property name="minimumSize">
       <size>
-       <width>70</width>
+       <width>50</width>
        <height>35</height>
       </size>
      </property>
      <property name="maximumSize">
       <size>
-       <width>70</width>
+       <width>180</width>
        <height>35</height>
       </size>
      </property>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index 9304b2ad..80d40b20 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>595</width>
-    <height>561</height>
+    <width>1572</width>
+    <height>403</height>
    </rect>
   </property>
   <property name="sizePolicy">
@@ -26,43 +26,18 @@
   </property>
   <layout class="QGridLayout" name="gridLayout_2">
    <item row="0" column="0">
-    <layout class="QGridLayout" name="gridLayout">
-     <item row="7" column="1">
-      <widget class="QPushButton" name="load_yaml_safe_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="minimumSize">
-        <size>
-         <width>120</width>
-         <height>40</height>
-        </size>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>40</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>Safe</string>
-       </property>
-      </widget>
-     </item>
-     <item row="7" column="0">
+    <layout class="QGridLayout" name="gridLayout_3">
+     <item row="0" column="4">
       <widget class="QPushButton" name="enable_safe_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>40</height>
         </size>
        </property>
@@ -84,16 +59,16 @@
       </widget>
      </item>
      <item row="0" column="0">
-      <widget class="QLabel" name="enable_controller_top_label">
+      <widget class="QLabel" name="enable_controller_label">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>20</height>
         </size>
        </property>
@@ -118,75 +93,81 @@
       </widget>
      </item>
      <item row="0" column="1">
-      <widget class="QLabel" name="load_yaml_top_label">
+      <widget class="QPushButton" name="enable_default_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
-         <height>20</height>
+         <width>60</width>
+         <height>40</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>20</height>
+         <height>40</height>
         </size>
        </property>
        <property name="font">
         <font>
-         <weight>75</weight>
-         <bold>true</bold>
+         <weight>50</weight>
+         <bold>false</bold>
         </font>
        </property>
        <property name="text">
-        <string>Load</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignCenter</set>
+        <string>Default</string>
        </property>
       </widget>
      </item>
-     <item row="4" column="1">
-      <widget class="QPushButton" name="load_yaml_demo_button">
+     <item row="1" column="0">
+      <widget class="QLabel" name="load_yaml_label">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
-         <height>40</height>
+         <width>60</width>
+         <height>20</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>20</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
        <property name="text">
-        <string>Demo</string>
+        <string>Load YAML</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item row="4" column="0">
-      <widget class="QPushButton" name="enable_demo_button">
+     <item row="1" column="4">
+      <widget class="QPushButton" name="load_yaml_safe_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>40</height>
         </size>
        </property>
@@ -196,109 +177,72 @@
          <height>40</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <weight>50</weight>
-         <bold>false</bold>
-        </font>
-       </property>
        <property name="text">
-        <string>Demo</string>
+        <string>Safe</string>
        </property>
       </widget>
      </item>
-     <item row="8" column="0">
-      <spacer name="verticalSpacer">
-       <property name="orientation">
-        <enum>Qt::Vertical</enum>
-       </property>
-       <property name="sizeHint" stdset="0">
-        <size>
-         <width>20</width>
-         <height>40</height>
-        </size>
-       </property>
-      </spacer>
-     </item>
-     <item row="1" column="0">
-      <widget class="QLabel" name="enable_controller_bot_label">
+     <item row="1" column="1">
+      <widget class="QPushButton" name="load_yaml_default_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
-         <height>20</height>
+         <width>60</width>
+         <height>40</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>20</height>
+         <height>40</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <weight>75</weight>
-         <bold>true</bold>
-        </font>
-       </property>
        <property name="text">
-        <string>Controller</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignCenter</set>
+        <string>Default</string>
        </property>
       </widget>
      </item>
-     <item row="1" column="1">
-      <widget class="QLabel" name="load_yaml_bot_label">
+     <item row="1" column="2">
+      <widget class="QPushButton" name="load_yaml_student_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
-         <height>20</height>
+         <width>60</width>
+         <height>40</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>20</height>
+         <height>40</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <weight>75</weight>
-         <bold>true</bold>
-        </font>
-       </property>
        <property name="text">
-        <string>YAML</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignCenter</set>
+        <string>Student</string>
        </property>
       </widget>
      </item>
-     <item row="2" column="0">
-      <widget class="QPushButton" name="enable_default_button">
+     <item row="0" column="2">
+      <widget class="QPushButton" name="enable_student_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>40</height>
         </size>
        </property>
@@ -315,46 +259,21 @@
         </font>
        </property>
        <property name="text">
-        <string>Default</string>
-       </property>
-      </widget>
-     </item>
-     <item row="2" column="1">
-      <widget class="QPushButton" name="load_yaml_default_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="minimumSize">
-        <size>
-         <width>120</width>
-         <height>40</height>
-        </size>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>40</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>Default</string>
+        <string>Student</string>
        </property>
       </widget>
      </item>
-     <item row="3" column="0">
-      <widget class="QPushButton" name="enable_student_button">
+     <item row="0" column="3">
+      <widget class="QPushButton" name="enable_demo_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>40</height>
         </size>
        </property>
@@ -371,21 +290,21 @@
         </font>
        </property>
        <property name="text">
-        <string>Student</string>
+        <string>Demo</string>
        </property>
       </widget>
      </item>
-     <item row="3" column="1">
-      <widget class="QPushButton" name="load_yaml_student_button">
+     <item row="1" column="3">
+      <widget class="QPushButton" name="load_yaml_demo_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>120</width>
+         <width>60</width>
          <height>40</height>
         </size>
        </property>
@@ -396,10 +315,23 @@
         </size>
        </property>
        <property name="text">
-        <string>Student</string>
+        <string>Demo</string>
        </property>
       </widget>
      </item>
+     <item row="0" column="5">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
     </layout>
    </item>
   </layout>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index e35441f9..a3018633 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -34,15 +34,21 @@
       </property>
       <item>
        <widget class="Coordinator" name="customWidget_coordinator" native="true">
+        <property name="sizePolicy">
+         <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+          <horstretch>0</horstretch>
+          <verstretch>0</verstretch>
+         </sizepolicy>
+        </property>
         <property name="minimumSize">
          <size>
-          <width>400</width>
+          <width>300</width>
           <height>0</height>
          </size>
         </property>
         <property name="maximumSize">
          <size>
-          <width>680</width>
+          <width>800</width>
           <height>16777215</height>
          </size>
         </property>
@@ -70,7 +76,7 @@
           <property name="maximumSize">
            <size>
             <width>16777215</width>
-            <height>120</height>
+            <height>100</height>
            </size>
           </property>
          </widget>
@@ -80,7 +86,32 @@
           <property name="maximumSize">
            <size>
             <width>16777215</width>
-            <height>120</height>
+            <height>80</height>
+           </size>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <widget class="EnableControllerLoadYamlBar" name="customWidget_enableControllerLoadYamlBar" native="true">
+          <property name="enabled">
+           <bool>true</bool>
+          </property>
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
+          </property>
+          <property name="minimumSize">
+           <size>
+            <width>0</width>
+            <height>0</height>
+           </size>
+          </property>
+          <property name="maximumSize">
+           <size>
+            <width>16777215</width>
+            <height>100</height>
            </size>
           </property>
          </widget>
@@ -112,31 +143,6 @@
             </property>
            </widget>
           </item>
-          <item>
-           <widget class="EnableControllerLoadYamlBar" name="customWidget_enableControllerLoadYamlBar" native="true">
-            <property name="enabled">
-             <bool>true</bool>
-            </property>
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>200</width>
-              <height>0</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>500</width>
-              <height>16777215</height>
-             </size>
-            </property>
-           </widget>
-          </item>
          </layout>
         </item>
        </layout>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
index 486f7235..0198a2db 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
@@ -43,7 +43,7 @@
        <property name="maximumSize">
         <size>
          <width>16777215</width>
-         <height>120</height>
+         <height>100</height>
         </size>
        </property>
        <property name="text">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
index 82f3faf8..27c6501b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
@@ -22,11 +22,17 @@ public:
 private:
     QVector<CoordinatorRow*> vector_of_coordinatorRows;
 
+    int level_of_detail_to_display = 1;
+
     void remove_all_entries_from_vector_of_coordinatorRows();
 
+    void apply_level_of_detail_to_all_entries(int level);
+
 private slots:
     void on_refresh_button_clicked();
 
+    void on_toggle_details_button_clicked();
+
     void on_delete_button_clicked();
 
     void on_coordinate_all_checkBox_clicked();
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 75410c45..6fa61806 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -126,6 +126,8 @@ public:
     // PUBLIC METHODS FOR SETTING PROPERTIES
     // > Set the state of the checkbox
     void setShouldCoordinate(bool shouldCoordinate);
+    // > Set the level of detail to display
+    void setLevelOfDetailToDisplay(int level);
 
 private:
     // --------------------------------------------------- //
@@ -133,9 +135,11 @@ private:
     Ui::CoordinatorRow *ui;
 
     // > For the ID of which agent this "coordinator row" relates to
-    int my_agentID;
+    int m_agentID;
     // > For using the agent ID in constructing namespaces
-    QString my_agentID_as_string;
+    QString m_agentID_as_string;
+    // > For the name of the allocated Crazyflie
+    QString m_crazyflie_name_as_string;
 
     // > For keeping track of the current RF Crazyradio state
     int my_radio_status;
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
index 2a89aaa9..be2efe66 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
@@ -94,10 +94,41 @@ void Coordinator::on_refresh_button_clicked()
         vector_of_coordinatorRows.append(temp_coordinatorRow);
 
         ui->coordinated_agents_scrollAreaWidgetContents->layout()->addWidget(temp_coordinatorRow);
+
+        // Call the function that applies this level
+        // of detail to all the entries
+        apply_level_of_detail_to_all_entries(level_of_detail_to_display);
     }
 #endif
 }
 
+
+void Coordinator::on_toggle_details_button_clicked()
+{
+    // Toggle the level of detail to display
+    switch (level_of_detail_to_display)
+    {
+    case 0:
+    {
+        level_of_detail_to_display = 1;
+        break;
+    }
+    case 1:
+    {
+        level_of_detail_to_display = 0;
+        break;
+    }
+    default:
+    {
+        level_of_detail_to_display = 0;
+        break;
+    }
+    }
+    // Call the function that applies this level
+    // of detail to all the entries
+    apply_level_of_detail_to_all_entries(level_of_detail_to_display);
+}
+
 void Coordinator::on_delete_button_clicked()
 {
     // Call the function that performs the task requested
@@ -114,6 +145,15 @@ void Coordinator::remove_all_entries_from_vector_of_coordinatorRows()
     vector_of_coordinatorRows.clear();
 }
 
+void Coordinator::apply_level_of_detail_to_all_entries(int level)
+{
+    // Apply this to all the rows
+    for ( int irow = 0 ; irow < vector_of_coordinatorRows.length() ; irow++ )
+    {
+        vector_of_coordinatorRows[irow]->setLevelOfDetailToDisplay( level );
+    }
+}
+
 void Coordinator::on_coordinate_all_checkBox_clicked()
 {
     // Get the state of the "coordinate all" is check box
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 68c7e58c..bffcaafe 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -36,27 +36,27 @@
 CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     QWidget(parent),
     ui(new Ui::CoordinatorRow),
-    my_agentID(agentID)
+    m_agentID(agentID)
 {
     ui->setupUi(this);
 
     // CONVERT THE AGENT ID TO A ZERO PADDED STRING
     // > This is the c++ method:
     //std::ostringstream str_stream;
-    //str_stream << std::setw(3) << std::setfill('0') << my_agentID;
+    //str_stream << std::setw(3) << std::setfill('0') << m_agentID;
     //std::string agentID_as_string(str_stream.str());
     // > This is the Qt method
-    //my_agentID_as_string = QString("%1").arg(my_agentID, 3, 10, QChar('0'));
+    //m_agentID_as_string = QString("%1").arg(m_agentID, 3, 10, QChar('0'));
     //   For which the syntax is:
     //   - Arg1: the number
     //   - Arg2: how many 0 you want?
     //   - Arg3: The base (10 - decimal, 16 hexadecimal)
     // > Alternate Qt method:
-    my_agentID_as_string = QString::number(my_agentID).rightJustified(3, '0');
+    m_agentID_as_string = QString::number(m_agentID).rightJustified(3, '0');
 
     // CONVERT THE AGENT ID TO A STRING FOR THE BASE NAMESPACE
     QString qstr_ros_base_namespace = "/dfall/agent";
-    qstr_ros_base_namespace.append(my_agentID_as_string);
+    qstr_ros_base_namespace.append(m_agentID_as_string);
     std::string ros_base_namespace = qstr_ros_base_namespace.toStdString();
 
     // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
@@ -103,7 +103,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
 
 
     // LET THE USER KNOW WHAT THE BASE NAMESPACE IS
-    ROS_INFO_STREAM("[Coordinator Row GUI] using base namespace: " << ros_base_namespace.c_str() << ", for agentID = " << my_agentID);
+    ROS_INFO_STREAM("[Coordinator Row GUI] using base namespace: " << ros_base_namespace.c_str() << ", for agentID = " << m_agentID);
 
     // DEBUGGING FOR NAMESPACES
     //std::string temp_ros_namespace = ros::this_node::getNamespace();
@@ -141,7 +141,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     loadCrazyflieContext();
 
     // FOR DEBUGGING:
-    //ui->shouldCoordinate_checkBox->setText(my_agentID_as_string);
+    //ui->shouldCoordinate_checkBox->setText(m_agentID_as_string);
     //ui->shouldCoordinate_checkBox->setText(QString::fromStdString(base_namespace));
 }
 
@@ -160,6 +160,68 @@ void CoordinatorRow::setShouldCoordinate(bool shouldCoordinate)
     ui->shouldCoordinate_checkBox->setChecked( shouldCoordinate );
 }
 
+void CoordinatorRow::setLevelOfDetailToDisplay(int level)
+{
+    switch (level)
+    {
+    case 0:
+    {
+        ui->motors_off_button->setVisible(true);
+        ui->enable_flying_button->setVisible(true);
+        ui->disable_flying_button->setVisible(true);
+
+        ui->battery_voltage_lineEdit->setVisible(true);
+
+        ui->rf_connect_button->setVisible(true);
+        ui->rf_disconnect_button->setVisible(true);
+
+        QString qstr_for_checkbox_label = "ID";
+        qstr_for_checkbox_label.append(QString::number(m_agentID));
+        qstr_for_checkbox_label.append(", ");
+        qstr_for_checkbox_label.append(m_crazyflie_name_as_string);
+        ui->shouldCoordinate_checkBox->setText(qstr_for_checkbox_label);
+        break;
+    }
+    case 1:
+    {
+        ui->motors_off_button->setVisible(false);
+        ui->enable_flying_button->setVisible(false);
+        ui->disable_flying_button->setVisible(false);
+
+        ui->battery_voltage_lineEdit->setVisible(false);
+
+        ui->rf_connect_button->setVisible(false);
+        ui->rf_disconnect_button->setVisible(false);
+
+        QString qstr_for_checkbox_label = "ID";
+        qstr_for_checkbox_label.append(QString::number(m_agentID));
+        ui->shouldCoordinate_checkBox->setText(qstr_for_checkbox_label);
+
+
+        break;
+    }
+    default:
+    {
+        ui->motors_off_button->setVisible(true);
+        ui->enable_flying_button->setVisible(true);
+        ui->disable_flying_button->setVisible(true);
+
+        ui->battery_voltage_lineEdit->setVisible(true);
+
+        ui->rf_connect_button->setVisible(true);
+        ui->rf_disconnect_button->setVisible(true);
+
+        QString qstr_for_checkbox_label = "ID";
+        qstr_for_checkbox_label.append(QString::number(m_agentID));
+        qstr_for_checkbox_label.append(", ");
+        qstr_for_checkbox_label.append(m_crazyflie_name_as_string);
+        ui->shouldCoordinate_checkBox->setText(qstr_for_checkbox_label);
+        break;
+    }
+    }
+}
+
+
 // > For making the "enable flight" and "disable flight" buttons unavailable
 void CoordinatorRow::disableFlyingStateButtons()
 {
@@ -186,7 +248,7 @@ void CoordinatorRow::enableFlyingStateButtons()
 // > For the Battery Voltage
 void CoordinatorRow::crazyRadioStatusCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Crazy Radio Status Callback called for agentID = " << my_agentID);
+    //ROS_INFO_STEAM("[Coordinator Row GUI] Crazy Radio Status Callback called for agentID = " << m_agentID);
     setCrazyRadioStatus( msg.data );
 }
 #endif
@@ -289,7 +351,7 @@ void CoordinatorRow::batteryVoltageCallback(const std_msgs::Float32& msg)
 
 void CoordinatorRow::batteryStateChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Battery State Changed Callback called for agentID = " << my_agentID);
+    //ROS_INFO_STEAM("[Coordinator Row GUI] Battery State Changed Callback called for agentID = " << m_agentID);
     setBatteryState( msg.data );
 }
 #endif
@@ -516,7 +578,7 @@ float CoordinatorRow::fromVoltageToPercent(float voltage)
 #ifdef CATKIN_MAKE
 void CoordinatorRow::flyingStateChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Flying State Changed Callback called for agentID = " << my_agentID);
+    //ROS_INFO_STEAM("[Coordinator Row GUI] Flying State Changed Callback called for agentID = " << m_agentID);
     setFlyingState(msg.data);
 }
 #endif
@@ -585,7 +647,7 @@ void CoordinatorRow::setFlyingState(int new_flying_state)
 // > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
 void CoordinatorRow::databaseChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Database Changed Callback called for agentID = " << my_agentID);
+    //ROS_INFO_STEAM("[Coordinator Row GUI] Database Changed Callback called for agentID = " << m_agentID);
     loadCrazyflieContext();
 }
 #endif
@@ -596,8 +658,8 @@ void CoordinatorRow::loadCrazyflieContext()
     QString qstr_crazyflie_name = "";
 #ifdef CATKIN_MAKE
     CMQuery contextCall;
-    contextCall.request.studentID = my_agentID;
-    //ROS_INFO_STREAM("StudentID:" << my_agentID);
+    contextCall.request.studentID = m_agentID;
+    //ROS_INFO_STREAM("StudentID:" << m_agentID);
 
     centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
 
@@ -610,7 +672,7 @@ void CoordinatorRow::loadCrazyflieContext()
     }
     else
     {
-        ROS_ERROR_STREAM("[Coordinator Row GUI] Failed to load context for agentID = " << my_agentID);
+        ROS_ERROR_STREAM("[Coordinator Row GUI] Failed to load context for agentID = " << m_agentID);
     }
     // This updating of the radio only needs to be done by the actual agent's node
     //ros::NodeHandle nh("CrazyRadio");
@@ -622,11 +684,13 @@ void CoordinatorRow::loadCrazyflieContext()
 
     // Construct and set the string for the checkbox label
     QString qstr_for_checkbox_label = "ID";
-    qstr_for_checkbox_label.append(QString::number(my_agentID));
-    qstr_for_checkbox_label.append(", CF");
+    qstr_for_checkbox_label.append(QString::number(m_agentID));
+    qstr_for_checkbox_label.append(", ");
     qstr_for_checkbox_label.append(qstr_crazyflie_name);
     ui->shouldCoordinate_checkBox->setText(qstr_for_checkbox_label);
 
+    // Set the name of the Crazyflie to the class variable
+    m_crazyflie_name_as_string = qstr_crazyflie_name;
 }
 
 
@@ -634,7 +698,7 @@ void CoordinatorRow::loadCrazyflieContext()
 // > For the controller currently operating, received on "controllerUsedSubscriber"
 void CoordinatorRow::controllerUsedChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Controller Used Changed Callback called for agentID = " << my_agentID);
+    //ROS_INFO_STEAM("[Coordinator Row GUI] Controller Used Changed Callback called for agentID = " << m_agentID);
     setControllerEnabled(msg.data);
 }
 #endif
-- 
GitLab


From d17639bff7f3e8d69772be9229739a67364bb32e Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 16:05:26 +0100
Subject: [PATCH 08/87] Started connecting the Connect Start Stop Bar of the
 GUI. Now needs some GUI settings to be changed with Qt

---
 .../include/connectstartstopbar.h             | 151 +++-
 .../flyingAgentGUI/include/coordinatorrow.h   | 100 +--
 .../include/enablecontrollerloadyamlbar.h     |  12 +-
 .../flyingAgentGUI/include/mainwindow.h       |  36 +-
 .../src/connectstartstopbar.cpp               | 688 +++++++++++++++++-
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp |   9 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     | 411 +++++------
 .../src/enablecontrollerloadyamlbar.cpp       |  53 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  | 194 +++--
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   | 116 ++-
 .../src/d_fall_pps/include/nodes/PPSClient.h  |   6 -
 pps_ws/src/d_fall_pps/launch/Agent.launch     |   8 +-
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp |  24 +-
 13 files changed, 1297 insertions(+), 511 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 285a788c..fbfd8c71 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -1,10 +1,42 @@
 #ifndef CONNECTSTARTSTOPBAR_H
 #define CONNECTSTARTSTOPBAR_H
 
+#include <string>
 #include <QWidget>
+#include <QMutex>
 
-//#include <QGraphicsSvgItem>
-//#include <QSvgRenderer>
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/AreaBounds.h"
+#include "d_fall_pps/CrazyflieContext.h"
+#include "d_fall_pps/CMQuery.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+#endif
+
+// BATTERY LABEL IMAGE INDEX
+#define BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE  -1
+#define BATTERY_LABEL_IMAGE_INDEX_EMPTY        0
+#define BATTERY_LABEL_IMAGE_INDEX_20           1
+#define BATTERY_LABEL_IMAGE_INDEX_40           2
+#define BATTERY_LABEL_IMAGE_INDEX_60           3
+#define BATTERY_LABEL_IMAGE_INDEX_80           4
+#define BATTERY_LABEL_IMAGE_INDEX_FULL         5
+#define BATTERY_LABEL_IMAGE_INDEX_UNKNOWN      6
 
 namespace Ui {
 class ConnectStartStopBar;
@@ -18,11 +50,122 @@ public:
     explicit ConnectStartStopBar(QWidget *parent = 0);
     ~ConnectStartStopBar();
 
+private:
+	// --------------------------------------------------- //
+    // PRIVATE VARIABLES
+    Ui::ConnectStartStopBar *ui;
+
+    // > For the type of this node,
+    //   i.e., an agent or a coordinator
+	int m_type = 0;
+
+	// > For the ID of this node
+	int m_ID = 0;
+
+	// The namespace into which node operates
+	std::string m_base_namespace;
+
+
+
+	// > For keeping track of the current battery state
+    int m_battery_state;
+    // > For keeping track of which image is currently displayed
+    int m_battery_status_label_image_current_index;
+
+
+
+    // MUTEX FOR HANDLING ACCESS
+    // > For the "rf_status_label" UI element
+    //QMutex m_rf_status_label_mutex;
+    // > For the "battery_voltage_lineEdit" UI element
+    //QMutex m_battery_voltage_lineEdit_mutex;
+    // > For the "battery_status_label" UI element
+    QMutex m_battery_status_label_mutex;
+    
+
+
+#ifdef CATKIN_MAKE
+	// PUBLISHERS AND SUBSRIBERS
+    // > For Crazyradio commands based on button clicks
+    ros::Publisher crazyRadioCommandPublisher;
+    // > For updating the "rf_status_label" picture
+    ros::Subscriber crazyRadioStatusSubscriber;
+    // > For updating the current battery voltage
+    ros::Subscriber batteryVoltageSubscriber;
+    // > For updating the current battery state
+    //ros::Subscriber batteryStateSubscriber;
+    // > For updating the current battery level
+    ros::Subscriber batteryLevelSubscriber;
+    // > For Flying state commands based on button clicks
+    ros::Publisher flyingStateCommandPublisher;
+    // > For updating the "flying_state_label" picture
+    ros::Subscriber flyingStateSubscriber;
+#endif
+
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+    // > For making the "enable flight" and "disable flight"
+    //   buttons (un-)available
+    void disableFlyingStateButtons();
+    void enableFlyingStateButtons();
+
+    // > For updating the RF Radio status shown in the
+    //   UI element of "rf_status_label"
+    void setCrazyRadioStatus(int radio_status);
+    // > For updating the battery state
+    void setBatteryState(int new_battery_state);
+    // > For updating the battery voltage shown in the UI elements 
+    //   of "battery_voltage_lineEdit" and "battery_status_label"
+    void setBatteryVoltageText(float battery_voltage);
+    void setBatteryImageBasedOnLevel(int battery_level);
+    // > For updating the "my_flying_state" variable, and
+    //   the UI element of "flying_state_label"
+    void setFlyingState(int new_flying_state);
+
+
+
+#ifdef CATKIN_MAKE
+    // Get the type and ID of this node
+    bool getTypeAndIDParameters();
+	// Fill the head for a message
+    void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
+
+    // > For the CrazyRadio status, received on the
+    //   "crazyRadioStatusSubscriber"
+    void crazyRadioStatusCallback(const std_msgs::Int32& msg);
+    // > For the Battery Voltage, received on the
+    //   "batteryVoltageSubscriber"
+    void batteryVoltageCallback(const std_msgs::Float32& msg);
+    // > For the Battery State, receieved on the
+    //   "batteryStateSubscriber"
+    void batteryStateChangedCallback(const std_msgs::Int32& msg);
+    // > For the Battery Level, receieved on the
+    //   "batteryLevelSubscriber"
+    void batteryLevelCallback(const std_msgs::Int32& msg);
+    // > For the Flying State, received on the
+    //   "flyingStateSubscriber"
+    void flyingStateChangedCallback(const std_msgs::Int32& msg);
+
+#endif
+
+
+
+
+
 private slots:
+
+	// PRIVATE METHODS FOR BUTTON CALLBACKS
+    // > For the RF Crazyradio connect/disconnect buttons
+	void on_rf_connect_button_clicked();
     void on_rf_disconnect_button_clicked();
+    // > For the enable, disable, motors-off buttons
+    void on_enable_flying_button_clicked();
+    void on_disable_flying_button_clicked();
+    void on_motors_off_button_clicked();
+
 
-private:
-    Ui::ConnectStartStopBar *ui;
 };
 
 #endif // CONNECTSTARTSTOPBAR_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 6fa61806..f80eb8ba 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -53,62 +53,22 @@
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/CMQuery.h"
 
+// Include the shared definitions
+#include "nodes/Constants.h"
 
-
+// SPECIFY THE PACKAGE NAMESPACE
 using namespace d_fall_pps;
 #endif
 
-// TYPES OF CONTROLLER BEING USED
-#define SAFE_CONTROLLER    1
-#define DEMO_CONTROLLER    2
-#define STUDENT_CONTROLLER 3
-#define MPC_CONTROLLER     4
-#define REMOTE_CONTROLLER  5
-#define TUNING_CONTROLLER  6
-
-// COMMANDS FOR CRAZYRADIO
-#define CMD_RECONNECT  0
-#define CMD_DISCONNECT 1
-
-// CRAZYRADIO STATES
-#define CONNECTED        0
-#define CONNECTING       1
-#define DISCONNECTED     2
-
-// 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"
-// node where the command is enacted
-#define CMD_USE_SAFE_CONTROLLER      1
-#define CMD_USE_DEMO_CONTROLLER      2
-#define CMD_USE_STUDENT_CONTROLLER   3
-#define CMD_USE_MPC_CONTROLLER       4
-#define CMD_USE_REMOTE_CONTROLLER    5
-#define CMD_USE_TUNING_CONTROLLER    6
-
-#define CMD_CRAZYFLY_TAKE_OFF        11
-#define CMD_CRAZYFLY_LAND            12
-#define CMD_CRAZYFLY_MOTORS_OFF      13
-
-// FLYING STATES
-#define STATE_MOTORS_OFF 1
-#define STATE_TAKE_OFF   2
-#define STATE_FLYING     3
-#define STATE_LAND       4
-
-// BATTERY STATES
-#define BATTERY_STATE_NORMAL 0
-#define BATTERY_STATE_LOW    1
-
 // BATTERY LABEL IMAGE INDEX
-#define BATTERY_LABEL_IMAGE_INDEX_EMPTY     0
-#define BATTERY_LABEL_IMAGE_INDEX_20        1
-#define BATTERY_LABEL_IMAGE_INDEX_40        2
-#define BATTERY_LABEL_IMAGE_INDEX_60        3
-#define BATTERY_LABEL_IMAGE_INDEX_80        4
-#define BATTERY_LABEL_IMAGE_INDEX_FULL      5
-#define BATTERY_LABEL_IMAGE_INDEX_UNKNOWN   6
+#define BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE  -1
+#define BATTERY_LABEL_IMAGE_INDEX_EMPTY        0
+#define BATTERY_LABEL_IMAGE_INDEX_20           1
+#define BATTERY_LABEL_IMAGE_INDEX_40           2
+#define BATTERY_LABEL_IMAGE_INDEX_60           3
+#define BATTERY_LABEL_IMAGE_INDEX_80           4
+#define BATTERY_LABEL_IMAGE_INDEX_FULL         5
+#define BATTERY_LABEL_IMAGE_INDEX_UNKNOWN      6
 
 
 namespace Ui {
@@ -141,34 +101,21 @@ private:
     // > For the name of the allocated Crazyflie
     QString m_crazyflie_name_as_string;
 
-    // > For keeping track of the current RF Crazyradio state
-    int my_radio_status;
+
     // > For keeping track of the current battery state
-    int my_battery_state;
+    int m_battery_state;
     // > For keeping track of which image is currently displayed
-    int my_battery_status_label_image_current_index;
-    // > For keeping track of the current operating state
-    int my_flying_state;
+    int m_battery_status_label_image_current_index;
+
 
     // MUTEX FOR HANDLING ACCESS
     // > For the "rf_status_label" UI element
-    QMutex my_rf_status_label_mutex;
-    // > For the "my_battery_state" variable
-    QMutex my_battery_state_mutex;
+    //QMutex m_rf_status_label_mutex;
     // > For the "battery_voltage_lineEdit" UI element
-    QMutex my_battery_voltage_lineEdit_mutex;
+    //QMutex m_battery_voltage_lineEdit_mutex;
     // > For the "battery_status_label" UI element
-    QMutex my_battery_status_label_mutex;
-    // > For the "my_flying_state" variable
-    QMutex my_flying_state_mutex;
+    QMutex m_battery_status_label_mutex;
 
-    // BATTERY VOLTAGE LIMITS (THESE SHOULD BE READ IN AS PARAMTERS)
-    // > When in a "standby" type of state
-    float battery_voltage_standby_empty;
-    float battery_voltage_standby_full;
-    // > When in a "flying" type of state
-    float battery_voltage_flying_empty;
-    float battery_voltage_flying_full;
 
 
     // --------------------------------------------------- //
@@ -179,11 +126,8 @@ private:
     // > For updating the battery state
     void setBatteryState(int new_battery_state);
     // > For updating the battery voltage shown in the UI elements of "battery_voltage_lineEdit" and "battery_status_label"
-    void setBatteryVoltageTextAndImage(float battery_voltage);
     void setBatteryVoltageText(float battery_voltage);
-    void setBatteryVoltageImage(float battery_voltage);
-    // > For converting a voltage to a percentage, depending on the current "my_flying_state" value
-    float fromVoltageToPercent(float voltage);
+    void setBatteryImageBasedOnLevel(int battery_level);
     // > For making the "enable flight" and "disable flight" buttons (un-)available
     void disableFlyingStateButtons();
     void enableFlyingStateButtons();
@@ -217,7 +161,9 @@ private:
     // > For updating the current battery voltage
     ros::Subscriber batteryVoltageSubscriber;
     // > For updating the current battery state
-    ros::Subscriber batteryStateSubscriber;
+    //ros::Subscriber batteryStateSubscriber;
+    // > For updating the current battery level
+    ros::Subscriber batteryLevelSubscriber;
     // > For Flying state commands based on button clicks
     ros::Publisher flyingStateCommandPublisher;
     // > For updating the "flying_state_label" picture
@@ -238,6 +184,8 @@ private:
     void batteryVoltageCallback(const std_msgs::Float32& msg);
     // > For the Battery State, receieved on the "batteryStateSubscriber"
     void batteryStateChangedCallback(const std_msgs::Int32& msg);
+    // > For the Battery Level, receieved on the "batteryLevelSubscriber"
+    void batteryLevelCallback(const std_msgs::Int32& msg);
     // > For the Flying State, received on the "flyingStateSubscriber"
     void flyingStateChangedCallback(const std_msgs::Int32& msg);
     // > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 1d757b1c..b42d1186 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -70,9 +70,9 @@ private slots:
 private:
     Ui::EnableControllerLoadYamlBar *ui;
 
-#ifdef CATKIN_MAKE
+
     // --------------------------------------------------- //
-    // PRIVATE VARIABLES FOR ROS
+    // PRIVATE VARIABLES
 
     // The type of this node, i.e., agent or a coordinator,
     // specified as a parameter in the "*.launch" file
@@ -81,22 +81,24 @@ private:
     // The ID  of this node
     int m_ID;
 
+#ifdef CATKIN_MAKE
     // PUBLISHERS AND SUBSRIBERS
     // > For {take-off,land,motors-off} and controller selection
     ros::Publisher commandPublisher;
+#endif
 
     // --------------------------------------------------- //
-    // PRIVATE FUNCTIONS FOR ROS
+    // PRIVATE FUNCTIONS
 
+#ifdef CATKIN_MAKE
     // Fill the head for a message
     void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
+#endif
 
 
-
-#endif
 };
 
 #endif // ENABLECONTROLLERLOADYAMLBAR_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 8281e486..c9f071fa 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -71,26 +71,22 @@ public:
     explicit MainWindow(int argc, char **argv, QWidget *parent = 0);
     ~MainWindow();
 
-private slots:
-    void on_actionShowHide_Coordinator_triggered();
-    void on_action_LoadYAML_BatteryMonitor_triggered();
-    void on_action_LoadYAML_ClientConfig_triggered();
+
 
 private:
     Ui::MainWindow *ui;
 
     QShortcut* m_close_GUI_shortcut;
 
-#ifdef CATKIN_MAKE
-    rosNodeThread* m_rosNodeThread;
+    // > For the type of this node,
+    //   i.e., an agent or a coordinator
+    int m_type = 0;
 
-    // Variables for the type and ID
-    // The type of this node, i.e., agent or a coordinator, 
-    // specififed as a parameter in the "*.launch" file
-	int m_type = 0;
+    // > For the ID of this node
+    int m_ID = 0;
 
-	// The ID of this node
-	int m_ID = 0;
+#ifdef CATKIN_MAKE
+    rosNodeThread* m_rosNodeThread;
 
 	// The namespace into which this parameter service loads yaml parameters
 	std::string m_parameter_service_namespace;
@@ -98,6 +94,22 @@ private:
 	ros::Publisher m_requestLoadYamlFilenamePublisher;
 #endif
 
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+#ifdef CATKIN_MAKE
+    bool getTypeAndIDParameters();
+#endif
+
+
+
+
+private slots:
+    // PRIVATE METHODS FOR MENU ITEM CALLBACKS
+    void on_actionShowHide_Coordinator_triggered();
+    void on_action_LoadYAML_BatteryMonitor_triggered();
+    void on_action_LoadYAML_ClientConfig_triggered();
+
 };
 
 #endif // MAINWINDOW_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index a7ec4e9d..ab730565 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -1,46 +1,141 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The bar of the GUI for (dis-)connecting (from)to the Crazyradio
+//    and for sending the {take-off,land,motors-off} commands
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "connectstartstopbar.h"
 #include "ui_connectstartstopbar.h"
 
+
+
+
+
 ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
     QWidget(parent),
     ui(new Ui::ConnectStartStopBar)
 {
     ui->setupUi(this);
 
-    // SET A FEW PROPERTIES OF THE UI ELEMENTS
-    // > Default the battery voltage field to be "blank"
-    QString qstr = "-.-- V";
-    ui->battery_voltage_lineEdit->setText(qstr);
-    // > Red font colour for the battery message label
-    //ui->battery_message_label->setStyleSheet("QLabel { color : red; }");
-    // > Default the battery message label to be "blank"
-    //ui->battery_message_label->setText("");
+#ifdef CATKIN_MAKE
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << this_namespace);
+
+
+    // Get the type and ID of this parameter service
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the TYPE and ID are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[CONNECT START STOP GUI BAR] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+#endif
+
+    // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
+    // > For keeping track of the current battery state
+    m_battery_state = BATTERY_STATE_NORMAL;
+    // > For keeping track of which image is currently displayed
+    m_battery_status_label_image_current_index = -999;
+
+
+    // SET THE STARTING RADIO STATUS TO BE: DISCONNECTED
+    setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+
+    // SET THE STARTING BATTERY VOLTAGE TO BE: UNKNOWN
+    setBatteryVoltageText(-1.0f);
+
+    // SET THE STARTING BATTERY LEVEL TO BE: UNAVAILABLE
+    setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
+
+    // SET THE STARTING FLYING STATE STATUS TO BE: MOTORS OFF
+    setFlyingState(CMD_CRAZYFLY_MOTORS_OFF);
+
+    // ENSURE THE F:YING STATE BUTTONS ARE AVAILABLE FOR A COORDINATOR
+    if (m_type == TYPE_COORDINATOR)
+    {
+        enableFlyingStateButtons();
+    }
 
-    // SET THE DEFAULT IMAGE FOR THE RF CONNECTION STATUS
-    QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
-    ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
-    ui->rf_status_label->setScaledContents(true);
 
-    // SET THE DEFAULT IMAGE FOR THE BATTERY STATUS
-    QPixmap battery_unknown_pixmap(":/images/battery_unknown.png");
-    ui->battery_status_label->setPixmap(battery_unknown_pixmap);
-    //ui->battery_status_label->setPixmap(battery_status_unknown_pixmap.scaled(ui->battery_status_label->size(), Qt::KeepAspectRatio, Qt::SmoothTransformation));
-    ui->battery_status_label->setScaledContents(true);
 
-    // SET THE DEFAULT IMAGE FOR THE FLYING STATE
-    QPixmap flying_state_unknown_pixmap(":/images/flying_state_unknown.png");
-    ui->flying_state_label->setPixmap(flying_state_unknown_pixmap);
-    ui->flying_state_label->setScaledContents(true);
+#ifdef CATKIN_MAKE
+    // CREATE A NODE HANDLE TO THE BASE NAMESPACE
+    ros::NodeHandle base_nodeHandle(this_namespace);
 
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
+    // SUBSCRIBERS AND PUBLISHERS:
 
+    // > For Crazyradio commands based on button clicks
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
+
+    // > For Flying state commands based on button clicks
+    flyingStateCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
+
+    if (m_type == TYPE_AGENT)
+    {
+        // > For updating the "rf_status_label" picture
+        crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &ConnectStartStopBar::crazyRadioStatusCallback, this);
+
+        // > For updating the current battery voltage
+        batteryVoltageSubscriber = base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &ConnectStartStopBar::batteryVoltageCallback, this);
+    
+        // > For updating the current battery state
+        //batteryStateSubscriber = base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &ConnectStartStopBar::batteryStateChangedCallback, this);
+
+        // > For updating the current battery level
+        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);
+    }
+#endif
+
+    // FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
+    // INITIALISATIONS ARE COMPLETE
+    if (m_type == TYPE_AGENT)
+    {
+        //loadCrazyflieContext();
+    }
 
 
     // ADD KEYBOARD SHORTCUTS
     // > For "all motors off", press the space bar
     ui->motors_off_button->setShortcut(tr("Space"));
-
-
 }
 
 ConnectStartStopBar::~ConnectStartStopBar()
@@ -48,7 +143,554 @@ ConnectStartStopBar::~ConnectStartStopBar()
     delete ui;
 }
 
+
+
+// > For making the "enable flight" and "disable flight" buttons unavailable
+void ConnectStartStopBar::disableFlyingStateButtons()
+{
+    //ui->motors_off_button->setEnabled(true);
+    //ui->enable_flying_button->setEnabled(false);
+    //ui->disable_flying_button->setEnabled(false);
+}
+
+// > For making the "enable flight" and "disable flight" buttons available
+void ConnectStartStopBar::enableFlyingStateButtons()
+{
+    //ui->motors_off_button->setEnabled(true);
+    //ui->enable_flying_button->setEnabled(true);
+    //ui->disable_flying_button->setEnabled(true);
+}
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC  RRRR     A    ZZZZZ  Y   Y  RRRR     A    DDDD   III   OOO
+//    C      R   R   A A      Z    Y Y   R   R   A A   D   D   I   O   O
+//    C      RRRR   A   A    Z      Y    RRRR   A   A  D   D   I   O   O
+//    C      R   R  AAAAA   Z       Y    R   R  AAAAA  D   D   I   O   O
+//     CCCC  R   R  A   A  ZZZZZ    Y    R   R  A   A  DDDD   III   OOO
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
+
+// > For the Battery Voltage
+void ConnectStartStopBar::crazyRadioStatusCallback(const std_msgs::Int32& msg)
+{
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Crazy Radio Status Callback called for agentID = " << m_agentID);
+    setCrazyRadioStatus( msg.data );
+}
+#endif
+
+
+// PRIVATE METHODS FOR SETTING PROPERTIES
+
+void ConnectStartStopBar::setCrazyRadioStatus(int new_radio_status)
+{
+    // add more things whenever the status is changed
+    switch(new_radio_status)
+    {
+        case CRAZY_RADIO_STATE_CONNECTED:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE RADIOSTATUS LABEL
+            //m_rf_status_label_mutex.lock();
+            //ui->rf_status_label->clear();
+            QPixmap rf_connected_pixmap(":/images/rf_connected.png");
+            ui->rf_status_label->setPixmap(rf_connected_pixmap);
+            ui->rf_status_label->setScaledContents(true);
+            //ui->rf_status_label->update();
+            //m_rf_status_label_mutex.unlock();
+
+            // ENABLE THE REMAINDER OF THE GUI
+            if (m_type == TYPE_AGENT)
+            {
+                enableFlyingStateButtons();
+            }
+            break;
+        }
+
+        case CRAZY_RADIO_STATE_CONNECTING:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
+            //m_rf_status_label_mutex.lock();
+            //ui->rf_status_label->clear();
+            QPixmap rf_connecting_pixmap(":/images/rf_connecting.png");
+            ui->rf_status_label->setPixmap(rf_connecting_pixmap);
+            ui->rf_status_label->setScaledContents(true);
+            //ui->rf_status_label->update();
+            //m_rf_status_label_mutex.unlock();
+            break;
+        }
+
+        case CRAZY_RADIO_STATE_DISCONNECTED:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
+            //m_rf_status_label_mutex.lock();
+            //ui->rf_status_label->clear();
+            QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
+            ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
+            ui->rf_status_label->setScaledContents(true);
+            //ui->rf_status_label->update();
+            //m_rf_status_label_mutex.unlock();
+
+            // DISABLE THE REMAINDER OF THE GUI
+            if (m_type == TYPE_AGENT)
+            {
+                disableFlyingStateButtons();
+            }
+            break;
+        }
+
+        default:
+        {
+            break;
+        }
+    }
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
+
+// > For the Battery Voltage
+void ConnectStartStopBar::batteryVoltageCallback(const std_msgs::Float32& msg)
+{
+    //setBatteryVoltageTextAndImage( msg.data );
+    setBatteryVoltageText( msg.data );
+}
+
+
+void ConnectStartStopBar::batteryStateChangedCallback(const std_msgs::Int32& msg)
+{
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Battery State Changed Callback called for agentID = " << m_agentID);
+    setBatteryState( msg.data );
+}
+
+
+void ConnectStartStopBar::batteryLevelCallback(const std_msgs::Int32& msg)
+{
+    setBatteryImageBasedOnLevel( msg.data );
+}
+#endif
+
+
+
+// PRIVATE METHODS FOR SETTING PROPERTIES
+
+// > For updating the battery state
+void ConnectStartStopBar::setBatteryState(int new_battery_state)
+{
+    // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
+    m_battery_state = new_battery_state;
+}
+
+
+
+// > For updating the battery voltage shown in the UI elements of "battery_voltage_lineEdit"
+void ConnectStartStopBar::setBatteryVoltageText(float battery_voltage)
+{
+    // Lock the mutex
+    //m_battery_voltage_lineEdit_mutex.lock();
+    // Construct the text string
+    QString qstr = "";
+    if (battery_voltage >= 0.0f)
+    {
+        qstr.append(QString::number(battery_voltage, 'f', 2));
+    }
+    else
+    {
+        qstr.append("-.--");
+    }
+    qstr.append(" V");
+    // Set the text to the battery voltage line edit
+    ui->battery_voltage_lineEdit->setText(qstr);
+    // Unlock the mutex
+    //m_battery_voltage_lineEdit_mutex.unlock();
+}
+
+
+
+// > For updating the battery image shown in the UI element of "battery_status_label"
+void ConnectStartStopBar::setBatteryImageBasedOnLevel(int battery_level)
+{
+    // COMPUTE THE BATTERY VOLTAGE AS A PERCENTAGE
+    //float battery_voltage_percentage = fromVoltageToPercent(battery_voltage);
+
+    // CONVERT THE VOLTAGE LEVEL TO AN INDEX OF WHICH BATTERY LEVEL IMAGE TO DISPLAY
+    // > Initialise a local variable that will be set in the switch case below
+    int new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
+    // > Initialise a local variable for the string of which image to use
+    QString qstr_new_image = "";
+    qstr_new_image.append(":/images/");
+    
+    // Fill in these two local variables accordingly
+    switch(battery_level)
+    {
+        case BATTERY_LEVEL_000:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
+            qstr_new_image.append("battery_empty.png");
+            break;
+        }
+        case BATTERY_LEVEL_010:
+        case BATTERY_LEVEL_020:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_20;
+            qstr_new_image.append("battery_20.png");
+            break;
+        }
+        case BATTERY_LEVEL_030:
+        case BATTERY_LEVEL_040:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_40;
+            qstr_new_image.append("battery_40.png");
+            break;
+        }
+        case BATTERY_LEVEL_050:
+        case BATTERY_LEVEL_060:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_60;
+            qstr_new_image.append("battery_60.png");
+            break;
+        }
+        case BATTERY_LEVEL_070:
+        case BATTERY_LEVEL_080:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_80;
+            qstr_new_image.append("battery_80.png");
+            break;
+        }
+        case BATTERY_LEVEL_090:
+        case BATTERY_LEVEL_100:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_FULL;
+            qstr_new_image.append("battery_full.png");
+            break;
+        }
+        case BATTERY_LEVEL_UNAVAILABLE:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE;
+            qstr_new_image.append("battery_unknown.png");
+            break;
+        }
+        default:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
+            qstr_new_image.append("battery_unknown.png");
+            break;
+        }
+    }
+    // UPDATE THE IMAGE DISPLAYED BASED ON THE "new index"
+    // > Only if it is different from the current index
+    m_battery_status_label_mutex.lock();
+    if (m_battery_status_label_image_current_index != new_image_index)
+    {
+        // SET THE IMAGE FOR THE BATTERY STATUS LABEL
+        ui->battery_status_label->clear();
+        QPixmap battery_image_pixmap(qstr_new_image);
+        ui->battery_status_label->setPixmap(battery_image_pixmap);
+        ui->battery_status_label->setScaledContents(true);
+        m_battery_status_label_image_current_index = new_image_index;
+        ui->battery_status_label->update();
+    }
+    m_battery_status_label_mutex.unlock();
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  L      Y   Y  III   GGGG      SSSS  TTTTT    A    TTTTT  EEEE
+//    F      L       Y Y    I   G         S        T     A A     T    E
+//    FFF    L        Y     I   G          SSS     T    A   A    T    EEE
+//    F      L        Y     I   G   G         S    T    AAAAA    T    E
+//    F      LLLLL    Y    III   GGGG     SSSS     T    A   A    T    EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+// RESPONDING TO CHANGES IN THE FLYING STATE
+#ifdef CATKIN_MAKE
+void ConnectStartStopBar::flyingStateChangedCallback(const std_msgs::Int32& msg)
+{
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Flying State Changed Callback called for agentID = " << m_agentID);
+    setFlyingState(msg.data);
+}
+#endif
+
+void ConnectStartStopBar::setFlyingState(int new_flying_state)
+{
+    // UPDATE THE LABEL TO DISPLAY THE FLYING STATE
+    switch(new_flying_state)
+    {
+        case STATE_MOTORS_OFF:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_off_pixmap(":/images/flying_state_off.png");
+            ui->flying_state_label->setPixmap(flying_state_off_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
+        case STATE_TAKE_OFF:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_enabling_pixmap(":/images/flying_state_enabling.png");
+            ui->flying_state_label->setPixmap(flying_state_enabling_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
+        case STATE_FLYING:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_flying_pixmap(":/images/flying_state_flying.png");
+            ui->flying_state_label->setPixmap(flying_state_flying_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
+        case STATE_LAND:
+        {
+            //qstr.append("Land");
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_disabling_pixmap(":/images/flying_state_disabling.png");
+            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
+        default:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_unknown_pixmap(":/images/flying_state_unknown.png");
+            ui->flying_state_label->setPixmap(flying_state_unknown_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+    }
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
+//    B   B  U   U    T      T    O   O  NN  N  S
+//    BBBB   U   U    T      T    O   O  N N N   SSS
+//    B   B  U   U    T      T    O   O  N  NN      S
+//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+void ConnectStartStopBar::on_rf_connect_button_clicked()
+{
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_RECONNECT;
+    this->crazyRadioCommandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+}
+
 void ConnectStartStopBar::on_rf_disconnect_button_clicked()
 {
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_DISCONNECT;
+    this->crazyRadioCommandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+}
+
+void ConnectStartStopBar::on_enable_flying_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_CRAZYFLY_TAKE_OFF;
+    this->flyingStateCommandPublisher.publish(msg);
+#endif
+}
+
+void ConnectStartStopBar::on_disable_flying_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_CRAZYFLY_LAND;
+    this->flyingStateCommandPublisher.publish(msg);
+#endif
+}
+
+void ConnectStartStopBar::on_motors_off_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_CRAZYFLY_MOTORS_OFF;
+    this->flyingStateCommandPublisher.publish(msg);
+#endif
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the head for a message
+void ConnectStartStopBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            msg.shouldCheckForID = true;
+            msg.agentIDs.push_back(7);
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForID = true;
+            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool ConnectStartStopBar::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[CONNECT START STOP GUI BAR] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[CONNECT START STOP GUI BAR] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
 
+    // Return
+    return return_was_successful;
 }
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
index be2efe66..6c8419a1 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
@@ -94,12 +94,13 @@ void Coordinator::on_refresh_button_clicked()
         vector_of_coordinatorRows.append(temp_coordinatorRow);
 
         ui->coordinated_agents_scrollAreaWidgetContents->layout()->addWidget(temp_coordinatorRow);
-
-        // Call the function that applies this level
-        // of detail to all the entries
-        apply_level_of_detail_to_all_entries(level_of_detail_to_display);
     }
 #endif
+
+    
+    // Call the function that applies this level
+    // of detail to all the entries
+    apply_level_of_detail_to_all_entries(level_of_detail_to_display);
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index bffcaafe..31a0e1a4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -30,9 +30,16 @@
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #include "coordinatorrow.h"
 #include "ui_coordinatorrow.h"
 
+
+
+
+
 CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     QWidget(parent),
     ui(new Ui::CoordinatorRow),
@@ -60,32 +67,28 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     std::string ros_base_namespace = qstr_ros_base_namespace.toStdString();
 
     // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
-    // > For keeping track of the current RF Crazyradio state
-    my_radio_status = CONNECTED;
     // > For keeping track of the current battery state
-    my_battery_state = BATTERY_STATE_NORMAL;
+    m_battery_state = BATTERY_STATE_NORMAL;
     // > For keeping track of which image is currently displayed
-    my_battery_status_label_image_current_index = -999;
-    // > For keeping track of the current operating state
-    my_flying_state = STATE_MOTORS_OFF;
-
-    // FOR BATTERY VOLTAGE LIMITS (THESE SHOULD BE READ IN AS PARAMTERS)
-    // > When in a "standby" type of state
-    battery_voltage_standby_empty  =  3.30f;
-    battery_voltage_standby_full   =  4.20f;
-    // > When in a "flying" type of state
-    battery_voltage_flying_empty   =  2.60f;
-    battery_voltage_flying_full    =  3.70f;
+    m_battery_status_label_image_current_index = -999;
+
 
     // SET THE STARTING RADIO STATUS TO BE: DISCONNECTED
-    // > this also updates the image for the "rf_status_label", "battery_voltage_lineEdit", and "battery_status_label"
-    setCrazyRadioStatus(DISCONNECTED);
+    setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+
+    // SET THE STARTING BATTERY VOLTAGE TO BE: UNKNOWN
+    setBatteryVoltageText(-1.0f);
+
+    // SET THE STARTING BATTERY LEVEL TO BE: UNAVAILABLE
+    setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
+    
     // SET THE STARTING FLYING STATE STATUS TO BE: MOTORS OFF
-    // > this also updates the image for the "flying_state_label"
     setFlyingState(CMD_CRAZYFLY_MOTORS_OFF);
+    
     // SET THE DEFAULT NAME FOR THE SELECTED CONTROLLER
     setControllerEnabled(SAFE_CONTROLLER);
 
+
 #ifdef CATKIN_MAKE
     //m_rosNodeThread = new rosNodeThread(argc, argv, "coordinatorRowGUI");
     //m_rosNodeThread->init();
@@ -103,11 +106,11 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
 
 
     // LET THE USER KNOW WHAT THE BASE NAMESPACE IS
-    ROS_INFO_STREAM("[Coordinator Row GUI] using base namespace: " << ros_base_namespace.c_str() << ", for agentID = " << m_agentID);
+    ROS_INFO_STREAM("[COORDINATOR ROW GUI] using base namespace: " << ros_base_namespace.c_str() << ", for agentID = " << m_agentID);
 
     // DEBUGGING FOR NAMESPACES
     //std::string temp_ros_namespace = ros::this_node::getNamespace();
-    //ROS_INFO_STREAM("[Coordinator Row GUI] compared to: ros::this_node::getNamespace() = " << temp_ros_namespace.c_str());
+    //ROS_INFO_STREAM("[COORDINATOR ROW GUI] compared to: ros::this_node::getNamespace() = " << temp_ros_namespace.c_str());
 
     // CREATE A NODE HANDLE TO THE BASE NAMESPACE
     ros::NodeHandle base_nodeHandle(ros_base_namespace);
@@ -117,19 +120,21 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
 
     // SUBSCRIBERS AND PUBLISHERS:
     // > For Crazyradio commands based on button clicks
-    crazyRadioCommandPublisher = base_nodeHandle.advertise<std_msgs::Int32>("PPSClient/crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
     // > For updating the "rf_status_label" picture
     crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &CoordinatorRow::crazyRadioStatusCallback, this);
     // > For updating the current battery voltage
-    batteryVoltageSubscriber = base_nodeHandle.subscribe("CrazyRadio/CFBattery", 1, &CoordinatorRow::batteryVoltageCallback, this);
+    batteryVoltageSubscriber = base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &CoordinatorRow::batteryVoltageCallback, this);
     // > For updating the current battery state
-    batteryStateSubscriber = base_nodeHandle.subscribe("PPSClient/batteryState", 1, &CoordinatorRow::batteryStateChangedCallback, this);
+    //batteryStateSubscriber = base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &CoordinatorRow::batteryStateChangedCallback, this);
+    // > For updating the current battery level
+    batteryLevelSubscriber = base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &CoordinatorRow::batteryLevelCallback, this);
     // > For Flying state commands based on button clicks
     flyingStateCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
     // > For updating the "flying_state_label" picture
     flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/flyingState", 1, &CoordinatorRow::flyingStateChangedCallback, this);
     // > For changes in the database that defines {agentID,cfID,flying zone} links
-    databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("/my_GUI/DBChanged", 1, &CoordinatorRow::databaseChangedCallback, this);;
+    databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &CoordinatorRow::databaseChangedCallback, this);;
     centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
     // > For updating the controller that is currently operating
     controllerUsedSubscriber = base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
@@ -242,13 +247,23 @@ void CoordinatorRow::enableFlyingStateButtons()
 
 
 
+//    ----------------------------------------------------------------------------------
+//     CCCC  RRRR     A    ZZZZZ  Y   Y  RRRR     A    DDDD   III   OOO
+//    C      R   R   A A      Z    Y Y   R   R   A A   D   D   I   O   O
+//    C      RRRR   A   A    Z      Y    RRRR   A   A  D   D   I   O   O
+//    C      R   R  AAAAA   Z       Y    R   R  AAAAA  D   D   I   O   O
+//     CCCC  R   R  A   A  ZZZZZ    Y    R   R  A   A  DDDD   III   OOO
+//    ----------------------------------------------------------------------------------
+
+
+
 #ifdef CATKIN_MAKE
 // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
 
 // > For the Battery Voltage
 void CoordinatorRow::crazyRadioStatusCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Crazy Radio Status Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Crazy Radio Status Callback called for agentID = " << m_agentID);
     setCrazyRadioStatus( msg.data );
 }
 #endif
@@ -261,69 +276,46 @@ void CoordinatorRow::setCrazyRadioStatus(int new_radio_status)
     // add more things whenever the status is changed
     switch(new_radio_status)
     {
-        case CONNECTED:
+        case CRAZY_RADIO_STATE_CONNECTED:
         {
             // SET THE APPROPRIATE IMAGE FOR THE RADIOSTATUS LABEL
-            my_rf_status_label_mutex.lock();
+            //m_rf_status_label_mutex.lock();
             //ui->rf_status_label->clear();
             QPixmap rf_connected_pixmap(":/images/rf_connected.png");
             ui->rf_status_label->setPixmap(rf_connected_pixmap);
             ui->rf_status_label->setScaledContents(true);
             //ui->rf_status_label->update();
-            my_rf_status_label_mutex.unlock();
-            // ENABLE THE REMAINDER OF THE GUI
-            my_battery_state_mutex.lock();
-            if (my_battery_state == BATTERY_STATE_NORMAL)
-            {
-                enableFlyingStateButtons();
-            }
-            my_battery_state_mutex.unlock();
+            //m_rf_status_label_mutex.unlock();
 
+            // ENABLE THE REMAINDER OF THE GUI
+            enableFlyingStateButtons();
             break;
         }
 
-        case CONNECTING:
+        case CRAZY_RADIO_STATE_CONNECTING:
         {
             // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
-            my_rf_status_label_mutex.lock();
+            //m_rf_status_label_mutex.lock();
             //ui->rf_status_label->clear();
             QPixmap rf_connecting_pixmap(":/images/rf_connecting.png");
             ui->rf_status_label->setPixmap(rf_connecting_pixmap);
             ui->rf_status_label->setScaledContents(true);
             //ui->rf_status_label->update();
-            my_rf_status_label_mutex.unlock();
+            //m_rf_status_label_mutex.unlock();
             break;
         }
 
-        case DISCONNECTED:
+        case CRAZY_RADIO_STATE_DISCONNECTED:
         {
             // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
-            my_rf_status_label_mutex.lock();
+            //m_rf_status_label_mutex.lock();
             //ui->rf_status_label->clear();
             QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
             ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
             ui->rf_status_label->setScaledContents(true);
             //ui->rf_status_label->update();
-            my_rf_status_label_mutex.unlock();
-            // SET THE BATTERY VOLTAGE FIELD TO BE BLANK
-            QString qstr = "-.-- V";
-            my_battery_voltage_lineEdit_mutex.lock();
-            ui->battery_voltage_lineEdit->setText(qstr);
-            my_battery_voltage_lineEdit_mutex.unlock();
-            // SET THE APPROPRIATE IMAGE FOR THE BATTERY STATUS LABEL
-            // > Lock the mutex for accessing both "my_battery_status_label_image_current_index"
-            //   and "ui->battery_status_label"
-            my_battery_status_label_mutex.lock();
-            if (my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_UNKNOWN)
-            {
-                ui->battery_status_label->clear();
-                QPixmap battery_unknown_pixmap(":/images/battery_unknown.png");
-                ui->battery_status_label->setPixmap(battery_unknown_pixmap);
-                ui->battery_status_label->setScaledContents(true);
-                my_battery_status_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
-                ui->battery_status_label->update();
-            }
-            my_battery_status_label_mutex.unlock();
+            //m_rf_status_label_mutex.unlock();
+
             // DISABLE THE REMAINDER OF THE GUI
             disableFlyingStateButtons();
             break;
@@ -334,26 +326,44 @@ void CoordinatorRow::setCrazyRadioStatus(int new_radio_status)
             break;
         }
     }
-    my_radio_status = new_radio_status;
 }
 
 
 
+
+
+//    ----------------------------------------------------------------------------------
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
+//    ----------------------------------------------------------------------------------
+
+
+
 #ifdef CATKIN_MAKE
 // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
 
 // > For the Battery Voltage
 void CoordinatorRow::batteryVoltageCallback(const std_msgs::Float32& msg)
 {
-    setBatteryVoltageTextAndImage( msg.data );
+    //setBatteryVoltageTextAndImage( msg.data );
+    setBatteryVoltageText( msg.data );
 }
 
 
 void CoordinatorRow::batteryStateChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Battery State Changed Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Battery State Changed Callback called for agentID = " << m_agentID);
     setBatteryState( msg.data );
 }
+
+
+void CoordinatorRow::batteryLevelCallback(const std_msgs::Int32& msg)
+{
+    setBatteryImageBasedOnLevel( msg.data );
+}
 #endif
 
 
@@ -363,214 +373,133 @@ void CoordinatorRow::batteryStateChangedCallback(const std_msgs::Int32& msg)
 // > For updating the battery state
 void CoordinatorRow::setBatteryState(int new_battery_state)
 {
-    // LOCK THE MUTEX FOR THE WHOLE SWITCH CASE STATEMENT
-    my_battery_state_mutex.lock();
-    // Switch depending the the new battery state provided
-    switch(new_battery_state)
-    {
-        case BATTERY_STATE_LOW:
-        {
-            // MAKE UNAVAILABLE THE BUTTONS FOR ENABLING AND DISABLING FLIGHT
-            disableFlyingStateButtons();
-
-            // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
-            my_battery_state = BATTERY_STATE_LOW;
-            break;
-        }
-
-        case BATTERY_STATE_NORMAL:
-        {
-            // MAKE UNAVAILABLE THE BUTTONS FOR ENABLING AND DISABLING FLIGHT
-            enableFlyingStateButtons();
-
-            // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
-            my_battery_state = BATTERY_STATE_NORMAL;
-            break;
-        }
-
-        default:
-            break;
-    }
-    // UNLOCK THE MUTEX
-    my_battery_state_mutex.unlock();
+    // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
+    m_battery_state = new_battery_state;
 }
 
-// > For the battery voltage label and image
-void CoordinatorRow::setBatteryVoltageTextAndImage(float battery_voltage)
-{
-    setBatteryVoltageText( battery_voltage );
-    setBatteryVoltageImage( battery_voltage );
-}
+
 
 // > For updating the battery voltage shown in the UI elements of "battery_voltage_lineEdit"
 void CoordinatorRow::setBatteryVoltageText(float battery_voltage)
 {
     // Lock the mutex
-    my_battery_voltage_lineEdit_mutex.lock();
+    //m_battery_voltage_lineEdit_mutex.lock();
     // Construct the text string
     QString qstr = "";
-    qstr.append(QString::number(battery_voltage, 'f', 2));
+    if (battery_voltage >= 0.0f)
+    {
+        qstr.append(QString::number(battery_voltage, 'f', 2));
+    }
+    else
+    {
+        qstr.append("-.--");
+    }
     qstr.append(" V");
     // Set the text to the battery voltage line edit
     ui->battery_voltage_lineEdit->setText(qstr);
     // Unlock the mutex
-    my_battery_voltage_lineEdit_mutex.unlock();
+    //m_battery_voltage_lineEdit_mutex.unlock();
 }
 
-// > For updating the battery voltage shown in the UI elements of "battery_status_label"
-void CoordinatorRow::setBatteryVoltageImage(float battery_voltage)
+
+
+// > For updating the battery image shown in the UI element of "battery_status_label"
+void CoordinatorRow::setBatteryImageBasedOnLevel(int battery_level)
 {
     // COMPUTE THE BATTERY VOLTAGE AS A PERCENTAGE
-    float battery_voltage_percentage = fromVoltageToPercent(battery_voltage);
+    //float battery_voltage_percentage = fromVoltageToPercent(battery_voltage);
 
-    // CONVERT THE VOLTAGE PERCENTAGE TO AN INDEX OF WHICH BATTERY LEVEL IMAGE TO DISPLAY
+    // CONVERT THE VOLTAGE LEVEL TO AN INDEX OF WHICH BATTERY LEVEL IMAGE TO DISPLAY
     // > Initialise a local variable that will be set in the switch case below
-    int new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
+    int new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
     // > Initialise a local variable for the string of which image to use
     QString qstr_new_image = "";
     qstr_new_image.append(":/images/");
-    // > Get the value of the "my_battery_state" variable into a local variable
-    my_battery_state_mutex.lock();
-    int local_copy_of_my_battery_state = my_battery_state;
-    my_battery_state_mutex.unlock();
-    // > Switch based on the current battery state, first locking the mutex for accessing
-    //   both "my_battery_status_label_image_current_index" and "ui->battery_status_label"
-    my_battery_status_label_mutex.lock();
-    switch(local_copy_of_my_battery_state)
+    
+    // Fill in these two local variables accordingly
+    switch(battery_level)
     {
-        // WHEN THE BATTERY IS IN A LOW STATE
-        case BATTERY_STATE_LOW:
+        case BATTERY_LEVEL_000:
         {
-            new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
             qstr_new_image.append("battery_empty.png");
             break;
         }
-
-        // WHEN THE BATTERY IS IN A NORMAL STATE
-        case BATTERY_STATE_NORMAL:
+        case BATTERY_LEVEL_010:
+        case BATTERY_LEVEL_020:
         {
-
-            if (
-                ((my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_EMPTY) && (battery_voltage_percentage <= 0.0f))
-                ||
-                ((my_battery_status_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_EMPTY) && (battery_voltage_percentage <= 2.0f))
-            )
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
-                qstr_new_image.append("battery_empty.png");
-            }
-            else if (
-                ((my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_20) && (battery_voltage_percentage <= 20.0f))
-                ||
-                ((my_battery_status_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_20) && (battery_voltage_percentage <= 22.0f))
-            )
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_20;
-                qstr_new_image.append("battery_20.png");
-            }
-            else if (
-                ((my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_40) && (battery_voltage_percentage <= 40.0f))
-                ||
-                ((my_battery_status_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_40) && (battery_voltage_percentage <= 42.0f))
-            )
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_40;
-                qstr_new_image.append("battery_40.png");
-            }
-            else if (
-                ((my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_60) && (battery_voltage_percentage <= 60.0f))
-                ||
-                ((my_battery_status_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_60) && (battery_voltage_percentage <= 62.0f))
-            )
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_60;
-                qstr_new_image.append("battery_60.png");
-            }
-            else if (
-                ((my_battery_status_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_80) && (battery_voltage_percentage <= 80.0f))
-                ||
-                ((my_battery_status_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_80) && (battery_voltage_percentage <= 82.0f))
-            )
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_80;
-                qstr_new_image.append("battery_80.png");
-            }
-            else
-            {
-                new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_FULL;
-                qstr_new_image.append("battery_full.png");
-            }
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_20;
+            qstr_new_image.append("battery_20.png");
+            break;
+        }
+        case BATTERY_LEVEL_030:
+        case BATTERY_LEVEL_040:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_40;
+            qstr_new_image.append("battery_40.png");
+            break;
+        }
+        case BATTERY_LEVEL_050:
+        case BATTERY_LEVEL_060:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_60;
+            qstr_new_image.append("battery_60.png");
+            break;
+        }
+        case BATTERY_LEVEL_070:
+        case BATTERY_LEVEL_080:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_80;
+            qstr_new_image.append("battery_80.png");
+            break;
+        }
+        case BATTERY_LEVEL_090:
+        case BATTERY_LEVEL_100:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_FULL;
+            qstr_new_image.append("battery_full.png");
+            break;
+        }
+        case BATTERY_LEVEL_UNAVAILABLE:
+        {
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE;
+            qstr_new_image.append("battery_unknown.png");
             break;
         }
-
         default:
         {
-            new_battery_label_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
+            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
             qstr_new_image.append("battery_unknown.png");
             break;
         }
     }
     // UPDATE THE IMAGE DISPLAYED BASED ON THE "new index"
     // > Only if it is different from the current index
-    if (my_battery_status_label_image_current_index != new_battery_label_image_index)
+    m_battery_status_label_mutex.lock();
+    if (m_battery_status_label_image_current_index != new_image_index)
     {
         // SET THE IMAGE FOR THE BATTERY STATUS LABEL
         ui->battery_status_label->clear();
         QPixmap battery_image_pixmap(qstr_new_image);
         ui->battery_status_label->setPixmap(battery_image_pixmap);
         ui->battery_status_label->setScaledContents(true);
-        my_battery_status_label_image_current_index = new_battery_label_image_index;
+        m_battery_status_label_image_current_index = new_image_index;
         ui->battery_status_label->update();
     }
-    // Finally unlock the mutex
-    my_battery_status_label_mutex.unlock();
+    m_battery_status_label_mutex.unlock();
 }
 
 
-// > For converting a voltage to a percentage, depending on the current "my_flying_state" value
-float CoordinatorRow::fromVoltageToPercent(float voltage)
-{
-    // INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
-    float voltage_when_full;
-    float voltage_when_empty;
-
-    // COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
-    // THE CURRENT FLYING STATE
-    // > First lock the mutex before accessing the "my_flying_state" variable
-    my_flying_state_mutex.lock();
-    if (my_flying_state == STATE_MOTORS_OFF)
-    {
-        // Voltage limits for a "standby" type of state
-        voltage_when_empty = battery_voltage_standby_empty;
-        voltage_when_full  = battery_voltage_standby_full;
-    }
-    else
-    {
-        // Voltage limits for a "flying" type of state
-        voltage_when_empty = battery_voltage_flying_empty;
-        voltage_when_full  = battery_voltage_flying_full;
-    }
-    // > Unlock the mutex
-    my_flying_state_mutex.unlock();
 
-    // COMPUTE THE PERCENTAGE
-    float percentage = 100.0f * (voltage-voltage_when_empty)/(voltage_when_full-voltage_when_empty);
 
-    // CLIP THE PERCENTAGE TO BE BETWEEN [0,100]
-    // > This should not happen to often
-    if(percentage > 100.0f)
-    {
-        percentage = 100.0f;
-    }
-    if(percentage < 0.0f)
-    {
-        percentage = 0.0f;
-    }
-
-    // RETURN THE PERCENTAGE
-    return percentage;
-}
 
+//    ----------------------------------------------------------------------------------
+//    FFFFF  L      Y   Y  III   GGGG      SSSS  TTTTT    A    TTTTT  EEEE
+//    F      L       Y Y    I   G         S        T     A A     T    E
+//    FFF    L        Y     I   G          SSS     T    A   A    T    EEE
+//    F      L        Y     I   G   G         S    T    AAAAA    T    E
+//    F      LLLLL    Y    III   GGGG     SSSS     T    A   A    T    EEEEE
+//    ----------------------------------------------------------------------------------
 
 
 
@@ -578,18 +507,13 @@ float CoordinatorRow::fromVoltageToPercent(float voltage)
 #ifdef CATKIN_MAKE
 void CoordinatorRow::flyingStateChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Flying State Changed Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Flying State Changed Callback called for agentID = " << m_agentID);
     setFlyingState(msg.data);
 }
 #endif
 
 void CoordinatorRow::setFlyingState(int new_flying_state)
 {
-    // PUT THE CURRENT STATE INTO THE CLASS VARIABLE
-    my_flying_state_mutex.lock();
-    my_flying_state = new_flying_state;
-    my_flying_state_mutex.unlock();
-
     // UPDATE THE LABEL TO DISPLAY THE FLYING STATE
     switch(new_flying_state)
     {
@@ -642,12 +566,18 @@ void CoordinatorRow::setFlyingState(int new_flying_state)
 }
 
 
+
+
+
+
+
+
 // RESPONDING TO CHANGES IN THE DATABASE
 #ifdef CATKIN_MAKE
 // > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
 void CoordinatorRow::databaseChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Database Changed Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Database Changed Callback called for agentID = " << m_agentID);
     loadCrazyflieContext();
 }
 #endif
@@ -666,13 +596,13 @@ void CoordinatorRow::loadCrazyflieContext()
     if(centralManagerDatabaseService.call(contextCall))
     {
         my_context = contextCall.response.crazyflieContext;
-        ROS_INFO_STREAM("[Coordinator Row GUI] CrazyflieContext:\n" << my_context);
+        ROS_INFO_STREAM("[COORDINATOR ROW GUI] CrazyflieContext:\n" << my_context);
 
         qstr_crazyflie_name.append(QString::fromStdString(my_context.crazyflieName));
     }
     else
     {
-        ROS_ERROR_STREAM("[Coordinator Row GUI] Failed to load context for agentID = " << m_agentID);
+        ROS_ERROR_STREAM("[COORDINATOR ROW GUI] Failed to load context for agentID = " << m_agentID);
     }
     // This updating of the radio only needs to be done by the actual agent's node
     //ros::NodeHandle nh("CrazyRadio");
@@ -698,7 +628,7 @@ void CoordinatorRow::loadCrazyflieContext()
 // > For the controller currently operating, received on "controllerUsedSubscriber"
 void CoordinatorRow::controllerUsedChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[Coordinator Row GUI] Controller Used Changed Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Controller Used Changed Callback called for agentID = " << m_agentID);
     setControllerEnabled(msg.data);
 }
 #endif
@@ -749,30 +679,39 @@ void CoordinatorRow::setControllerEnabled(int new_controller)
 
 
 
-//    ------------------------------------------------------------------- //
-// # RF Crazyradio Connect Disconnect
+
+//    ----------------------------------------------------------------------------------
+//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
+//    B   B  U   U    T      T    O   O  NN  N  S
+//    BBBB   U   U    T      T    O   O  N N N   SSS
+//    B   B  U   U    T      T    O   O  N  NN      S
+//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
 void CoordinatorRow::on_rf_connect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckForID = false;
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[FLYING AGENT GUI] Command to RF reconnect published");
+    ROS_INFO("[COORDINATOR ROW GUI] Command to RF reconnect published");
 #endif
 }
 
 void CoordinatorRow::on_rf_disconnect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    std_msgs::Int32 msg;
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckForID = false;
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[FLYING AGENT GUI] Command to RF disconnect published");
+    ROS_INFO("[COORDINATOR ROW GUI] Command to RF disconnect published");
 #endif
 }
 
-//    ------------------------------------------------------------------- //
-// # Take off, land, motors off
 void CoordinatorRow::on_enable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 14df7d63..94f26a33 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -13,7 +13,7 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
 
     // Get the namespace of this node
     std::string this_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[FLYING AGENT GUI] ros::this_node::getNamespace() =  " << this_namespace);
+    ROS_INFO_STREAM("[ENABLE CONTROLLER LOAD YAML GUI BAR] ros::this_node::getNamespace() =  " << this_namespace);
 
     // Get the type and ID of this flying agent GUI
     bool isValid_type_and_ID = getTypeAndIDParameters();
@@ -21,7 +21,7 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
     // Stall if the node IDs are not valid
     if ( !isValid_type_and_ID )
     {
-        ROS_ERROR("[FLYING AGENT GUI] Node NOT FUNCTIONING :-)");
+        ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Node NOT FUNCTIONING :-)");
         ros::spin();
     }
 
@@ -52,7 +52,7 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_SAFE_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[FLYING AGENT GUI] Enable Safe Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
 #endif
 }
 
@@ -63,7 +63,7 @@ void EnableControllerLoadYamlBar::on_enable_demo_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_DEMO_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[FLYING AGENT GUI] Enable Demo Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Demo Controller");
 #endif
 }
 
@@ -74,7 +74,7 @@ void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_STUDENT_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[FLYING AGENT GUI] Enable Student Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Student Controller");
 #endif
 }
 
@@ -107,6 +107,19 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 }
 
 
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
 #ifdef CATKIN_MAKE
 // Fill the head for a message
 void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg )
@@ -128,7 +141,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade
         default:
         {
             msg.shouldCheckForID = true;
-            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
+            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
             break;
         }
     } 
@@ -136,6 +149,20 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade
 #endif
 
 
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
 #ifdef CATKIN_MAKE
 bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
 {
@@ -151,7 +178,7 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
     if(!nodeHandle.getParam("type", type_string))
     {
         // Throw an error if the agent ID parameter could not be obtained
-        ROS_ERROR("[FLYING AGENT GUI] Failed to get type");
+        ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get type");
     }
 
     // Set the "m_type" class variable based on this string loaded
@@ -168,7 +195,7 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
         // Set "m_type" to the value indicating that it is invlid
         m_type = TYPE_INVALID;
         return_was_successful = false;
-        ROS_ERROR("[FLYING AGENT GUI] The 'type' parameter retrieved was not recognised.");
+        ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'type' parameter retrieved was not recognised.");
     }
 
 
@@ -182,12 +209,12 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
             {
                 // Throw an error if the agent ID parameter could not be obtained
                 return_was_successful = false;
-                ROS_ERROR("[FLYING AGENT GUI] Failed to get agentID");
+                ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get agentID");
             }
             else
             {
                 // Inform the user about the type and ID
-                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type AGENT with ID = " << m_ID);
+                ROS_INFO_STREAM("[ENABLE CONTROLLER LOAD YAML GUI BAR] Is of type AGENT with ID = " << m_ID);
             }
             break;
         }
@@ -201,12 +228,12 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
             {
                 // Throw an error if the coord ID parameter could not be obtained
                 return_was_successful = false;
-                ROS_ERROR("[FLYING AGENT GUI] Failed to get coordID");
+                ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get coordID");
             }
             else
             {
                 // Inform the user about the type and ID
-                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type COORDINATOR with ID = " << m_ID);
+                ROS_INFO_STREAM("[ENABLE CONTROLLER LOAD YAML GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
             }
             break;
         }
@@ -215,7 +242,7 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
         {
             // Throw an error if the type is not recognised
             return_was_successful = false;
-            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
+            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
             break;
         }
     }
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index a0e08224..3d839967 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -51,89 +51,32 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     m_close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close()));
 
 #ifdef CATKIN_MAKE
-    // 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 value of the "type" parameter into a local string variable
-    std::string type_string;
-    if(!nodeHandle.getParam("type", type_string))
-    {
-        // Throw an error if the agent ID parameter could not be obtained
-        ROS_ERROR("[FLYING AGENT GUI] Failed to get type");
-    }
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[FLYING AGENT GUI MAIN WINDOW] ros::this_node::getNamespace() =  " << this_namespace);
 
 
-    // Set the "m_type" class variable based on this string loaded
-    if ((!type_string.compare("coordinator")))
-    {
-        m_type = TYPE_COORDINATOR;
-    }
-    else if ((!type_string.compare("agent")))
-    {
-        m_type = TYPE_AGENT;
-    }
-    else
-    {
-        // Set "m_type" to the value indicating that it is invlid
-        m_type = TYPE_INVALID;
-        ROS_ERROR("[FLYING AGENT GUI] The 'type' parameter retrieved was not recognised.");
-    }
-
+    // Get the type and ID of this parameter service
+    bool isValid_type_and_ID = getTypeAndIDParameters();
 
-    // Construct the string to the namespace of this Paramater Service
-    switch (m_type)
+    // Stall if the TYPE and ID are not valid
+    if ( !isValid_type_and_ID )
     {
-        case TYPE_AGENT:
-        {
-            // Get the value of the "agentID" parameter into the class variable "m_Id"
-            if(!nodeHandle.getParam("agentID", m_ID))
-            {
-                // Throw an error if the agent ID parameter could not be obtained
-                ROS_ERROR("[FLYING AGENT GUI] Failed to get agentID");
-            }
-            else
-            {
-                // Inform the user about the type and ID
-                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type AGENT with ID = " << m_ID);
-            }
-            break;
-        }
-
-        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
-        // > The master GUI
-        case TYPE_COORDINATOR:
-        {
-            // Get the value of the "coordID" parameter into the class variable "m_Id"
-            if(!nodeHandle.getParam("coordID", m_ID))
-            {
-                // Throw an error if the coord ID parameter could not be obtained
-                ROS_ERROR("[FLYING AGENT GUI] Failed to get coordID");
-            }
-            else
-            {
-                // Inform the user about the type and ID
-                ROS_INFO_STREAM("[FLYING AGENT GUI] Is of type COORDINATOR with ID = " << m_ID);
-            }
-            break;
-        }
-
-        default:
-        {
-            // Throw an error if the type is not recognised
-            ROS_ERROR("[FLYING AGENT GUI] The 'm_type' variable was not recognised.");
-            break;
-        }
+        ROS_ERROR("[FLYING AGENT GUI MAIN WINDOW] Node NOT FUNCTIONING :-)");
+        ros::spin();
     }
-
-
+    
+    // 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 "ParameterService" node
     std::string this_node_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[FLYING AGENT GUI] ros::this_node::getNamespace() =  " << this_node_namespace);
+    ROS_INFO_STREAM("[FLYING AGENT GUI MAIN WINDOW] ros::this_node::getNamespace() =  " << this_node_namespace);
 
     // Construct the string to the namespace of this Paramater Service
     m_parameter_service_namespace = this_node_namespace + '/' + "ParameterService";
-    ROS_INFO_STREAM("[FLYING AGENT GUI] parameter service is: " << m_parameter_service_namespace);
+    ROS_INFO_STREAM("[FLYING AGENT GUI MAIN WINDOW] parameter service is: " << m_parameter_service_namespace);
 
     // Get the node handle to this parameter service
     ros::NodeHandle nodeHandle_to_parameter_service(m_parameter_service_namespace);
@@ -180,7 +123,7 @@ void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
 {
 #ifdef CATKIN_MAKE
     // Inform the user that the menu item was selected
-    ROS_INFO("[FLYING AGENT GUI] Load Battery Monitor YAML was clicked.");
+    ROS_INFO("[FLYING AGENT GUI MAIN WINDOW] Load Battery Monitor YAML was clicked.");
 
     // Create a local variable for the message
     StringWithHeader yaml_filename_msg;
@@ -198,7 +141,7 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
 {
 #ifdef CATKIN_MAKE
     // Inform the user that the menu item was selected
-    ROS_INFO("[FLYING AGENT GUI] Load Client Config YAML was clicked.");
+    ROS_INFO("[FLYING AGENT GUI MAIN WINDOW] Load Client Config YAML was clicked.");
 
     // Create a local variable for the message
     StringWithHeader yaml_filename_msg;
@@ -210,3 +153,106 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 #endif
 }
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool MainWindow::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[ENABLE CONTROLLER LOAD YAML GUI BAR] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[ENABLE CONTROLLER LOAD YAML GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index d12f08d2..13de6248 100755
--- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -146,7 +146,7 @@ class PPSRadioClient:
         self.change_status_to(DISCONNECTED)
 
     def change_status_to(self, new_status):
-        print "status changed to: %s" % new_status
+        print "[CRAZY RADIO] status changed to: %s" % new_status
         self._status = new_status
         self.status_pub.publish(new_status)
 
@@ -160,13 +160,13 @@ class PPSRadioClient:
         # update link from ros params
         self.update_link_uri()
 
-        print "Connecting to %s" % self.link_uri
+        print "[CRAZY RADIO] Connecting to %s" % self.link_uri
         self.change_status_to(CONNECTING)
-        rospy.loginfo("connecting...")
+        rospy.loginfo("[CRAZY RADIO] connecting...")
         self._cf.open_link(self.link_uri)
 
     def disconnect(self):
-        print "Motors OFF"
+        print "[CRAZY RADIO] sending Motors OFF command before disconnecting"
         self._send_to_commander_motor(0, 0, 0, 0)
         # change state to motors OFF
         msg = IntWithHeader()
@@ -174,7 +174,7 @@ class PPSRadioClient:
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
         self.PPSClient_command_pub.publish(msg)
         time.sleep(0.1)
-        print "Disconnecting from %s" % self.link_uri
+        print "[CRAZY RADIO] Disconnecting from %s" % self.link_uri
         self._cf.close_link()
         self.change_status_to(DISCONNECTED)
 
@@ -200,7 +200,7 @@ class PPSRadioClient:
 
 
     def _logging_error(self, logconf, msg):
-        print "Error when logging %s" % logconf.name
+        print "[CRAZY RADIO] Error when logging %s" % logconf.name
 
     # def _init_logging(self):
 
@@ -215,12 +215,12 @@ class PPSRadioClient:
         if self.logconf.valid:
             self.logconf.data_received_cb.add_callback(self._data_received_callback)
             self.logconf.error_cb.add_callback(self._logging_error)
-            print "logconf valid"
+            print "[CRAZY RADIO] logconf valid"
         else:
-            print "logconf invalid"
+            print "[CRAZY RADIO] logconf invalid"
 
         self.logconf.start()
-        print "logconf start"
+        print "[CRAZY RADIO] logconf start"
 
     def _connected(self, link_uri):
         """
@@ -234,7 +234,7 @@ class PPSRadioClient:
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
         cf_client.PPSClient_command_pub.publish(msg)
 
-        rospy.loginfo("Connection to %s successful: " % link_uri)
+        rospy.loginfo("[CRAZY RADIO] Connection to %s successful: " % link_uri)
         # Config for Logging
         self._start_logging()
 
@@ -245,18 +245,18 @@ class PPSRadioClient:
         """Callback when connection initial connection fails (i.e no Crazyflie
         at the specified address)"""
         self.change_status_to(DISCONNECTED)
-        rospy.logerr("Connection to %s failed: %s" % (link_uri, msg))
+        rospy.logerr("[CRAZY RADIO] Connection to %s failed: %s" % (link_uri, msg))
 
     def _connection_lost(self, link_uri, msg):
         """Callback when disconnected after a connection has been made (i.e
         Crazyflie moves out of range)"""
         self.change_status_to(DISCONNECTED)
-        rospy.logerr("Connection to %s lost: %s" % (link_uri, msg))
+        rospy.logerr("[CRAZY RADIO] Connection to %s lost: %s" % (link_uri, msg))
 
     def _disconnected(self, link_uri):
         """Callback when the Crazyflie is disconnected (called in all cases)"""
         self.change_status_to(DISCONNECTED)
-        rospy.logwarn("Disconnected from %s" % link_uri)
+        rospy.logwarn("[CRAZY RADIO] Disconnected from %s" % link_uri)
 
         # change state to motors OFF
         msg = IntWithHeader()
@@ -295,23 +295,45 @@ class PPSRadioClient:
 
     def crazyRadioCommandCallback(self, msg):
         """Callback to tell CrazyRadio to reconnect"""
-        print "crazyRadio command received %s" % msg.data
-
-        if msg.data == CMD_RECONNECT:            # reconnect, check _status first and then do whatever needs to be done
-            print "entered reconnect"
-            print "_status: %s" % self._status
-            if self.get_status() == DISCONNECTED:
-                print "entered disconnected"
-                self.connect()
-            if self.get_status() == CONNECTED:
-                self.status_pub.publish(CONNECTED)
-
-        elif msg.data == CMD_DISCONNECT:
-            print "disconnect received"
-            if self.get_status() != DISCONNECTED: # what happens if we disconnect while we are in connecting state?
-                self.disconnect()
-            else:
-                self.status_pub.publish(DISCONNECTED)
+
+        print "[CRAZY RADIO]  DEBUGGING received command"
+
+        # Initialise a boolean flag that the command is NOT relevant
+        command_is_relevant = False
+
+        # Check the header details of the message for it relevance
+        if (!msg.shouldCheckForID):
+            command_is_relevant = True
+        else
+            for this_ID in msg.agentIDs:
+                if (this_ID == m_agentID):
+                    command_is_relevant = True
+                    break
+
+        # Only consider the command if it is relevant
+        if (command_is_relevant):
+            #print "[CRAZY RADIO] received command to: %s" % msg.data
+            if msg.data == CMD_RECONNECT:
+                if self.get_status() == DISCONNECTED:
+                    print "[CRAZY RADIO] received command to CONNECT (current status is DISCONNECTED)"
+                    self.connect()
+                elif self.get_status() == CONNECTING:
+                    print "[CRAZY RADIO] received command to CONNECT (current status is CONNECTING)"
+                    #self.status_pub.publish(CONNECTING)
+                elif self.get_status() == CONNECTED:
+                    print "[CRAZY RADIO] received command to CONNECT (current status is CONNECTED)"
+                    #self.status_pub.publish(CONNECTED)
+
+            elif msg.data == CMD_DISCONNECT:
+                if self.get_status() == CONNECTED:
+                    print "[CRAZY RADIO] received command to DISCONNECT (current status is CONNECTED)"
+                    self.disconnect()
+                elif self.get_status() == CONNECTING:
+                    print "[CRAZY RADIO] received command to DISCONNECT (current status is CONNECTING)"
+                    #self.status_pub.publish(CONNECTING)
+                elif self.get_status() == DISCONNECTED:
+                    print "[CRAZY RADIO] received command to DISCONNECT (current status is DISCONNECTED)"
+                    #self.status_pub.publish(DISCONNECTED)
 
 def controlCommandCallback(data):
     """Callback for controller actions"""
@@ -333,12 +355,17 @@ def controlCommandCallback(data):
 
 
 if __name__ == '__main__':
+
+    # Starting the ROS-node
     global node_name
     node_name = "CrazyRadio"
     rospy.init_node(node_name, anonymous=True)
 
+    # Get the namespace of this node
     global ros_namespace
     ros_namespace = rospy.get_namespace()
+
+
     # Initialize the low-level drivers (don't list the debug drivers)
     cflib.crtp.init_drivers(enable_debug_driver=False)
 
@@ -349,23 +376,42 @@ if __name__ == '__main__':
     #use this following two lines to connect without data from CentralManager
     # radio_address = "radio://0/72/2M"
     # rospy.loginfo("manual address loaded")
+
+    # Fetch the YAML paramter "battery polling period"
     global battery_polling_period
     battery_polling_period = rospy.get_param(ros_namespace + "/CrazyRadio/battery_polling_period")
 
+    # 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")
+    # Convert the coordinator ID to a zero-padded string
+    coordID_as_string = format(coordID, '03')
+
+
+    # Initialise a publisher for the battery voltage
     global cfbattery_pub
     cfbattery_pub = rospy.Publisher(node_name + '/CFBattery', Float32, queue_size=10)
 
+    # Initialise a "PPSRadioClient" type variable that handles
+    # all communication over the CrazyRadio
     global cf_client
-
     cf_client = PPSRadioClient()
-    rospy.Subscriber("PPSClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
+
+    # 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 command from the coordinator
+    rospy.Subscriber("/dfall/coord" + coordID_as_string + "/PPSClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
+
 
     time.sleep(1.0)
 
     rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
 
     rospy.spin()
-    rospy.loginfo("Turning off crazyflie")
+    rospy.loginfo("[CRAZY RADIO] Turning off crazyflie")
 
     cf_client._send_to_commander_motor(0, 0, 0, 0)
     # change state to motors OFF
@@ -378,7 +424,7 @@ if __name__ == '__main__':
 
 
     bag.close()
-    rospy.loginfo("bag closed")
+    rospy.loginfo("[CRAZY RADIO] bag closed")
 
     cf_client._cf.close_link()
-    rospy.loginfo("Link closed")
+    rospy.loginfo("[CRAZY RADIO] Link closed")
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
index 2ab71e04..9793c7ef 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -260,12 +260,6 @@ void viconCallback(const ViconData& viconData);
 
 
 
-// > For the {dis/re}-connect command received from the coordinator
-//void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
-void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg);
-
-
-
 
 void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
 
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index 868bb531..ef9305a7 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -24,7 +24,7 @@
 			output = "screen"
 			type   = "CrazyRadio.py"
 			>
-			<rosparam command="load" file="$(find d_fall_pps)/param/ClientConfig.yaml" />
+			<rosparam command="load" file="$(find d_fall_pps)/param/BatteryMonitor.yaml" />
 		</node>
 
 		<!-- PPS CLIENT -->
@@ -34,7 +34,6 @@
 			output = "screen"
 			type   = "PPSClient"
 			>
-			<rosparam command="load" file="$(find d_fall_pps)/param/ClientConfig.yaml" />
 			<param name="agentID" value="$(arg agentID)" />
 			<param name="coordID" value="$(arg coordID)" />
 		</node>
@@ -120,6 +119,11 @@
 			>
 			<param name="type"     type="str"  value="agent" />
 			<param name="agentID"  value="$(arg agentID)" />
+			<rosparam
+				command = "load"
+				file    = "$(find d_fall_pps)/param/ClientConfig.yaml"
+				ns      = "PPSClient"
+			/>
 			<rosparam
 				command = "load"
 				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 0754860e..46422732 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -416,7 +416,8 @@ void loadCrazyflieContext() {
 
             ROS_INFO("[PPS CLIENT] CF is now different for this student. Disconnect and turn it off");
 
-            std_msgs::Int32 msg;
+            IntWithHeader msg;
+            msg.shouldCheckForID = false;
             msg.data = CMD_DISCONNECT;
             crazyRadioCommandPublisher.publish(msg);
         }
@@ -558,22 +559,6 @@ void safeSetPointCallback(const Setpoint& newSetpoint)
 
 
 
-void crazyRadioCommandAllAgentsCallback(const std_msgs::Int32& msg)
-{
-    // The "msg" received can be directly published on the "crazyRadioCommandPublisher"
-    // class variable because it is same format message
-    // > NOTE: this may be inefficient to "just" pass on the message,
-    //   the intention is that it is more transparent that the "coordinator"
-    //   node requests all agents to (re/dis)-connect from, and the
-    //   individual agents pass this along to their respective radio node.
-    crazyRadioCommandPublisher.publish(msg);
-}
-
-
-
-
-
-
 
 
 
@@ -1268,7 +1253,7 @@ int main(int argc, char* argv[])
 
 
     //this topic lets us use the terminal to communicate with crazyRadio node.
-    crazyRadioCommandPublisher = nodeHandle.advertise<std_msgs::Int32>("crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = nodeHandle.advertise<IntWithHeader>("crazyRadioCommand", 1);
 
     // this topic will publish flying state whenever it changes.
     flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
@@ -1302,9 +1287,6 @@ int main(int argc, char* argv[])
     // crazyradio status. Connected, connecting or disconnected
     ros::Subscriber crazyRadioStatusSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
-    // Subscriber for "crazyRadioCommandAllAgents" commands that are sent from the coordinator node
-    ros::Subscriber crazyRadioCommandAllAgentsSubscriber = namespaceNodeHandle.subscribe("/my_GUI/crazyRadioCommandAllAgents", 1, crazyRadioCommandAllAgentsCallback);
-
 
 
 
-- 
GitLab


From 97d7101d25eac657ecd9bd3a1e8b4e58026e6d47 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 16:36:18 +0100
Subject: [PATCH 09/87] Small adjusts to flying agent GUI, layout and button
 naming

---
 .../GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro  |   3 +-
 .../forms/connectstartstopbar.ui              |  16 +-
 .../flyingAgentGUI/forms/coordinatorrow.ui    |   5 +-
 .../forms/enablecontrollerloadyamlbar.ui      |  55 +++--
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |  32 ++-
 .../include/Constants_for_Qt_compile.h        | 229 ++++++++++++++++++
 .../include/connectstartstopbar.h             |   5 +
 .../flyingAgentGUI/include/coordinatorrow.h   |   5 +
 .../include/enablecontrollerloadyamlbar.h     |   5 +
 .../flyingAgentGUI/include/mainwindow.h       |   4 +
 .../src/connectstartstopbar.cpp               |   6 +-
 11 files changed, 327 insertions(+), 38 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
index 07c4fbce..dba7e186 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
@@ -39,7 +39,8 @@ HEADERS  += include/mainwindow.h \
     include/coordinatorrow.h \
     include/studentcontrollertab.h \
     include/defaultcontrollertab.h \
-    include/pickercontrollertab.h
+    include/pickercontrollertab.h \
+    include/Constants_for_Qt_compile.h
 
 FORMS    += forms/mainwindow.ui \
     forms/topbanner.ui \
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
index c08c3341..c2e783df 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
@@ -22,19 +22,19 @@
    <item row="0" column="0">
     <layout class="QHBoxLayout" name="horizontalLayout">
      <property name="spacing">
-      <number>6</number>
+      <number>12</number>
      </property>
      <property name="leftMargin">
       <number>6</number>
      </property>
      <property name="topMargin">
-      <number>6</number>
+      <number>0</number>
      </property>
      <property name="rightMargin">
       <number>6</number>
      </property>
      <property name="bottomMargin">
-      <number>6</number>
+      <number>0</number>
      </property>
      <item>
       <widget class="QPushButton" name="rf_disconnect_button">
@@ -113,6 +113,9 @@
      </item>
      <item>
       <widget class="QLineEdit" name="battery_voltage_lineEdit">
+       <property name="enabled">
+        <bool>true</bool>
+       </property>
        <property name="sizePolicy">
         <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -144,6 +147,9 @@
        <property name="alignment">
         <set>Qt::AlignCenter</set>
        </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
       </widget>
      </item>
      <item>
@@ -172,7 +178,7 @@
       </widget>
      </item>
      <item>
-      <widget class="QPushButton" name="take_off_button">
+      <widget class="QPushButton" name="enable_flying_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -197,7 +203,7 @@
       </widget>
      </item>
      <item>
-      <widget class="QPushButton" name="land_button">
+      <widget class="QPushButton" name="disable_flying_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
index 06003ef3..ffb245eb 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
@@ -6,7 +6,7 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>660</width>
+    <width>740</width>
     <height>45</height>
    </rect>
   </property>
@@ -193,6 +193,9 @@
      <property name="text">
       <string>-.-- V</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index 80d40b20..704e95ab 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -27,6 +27,9 @@
   <layout class="QGridLayout" name="gridLayout_2">
    <item row="0" column="0">
     <layout class="QGridLayout" name="gridLayout_3">
+     <property name="spacing">
+      <number>12</number>
+     </property>
      <item row="0" column="4">
       <widget class="QPushButton" name="enable_safe_button">
        <property name="sizePolicy">
@@ -38,13 +41,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="font">
@@ -61,21 +64,21 @@
      <item row="0" column="0">
       <widget class="QLabel" name="enable_controller_label">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>60</width>
-         <height>20</height>
+         <width>0</width>
+         <height>70</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
-         <width>180</width>
-         <height>20</height>
+         <width>16777215</width>
+         <height>70</height>
         </size>
        </property>
        <property name="font">
@@ -103,13 +106,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="font">
@@ -126,21 +129,21 @@
      <item row="1" column="0">
       <widget class="QLabel" name="load_yaml_label">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>60</width>
-         <height>20</height>
+         <width>0</width>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
-         <width>180</width>
-         <height>20</height>
+         <width>16777215</width>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -168,13 +171,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -193,13 +196,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -218,13 +221,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -243,13 +246,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="font">
@@ -274,13 +277,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>70</height>
         </size>
        </property>
        <property name="font">
@@ -305,13 +308,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>40</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index a3018633..28300e78 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -73,20 +73,44 @@
         </property>
         <item>
          <widget class="TopBanner" name="customWidget_topBanner" native="true">
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Preferred" vsizetype="Minimum">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
+          </property>
+          <property name="minimumSize">
+           <size>
+            <width>0</width>
+            <height>0</height>
+           </size>
+          </property>
           <property name="maximumSize">
            <size>
             <width>16777215</width>
-            <height>100</height>
+            <height>16777215</height>
            </size>
           </property>
          </widget>
         </item>
         <item>
          <widget class="ConnectStartStopBar" name="customWidget_connectStartStopBar" native="true">
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Preferred" vsizetype="Minimum">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
+          </property>
+          <property name="minimumSize">
+           <size>
+            <width>0</width>
+            <height>0</height>
+           </size>
+          </property>
           <property name="maximumSize">
            <size>
             <width>16777215</width>
-            <height>80</height>
+            <height>16777215</height>
            </size>
           </property>
          </widget>
@@ -97,7 +121,7 @@
            <bool>true</bool>
           </property>
           <property name="sizePolicy">
-           <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+           <sizepolicy hsizetype="Preferred" vsizetype="Minimum">
             <horstretch>0</horstretch>
             <verstretch>0</verstretch>
            </sizepolicy>
@@ -111,7 +135,7 @@
           <property name="maximumSize">
            <size>
             <width>16777215</width>
-            <height>100</height>
+            <height>16777215</height>
            </size>
           </property>
          </widget>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
new file mode 100644
index 00000000..ac3ecb91
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
@@ -0,0 +1,229 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    Constants that are used across multiple files
+//
+//    ----------------------------------------------------------------------------------
+
+
+//    ----------------------------------------------------------------------------------
+//    U   U
+//    U   U
+//    U   U
+//    U   U
+//     UUU
+//    ----------------------------------------------------------------------------------
+
+
+// Conversions between degrees and radians
+#define RAD2DEG 180.0/PI
+#define DEG2RAD PI/180.0
+
+// PI
+#define PI 3.141592653589
+
+
+
+
+// Types PPS firmware
+#define CF_COMMAND_TYPE_MOTORS 6
+#define CF_COMMAND_TYPE_RATE   7
+#define CF_COMMAND_TYPE_ANGLE  8
+
+// Types of controllers being used:
+#define SAFE_CONTROLLER      1
+#define DEMO_CONTROLLER      2
+#define STUDENT_CONTROLLER   3
+#define MPC_CONTROLLER       4
+#define REMOTE_CONTROLLER    5
+#define TUNING_CONTROLLER    6
+#define PICKER_CONTROLLER    7
+
+// The constants that "command" changes in the
+// operation state of this agent
+#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEMO_CONTROLLER      2
+#define CMD_USE_STUDENT_CONTROLLER   3
+#define CMD_USE_MPC_CONTROLLER       4
+#define CMD_USE_REMOTE_CONTROLLER    5
+#define CMD_USE_TUNING_CONTROLLER    6
+#define CMD_USE_PICKER_CONTROLLER    7
+
+
+#define CMD_CRAZYFLY_TAKE_OFF        11
+#define CMD_CRAZYFLY_LAND            12
+#define CMD_CRAZYFLY_MOTORS_OFF      13
+
+// Flying states
+#define STATE_MOTORS_OFF 1
+#define STATE_TAKE_OFF   2
+#define STATE_FLYING     3
+#define STATE_LAND       4
+
+
+// Commands for CrazyRadio
+#define CMD_RECONNECT  0
+#define CMD_DISCONNECT 1
+
+
+// CrazyRadio states:
+#define CRAZY_RADIO_STATE_CONNECTED      0
+#define CRAZY_RADIO_STATE_CONNECTING     1
+#define CRAZY_RADIO_STATE_DISCONNECTED   2
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
+//    ----------------------------------------------------------------------------------
+
+// Battery levels
+#define BATTERY_LEVEL_000            0
+#define BATTERY_LEVEL_010            1
+#define BATTERY_LEVEL_020            2
+#define BATTERY_LEVEL_030            3
+#define BATTERY_LEVEL_040            4
+#define BATTERY_LEVEL_050            5
+#define BATTERY_LEVEL_060            6
+#define BATTERY_LEVEL_070            7
+#define BATTERY_LEVEL_080            8
+#define BATTERY_LEVEL_090            9
+#define BATTERY_LEVEL_100           10
+#define BATTERY_LEVEL_UNAVAILABLE   -1
+
+// Battery states
+#define BATTERY_STATE_NORMAL         0
+#define BATTERY_STATE_LOW            1
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    Y   Y    A    M   M  L
+//     Y Y    A A   MM MM  L
+//      Y    A   A  M M M  L
+//      Y    AAAAA  M   M  L
+//      Y    A   A  M   M  LLLLL
+//    ----------------------------------------------------------------------------------
+
+// For where to load the yaml file from
+#define LOAD_YAML_FROM_AGENT             1
+#define LOAD_YAML_FROM_COORDINATOR       2
+
+
+
+
+
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// OLD STUFF FOR LOADING YAML FILES
+// For which controller parameters to load from file
+#define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
+#define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
+#define LOAD_YAML_STUDENT_CONTROLLER_AGENT          3
+#define LOAD_YAML_MPC_CONTROLLER_AGENT              4
+#define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
+#define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
+#define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
+
+#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
+#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
+#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR    13
+#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR        14
+#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
+#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
+#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
+
+
+// For sending commands to the controller node informing
+// which parameters to fetch
+// > NOTE: these are identical to the #defines above, but
+//         used because they have the name distinguishes
+//         between:
+//         - "loading" a yaml file into ram
+//         - "fetching" the values that were loaded into ram
+#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT      1
+#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
+#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT   3
+#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT       4
+#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
+#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
+#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
+
+#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
+#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
+#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR   13
+#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
+#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
+#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
+#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index fbfd8c71..98ce0104 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -26,6 +26,11 @@
 
 // SPECIFY THE PACKAGE NAMESPACE
 //using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
 #endif
 
 // BATTERY LABEL IMAGE INDEX
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index f80eb8ba..f8e8b749 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -58,6 +58,11 @@
 
 // SPECIFY THE PACKAGE NAMESPACE
 using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
 #endif
 
 // BATTERY LABEL IMAGE INDEX
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index b42d1186..5c239d18 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -25,6 +25,11 @@
 #include "nodes/Constants.h"
 
 // using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
 #endif
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index c9f071fa..baeea54b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -56,6 +56,10 @@
 using namespace d_fall_pps;
 //using namespace std;
 
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
 #endif
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index ab730565..9f699f92 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -504,20 +504,24 @@ void ConnectStartStopBar::setFlyingState(int new_flying_state)
 
 void ConnectStartStopBar::on_rf_connect_button_clicked()
 {
+#ifdef CATKIN_MAKE
     d_fall_pps::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
     ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+#endif
 }
 
 void ConnectStartStopBar::on_rf_disconnect_button_clicked()
 {
+#ifdef CATKIN_MAKE
     d_fall_pps::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
     ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+#endif
 }
 
 void ConnectStartStopBar::on_enable_flying_button_clicked()
@@ -693,4 +697,4 @@ bool ConnectStartStopBar::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
-- 
GitLab


From f3d74125d1538e0c9c78ceacb033578cd0acf776 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 17:01:15 +0100
Subject: [PATCH 10/87] Small changes

---
 .../GUI_Qt/flyingAgentGUI/include/coordinator.h           | 1 +
 .../GUI_Qt/flyingAgentGUI/include/coordinatorrow.h        | 5 +++++
 .../GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp     | 7 +++++--
 .../flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp    | 8 +++++++-
 4 files changed, 18 insertions(+), 3 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
index 27c6501b..d491c0c3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
@@ -19,6 +19,7 @@ public:
     explicit Coordinator(QWidget *parent = 0);
     ~Coordinator();
 
+
 private:
     QVector<CoordinatorRow*> vector_of_coordinatorRows;
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index f8e8b749..a96eaf1e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -94,6 +94,11 @@ public:
     // > Set the level of detail to display
     void setLevelOfDetailToDisplay(int level);
 
+
+signals:
+    void shouldCoordinateChanged(int newValue);
+
+
 private:
     // --------------------------------------------------- //
     // PRIVATE VARIABLES
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 9f699f92..a3dd4c1c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -509,7 +509,7 @@ void ConnectStartStopBar::on_rf_connect_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Connect button clicked");
 #endif
 }
 
@@ -520,7 +520,7 @@ void ConnectStartStopBar::on_rf_disconnect_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Disconnect button clicked");
 #endif
 }
 
@@ -531,6 +531,7 @@ void ConnectStartStopBar::on_enable_flying_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable flying button clicked");
 #endif
 }
 
@@ -541,6 +542,7 @@ void ConnectStartStopBar::on_disable_flying_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Disable flying button clicked");
 #endif
 }
 
@@ -551,6 +553,7 @@ void ConnectStartStopBar::on_motors_off_button_clicked()
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Motors-off button clicked");
 #endif
 }
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 94f26a33..2822b7b6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -80,7 +80,13 @@ void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 
 void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 {
-
+#ifdef CATKIN_MAKE
+    //d_fall_pps::IntWithHeader msg;
+    //fillIntMessageHeader(msg);
+    //msg.data = CMD_USE_STUDENT_CONTROLLER;
+    //this->commandPublisher.publish(msg);
+    //ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Student Controller");
+#endif
 }
 
 
-- 
GitLab


From bfda2a31d2cdab6d6a861de31d7a9d803d4e2332 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 21:46:09 +0100
Subject: [PATCH 11/87] Connected the Qt Slots and Signals from the Coordinator
 Row through to the ConnectStartStop bar

---
 .../include/connectstartstopbar.h             |  13 ++
 .../flyingAgentGUI/include/coordinator.h      |  16 +++
 .../flyingAgentGUI/include/coordinatorrow.h   |   5 +-
 .../src/connectstartstopbar.cpp               |  66 +++++++++-
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp | 114 +++++++++++++++---
 .../flyingAgentGUI/src/coordinatorrow.cpp     |   9 ++
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  11 +-
 7 files changed, 213 insertions(+), 21 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 98ce0104..878b6a17 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -5,6 +5,8 @@
 #include <QWidget>
 #include <QMutex>
 
+#include <QTextStream>
+
 #ifdef CATKIN_MAKE
 #include <ros/ros.h>
 #include <ros/network.h>
@@ -55,6 +57,11 @@ public:
     explicit ConnectStartStopBar(QWidget *parent = 0);
     ~ConnectStartStopBar();
 
+
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+
+
 private:
 	// --------------------------------------------------- //
     // PRIVATE VARIABLES
@@ -70,6 +77,12 @@ private:
 	// The namespace into which node operates
 	std::string m_base_namespace;
 
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+
 
 
 	// > For keeping track of the current battery state
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
index d491c0c3..c4f21a83 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
@@ -7,6 +7,8 @@
 #include <QVector>
 #include <regex>
 
+#include <QTextStream>
+
 namespace Ui {
 class Coordinator;
 }
@@ -20,9 +22,21 @@ public:
     ~Coordinator();
 
 
+public slots:
+    void setShouldCoordinateThisAgent(int agentID , bool shouldCoordinate);
+
+
+signals:
+    void agentIDsToCoordinateChanged(QVector<int> agentIDs , bool shouldCoordinateAll);
+
+
 private:
     QVector<CoordinatorRow*> vector_of_coordinatorRows;
 
+    QVector<bool> vector_of_shouldCoordinate_perRow;
+
+    QVector<int> vector_of_agentID_perRow;
+
     int level_of_detail_to_display = 1;
 
     void remove_all_entries_from_vector_of_coordinatorRows();
@@ -38,6 +52,8 @@ private slots:
 
     void on_coordinate_all_checkBox_clicked();
 
+    void emit_signal_with_agentIDs_toCoordinate();
+
 private:
     Ui::Coordinator *ui;
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index a96eaf1e..b7bb4eb6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -96,7 +96,7 @@ public:
 
 
 signals:
-    void shouldCoordinateChanged(int newValue);
+    void shouldCoordinateThisAgentValueChanged(int agentID , bool shouldCoordinate);
 
 
 private:
@@ -219,6 +219,9 @@ private slots:
     void on_disable_flying_button_clicked();
     void on_motors_off_button_clicked();
 
+    // > For the "should coordinate" checkbox
+    void on_shouldCoordinate_checkBox_clicked();
+
 };
 
 #endif // COORDINATORROW_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index a3dd4c1c..437aa7cc 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -47,6 +47,7 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
 {
     ui->setupUi(this);
 
+
 #ifdef CATKIN_MAKE
     // Get the namespace of this node
     std::string this_namespace = ros::this_node::getNamespace();
@@ -62,6 +63,10 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
         ROS_ERROR("[CONNECT START STOP GUI BAR] Node NOT FUNCTIONING :-)");
         ros::spin();
     }
+#else
+    // Default as a coordinator when compiling with QtCreator
+    m_type = TYPE_COORDINATOR;
+    m_ID = 1;
 #endif
 
     // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
@@ -132,7 +137,6 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
         //loadCrazyflieContext();
     }
 
-
     // ADD KEYBOARD SHORTCUTS
     // > For "all motors off", press the space bar
     ui->motors_off_button->setShortcut(tr("Space"));
@@ -560,6 +564,50 @@ void ConnectStartStopBar::on_motors_off_button_clicked()
 
 
 
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[CONNECT START STOP GUI BAR] is coordinating agentIDs:";
+    for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+    {
+        QTextStream(stdout) << " " << agentIDs[irow];
+    }
+    QTextStream(stdout) << " " << endl;
+#endif
+}
+
+
+
+
 
 //    ----------------------------------------------------------------------------------
 //    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
@@ -584,8 +632,20 @@ void ConnectStartStopBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg
         }
         case TYPE_COORDINATOR:
         {
-            msg.shouldCheckForID = true;
-            msg.agentIDs.push_back(7);
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.length() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
             break;
         }
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
index 6c8419a1..6e1f52d2 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
@@ -20,6 +20,9 @@ void Coordinator::on_refresh_button_clicked()
     // DELETE ALL EXISTING ROWS
     remove_all_entries_from_vector_of_coordinatorRows();
 
+    // Get the state of the "coordinate all" is check box
+    bool shouldCoordinateAll = ui->coordinate_all_checkBox->isChecked();
+
 
 #ifdef CATKIN_MAKE
     // USE A REGULAR EXPRESSION TO IDENTIFY NODES THAT EXIST
@@ -56,17 +59,12 @@ void Coordinator::on_refresh_button_clicked()
             CoordinatorRow *temp_coordinatorRow = new CoordinatorRow(this,this_agentID);
 
             // Check the box if "coordinate all" is checked
-            if (ui->coordinate_all_checkBox->isChecked())
-            {
-                temp_coordinatorRow->setShouldCoordinate(true);
-            }
-            else
-            {
-                temp_coordinatorRow->setShouldCoordinate(false);
-            }
+            temp_coordinatorRow->setShouldCoordinate(shouldCoordinateAll);
 
             // Add to the vector of coordinator rows
             vector_of_coordinatorRows.append(temp_coordinatorRow);
+            vector_of_shouldCoordinate_perRow.append(shouldCoordinateAll);
+            vector_of_agentID_perRow.append(this_agentID);
 
             ui->coordinated_agents_scrollAreaWidgetContents->layout()->addWidget(temp_coordinatorRow);
         }
@@ -81,22 +79,26 @@ void Coordinator::on_refresh_button_clicked()
         CoordinatorRow *temp_coordinatorRow = new CoordinatorRow(this,i_agent);
 
         // Check the box if "coordinate all" is checked
-        if (ui->coordinate_all_checkBox->isChecked())
-        {
-            temp_coordinatorRow->setShouldCoordinate(true);
-        }
-        else
-        {
-            temp_coordinatorRow->setShouldCoordinate(false);
-        }
+        temp_coordinatorRow->setShouldCoordinate(shouldCoordinateAll);
+
+        // Connect the "should coordinate value changed" signal to
+        // the respective slot
+        QObject::connect(
+                temp_coordinatorRow , &CoordinatorRow::shouldCoordinateThisAgentValueChanged ,
+                this , &Coordinator::setShouldCoordinateThisAgent
+                );
 
         // Add to the vector of coordinator rows
         vector_of_coordinatorRows.append(temp_coordinatorRow);
+        vector_of_shouldCoordinate_perRow.append(shouldCoordinateAll);
+        vector_of_agentID_perRow.append(i_agent);
 
         ui->coordinated_agents_scrollAreaWidgetContents->layout()->addWidget(temp_coordinatorRow);
     }
 #endif
 
+    // Send out a signal with the current IDs to coordinate
+    emit_signal_with_agentIDs_toCoordinate();
     
     // Call the function that applies this level
     // of detail to all the entries
@@ -134,6 +136,9 @@ void Coordinator::on_delete_button_clicked()
 {
     // Call the function that performs the task requested
     remove_all_entries_from_vector_of_coordinatorRows();
+
+    // Send out a signal with the current IDs to coordinate
+    emit_signal_with_agentIDs_toCoordinate();
 }
 
 void Coordinator::remove_all_entries_from_vector_of_coordinatorRows()
@@ -144,6 +149,8 @@ void Coordinator::remove_all_entries_from_vector_of_coordinatorRows()
     }
     // Clear the vector
     vector_of_coordinatorRows.clear();
+    vector_of_shouldCoordinate_perRow.clear();
+    vector_of_agentID_perRow.clear();
 }
 
 void Coordinator::apply_level_of_detail_to_all_entries(int level)
@@ -164,5 +171,80 @@ void Coordinator::on_coordinate_all_checkBox_clicked()
     for ( int irow = 0 ; irow < vector_of_coordinatorRows.length() ; irow++ )
     {
         vector_of_coordinatorRows[irow]->setShouldCoordinate( shouldCoordinateAll );
+        vector_of_shouldCoordinate_perRow[irow] = shouldCoordinateAll;
+    }
+
+    // Send out a signal with the current IDs to coordinate
+    emit_signal_with_agentIDs_toCoordinate();
+}
+
+
+void Coordinator::setShouldCoordinateThisAgent(int agentID , bool shouldCoordinate)
+{
+    // Find the row with the matching ID, and update the "shouldCoordinate" vector
+    for ( int irow = 0 ; irow < vector_of_agentID_perRow.length() ; irow++ )
+    {
+        if (vector_of_agentID_perRow[irow] == agentID)
+        {
+            vector_of_shouldCoordinate_perRow[irow] = shouldCoordinate;
+            break;
+        }
+    }
+
+    // Update the "Coordinate All Check Box" as appropriate
+    bool shouldCoordinateAll = true;
+    if (!shouldCoordinate)
+    {
+        shouldCoordinateAll = false;
     }
+    else
+    {
+        for ( int irow = 0 ; irow < vector_of_shouldCoordinate_perRow.length() ; irow++ )
+        {
+            if (!(vector_of_shouldCoordinate_perRow[irow]))
+            {
+                shouldCoordinateAll = false;
+                break;
+            }
+        }
+    }
+    ui->coordinate_all_checkBox->setChecked(shouldCoordinateAll);
+
+    // Send out a signal with the current IDs to coordinate
+    emit_signal_with_agentIDs_toCoordinate();
+}
+
+void Coordinator::emit_signal_with_agentIDs_toCoordinate()
+{
+    // Initilise a boolean for whether to coordinate all
+    bool shouldCoordinateAll = true;
+    // Send out a signal with the current IDs to coordinate
+    QVector<int> agentIDsToCoordinate;
+    for ( int irow = 0 ; irow < vector_of_shouldCoordinate_perRow.length() ; irow++ )
+    {
+        if (vector_of_shouldCoordinate_perRow[irow])
+        {
+            agentIDsToCoordinate.append(vector_of_agentID_perRow[irow]);
+        }
+        else
+        {
+            shouldCoordinateAll = false;
+        }
+    }
+    emit agentIDsToCoordinateChanged( agentIDsToCoordinate , shouldCoordinateAll );
+
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[COORDINATOR] is coordinating agentIDs:";
+    for ( int irow = 0 ; irow < vector_of_shouldCoordinate_perRow.length() ; irow++ )
+    {
+        if (vector_of_shouldCoordinate_perRow[irow])
+        {
+            QTextStream(stdout) << " " << vector_of_agentID_perRow[irow];
+        }
+    }
+    QTextStream(stdout) << " " << endl;
+#endif
 }
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 31a0e1a4..fe437e64 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -741,3 +741,12 @@ void CoordinatorRow::on_motors_off_button_clicked()
     this->flyingStateCommandPublisher.publish(msg);
 #endif
 }
+
+void CoordinatorRow::on_shouldCoordinate_checkBox_clicked()
+{
+    // Get the state of the "should coordinate" check box
+    bool shouldCoordinate = ui->shouldCoordinate_checkBox->isChecked();
+
+    // Send out a signal with this information
+    emit shouldCoordinateThisAgentValueChanged( m_agentID , shouldCoordinate );
+}
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 3d839967..b744a9a4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -93,6 +93,15 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     }
 #endif
 
+    // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
+    // WITH THE LIST OF AGENT IDs TO COORDINATE
+    // Connect the "should coordinate value changed" signal to
+    // the respective slot
+    QObject::connect(
+            ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
+            ui->customWidget_connectStartStopBar , &ConnectStartStopBar::setAgentIDsToCoordinate
+            );
+
 }
 
 MainWindow::~MainWindow()
@@ -255,4 +264,4 @@ bool MainWindow::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
-- 
GitLab


From 339bac5f39b182704067b6d2ebf3f7086b00edbd Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 9 Dec 2018 22:03:55 +0100
Subject: [PATCH 12/87] Connection between Coordinator and other components of
 GUI now working for passing around the agentIDs to coordinator. Next step is
 to clean things up, add all the necessary connections, and test.

---
 .../include/enablecontrollerloadyamlbar.h     | 12 ++++
 .../src/connectstartstopbar.cpp               |  2 +-
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp |  7 +++
 .../src/enablecontrollerloadyamlbar.cpp       | 61 ++++++++++++++++++-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  5 ++
 5 files changed, 84 insertions(+), 3 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 5c239d18..3df7eddd 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -2,6 +2,7 @@
 #define ENABLECONTROLLERLOADYAMLBAR_H
 
 #include <QWidget>
+#include <QMutex>
 
 #ifdef CATKIN_MAKE
 #include <ros/ros.h>
@@ -58,6 +59,11 @@ public:
     explicit EnableControllerLoadYamlBar(QWidget *parent = 0);
     ~EnableControllerLoadYamlBar();
 
+
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+
+
 private slots:
 
     // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
@@ -86,6 +92,12 @@ private:
     // The ID  of this node
     int m_ID;
 
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+
 #ifdef CATKIN_MAKE
     // PUBLISHERS AND SUBSRIBERS
     // > For {take-off,land,motors-off} and controller selection
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 437aa7cc..1e842c83 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -639,7 +639,7 @@ void ConnectStartStopBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
-                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.length() ; irow++ )
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
                 {
                     msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
                 }
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
index 6e1f52d2..64bece6d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
@@ -61,6 +61,13 @@ void Coordinator::on_refresh_button_clicked()
             // Check the box if "coordinate all" is checked
             temp_coordinatorRow->setShouldCoordinate(shouldCoordinateAll);
 
+            // Connect the "should coordinate value changed" signal to
+            // the respective slot
+            QObject::connect(
+                    temp_coordinatorRow , &CoordinatorRow::shouldCoordinateThisAgentValueChanged ,
+                    this , &Coordinator::setShouldCoordinateThisAgent
+                    );
+
             // Add to the vector of coordinator rows
             vector_of_coordinatorRows.append(temp_coordinatorRow);
             vector_of_shouldCoordinate_perRow.append(shouldCoordinateAll);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 2822b7b6..6eaaa3cf 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -116,6 +116,51 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 
 
 
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void EnableControllerLoadYamlBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[CONNECT START STOP GUI BAR] is coordinating agentIDs:";
+    for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+    {
+        QTextStream(stdout) << " " << agentIDs[irow];
+    }
+    QTextStream(stdout) << " " << endl;
+#endif
+}
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
 //    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
@@ -139,8 +184,20 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade
         }
         case TYPE_COORDINATOR:
         {
-            msg.shouldCheckForID = true;
-            msg.agentIDs.push_back(7);
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
             break;
         }
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index b744a9a4..65645bb8 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -102,6 +102,11 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
             ui->customWidget_connectStartStopBar , &ConnectStartStopBar::setAgentIDsToCoordinate
             );
 
+    QObject::connect(
+            ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
+            ui->customWidget_enableControllerLoadYamlBar , &EnableControllerLoadYamlBar::setAgentIDsToCoordinate
+            );
+
 }
 
 MainWindow::~MainWindow()
-- 
GitLab


From 1072e6c8e3d9b5addea9d1da134f10b8d7b93112 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 11 Dec 2018 13:50:10 +0100
Subject: [PATCH 13/87] Yaml connections working (for student and demo
 controller), and title is now proper. Ready for testing on real system before
 cleaning up the controllers and their interface

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   6 +-
 .../include/connectstartstopbar.h             |  92 ++-
 .../flyingAgentGUI/include/coordinatorrow.h   |  65 +-
 .../include/enablecontrollerloadyamlbar.h     |   9 +-
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h | 109 +++
 .../src/connectstartstopbar.cpp               |  26 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  67 +-
 .../src/enablecontrollerloadyamlbar.cpp       |  76 ++-
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   | 281 ++++++++
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   |   9 +-
 .../src/d_fall_pps/include/nodes/Constants.h  |  48 +-
 .../include/nodes/DemoControllerService.h     |  89 ++-
 .../src/d_fall_pps/include/nodes/PPSClient.h  |  39 +-
 .../include/nodes/SafeControllerService.h     |  66 +-
 .../include/nodes/StudentControllerService.h  | 162 +++--
 pps_ws/src/d_fall_pps/launch/Agent.launch     |  24 -
 .../src/nodes/DemoControllerService.cpp       | 618 +++++++++---------
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp |  58 +-
 .../d_fall_pps/src/nodes/ParameterService.cpp |   2 +-
 .../src/nodes/SafeControllerService.cpp       |   2 +-
 .../src/nodes/StudentControllerService.cpp    | 583 ++++++++---------
 21 files changed, 1537 insertions(+), 894 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 294a21b8..8fb21f1c 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -325,8 +325,10 @@ add_executable(PPSClient                 src/nodes/PPSClient.cpp
 add_executable(BatteryMonitor            src/nodes/BatteryMonitor.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(SafeControllerService     src/nodes/SafeControllerService.cpp)
-add_executable(DemoControllerService     src/nodes/DemoControllerService.cpp)
-add_executable(StudentControllerService  src/nodes/StudentControllerService.cpp)
+add_executable(DemoControllerService     src/nodes/DemoControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
+add_executable(StudentControllerService  src/nodes/StudentControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(MpcControllerService      src/nodes/MpcControllerService.cpp)
 add_executable(RemoteControllerService   src/nodes/RemoteControllerService.cpp)
 add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp)
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 878b6a17..4b8d2284 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -1,3 +1,35 @@
+//    Copyright (C) 2018, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The bar of the GUI for (dis-)connecting (from)to the Crazyradio
+//    and for sending the {take-off,land,motors-off} commands//
+//    ----------------------------------------------------------------------------------
+
+
 #ifndef CONNECTSTARTSTOPBAR_H
 #define CONNECTSTARTSTOPBAR_H
 
@@ -74,9 +106,6 @@ private:
 	// > For the ID of this node
 	int m_ID = 0;
 
-	// The namespace into which node operates
-	std::string m_base_namespace;
-
     // For coordinating multiple agents
     std::vector<int> m_vector_of_agentIDs_toCoordinate;
     bool m_shouldCoordinateAll = true;
@@ -99,27 +128,8 @@ private:
     //QMutex m_battery_voltage_lineEdit_mutex;
     // > For the "battery_status_label" UI element
     QMutex m_battery_status_label_mutex;
-    
 
 
-#ifdef CATKIN_MAKE
-	// PUBLISHERS AND SUBSRIBERS
-    // > For Crazyradio commands based on button clicks
-    ros::Publisher crazyRadioCommandPublisher;
-    // > For updating the "rf_status_label" picture
-    ros::Subscriber crazyRadioStatusSubscriber;
-    // > For updating the current battery voltage
-    ros::Subscriber batteryVoltageSubscriber;
-    // > For updating the current battery state
-    //ros::Subscriber batteryStateSubscriber;
-    // > For updating the current battery level
-    ros::Subscriber batteryLevelSubscriber;
-    // > For Flying state commands based on button clicks
-    ros::Publisher flyingStateCommandPublisher;
-    // > For updating the "flying_state_label" picture
-    ros::Subscriber flyingStateSubscriber;
-#endif
-
 
     // --------------------------------------------------- //
     // PRIVATE FUNCTIONS
@@ -129,22 +139,50 @@ private:
     void disableFlyingStateButtons();
     void enableFlyingStateButtons();
 
-    // > For updating the RF Radio status shown in the
-    //   UI element of "rf_status_label"
+    // > For updating the RF Radio status shown in the UI element
+    //   of "rf_status_label"
     void setCrazyRadioStatus(int radio_status);
+
     // > For updating the battery state
     void setBatteryState(int new_battery_state);
     // > For updating the battery voltage shown in the UI elements 
     //   of "battery_voltage_lineEdit" and "battery_status_label"
     void setBatteryVoltageText(float battery_voltage);
     void setBatteryImageBasedOnLevel(int battery_level);
-    // > For updating the "my_flying_state" variable, and
-    //   the UI element of "flying_state_label"
+
+    // > For updating the "my_flying_state" variable, and the
+    //   UI element of "flying_state_label"
     void setFlyingState(int new_flying_state);
 
 
 
 #ifdef CATKIN_MAKE
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES FOR ROS
+
+
+    // PUBLISHERS AND SUBSRIBERS
+    // > For Crazyradio commands based on button clicks
+    ros::Publisher crazyRadioCommandPublisher;
+    // > For updating the "rf_status_label" picture
+    ros::Subscriber crazyRadioStatusSubscriber;
+
+    // > For updating the current battery voltage
+    ros::Subscriber batteryVoltageSubscriber;
+    // > For updating the current battery state
+    //ros::Subscriber batteryStateSubscriber;
+    // > For updating the current battery level
+    ros::Subscriber batteryLevelSubscriber;
+
+    // > For Flying state commands based on button clicks
+    ros::Publisher flyingStateCommandPublisher;
+    // > For updating the "flying_state_label" picture
+    ros::Subscriber flyingStateSubscriber;
+
+
+    // --------------------------------------------------- //
+    // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
+
     // Get the type and ID of this node
     bool getTypeAndIDParameters();
 	// Fill the head for a message
@@ -153,6 +191,7 @@ private:
     // > For the CrazyRadio status, received on the
     //   "crazyRadioStatusSubscriber"
     void crazyRadioStatusCallback(const std_msgs::Int32& msg);
+
     // > For the Battery Voltage, received on the
     //   "batteryVoltageSubscriber"
     void batteryVoltageCallback(const std_msgs::Float32& msg);
@@ -162,6 +201,7 @@ private:
     // > For the Battery Level, receieved on the
     //   "batteryLevelSubscriber"
     void batteryLevelCallback(const std_msgs::Int32& msg);
+
     // > For the Flying State, received on the
     //   "flyingStateSubscriber"
     void flyingStateChangedCallback(const std_msgs::Int32& msg);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index b7bb4eb6..6d0a3943 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -57,7 +57,7 @@
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-using namespace d_fall_pps;
+//using namespace d_fall_pps;
 
 #else
 // Include the shared definitions
@@ -131,21 +131,32 @@ private:
     // --------------------------------------------------- //
     // PRIVATE FUNCTIONS
 
-    // > For updating the RF Radio status shown in the UI element of "rf_status_label"
+    // > For making the "enable flight" and "disable flight" buttons
+    //   (un-)available
+    void disableFlyingStateButtons();
+    void enableFlyingStateButtons();
+
+    // > For updating the RF Radio status shown in the UI element
+    //   of "rf_status_label"
     void setCrazyRadioStatus(int radio_status);
+
     // > For updating the battery state
     void setBatteryState(int new_battery_state);
-    // > For updating the battery voltage shown in the UI elements of "battery_voltage_lineEdit" and "battery_status_label"
+    // > For updating the battery voltage shown in the UI elements
+    //   of "battery_voltage_lineEdit" and "battery_status_label"
     void setBatteryVoltageText(float battery_voltage);
     void setBatteryImageBasedOnLevel(int battery_level);
-    // > For making the "enable flight" and "disable flight" buttons (un-)available
-    void disableFlyingStateButtons();
-    void enableFlyingStateButtons();
-    // > For updating the "my_flying_state" variable, and the UI element of "flying_state_label"
+
+    // > For updating the "my_flying_state" variable, and the
+    //   UI element of "flying_state_label"
     void setFlyingState(int new_flying_state);
-    // > For loading the "context" for this agent, i.e., the {agentID,cfID,flying zone} tuple
+
+    // > For loading the "context" for this agent,
+    //   i.e., the {agentID,cfID,flying zone} tuple
     void loadCrazyflieContext();
-    // > For updating the text in the UI element of "controller_enabled_label"
+
+    // > For updating the text in the UI element of
+    //   "controller_enabled_label"
     void setControllerEnabled(int new_controller);
 
 
@@ -154,30 +165,27 @@ private:
     // --------------------------------------------------- //
     // PRIVATE VARIABLES FOR ROS
 
-    // > For running this is a ROS node thread
-    //rosNodeThread* myrosNodeThread;
-
-    // > For the namespace of this node
-    std::string my_ros_namespace;
-
     // > For the "context" of this agent
-    CrazyflieContext my_context;
+    d_fall_pps::CrazyflieContext my_context;
 
     // PUBLISHERS AND SUBSRIBERS
     // > For Crazyradio commands based on button clicks
     ros::Publisher crazyRadioCommandPublisher;
     // > For updating the "rf_status_label" picture
     ros::Subscriber crazyRadioStatusSubscriber;
+
     // > For updating the current battery voltage
     ros::Subscriber batteryVoltageSubscriber;
     // > For updating the current battery state
     //ros::Subscriber batteryStateSubscriber;
     // > For updating the current battery level
     ros::Subscriber batteryLevelSubscriber;
+
     // > For Flying state commands based on button clicks
     ros::Publisher flyingStateCommandPublisher;
     // > For updating the "flying_state_label" picture
     ros::Subscriber flyingStateSubscriber;
+
     // > For changes in the database that defines {agentID,cfID,flying zone} links
     ros::Subscriber databaseChangedSubscriber;
     ros::ServiceClient centralManagerDatabaseService;
@@ -188,19 +196,30 @@ private:
     // --------------------------------------------------- //
     // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
 
-    // > For the CrazyRadio status, received on the "crazyRadioStatusSubscriber"
+    // > For the CrazyRadio status, received on the
+    //   "crazyRadioStatusSubscriber"
     void crazyRadioStatusCallback(const std_msgs::Int32& msg);
-    // > For the Battery Voltage, received on the "batteryVoltageSubscriber"
+
+    // > For the Battery Voltage, received on the
+    //   "batteryVoltageSubscriber"
     void batteryVoltageCallback(const std_msgs::Float32& msg);
-    // > For the Battery State, receieved on the "batteryStateSubscriber"
+    // > For the Battery State, receieved on the
+    //   "batteryStateSubscriber"
     void batteryStateChangedCallback(const std_msgs::Int32& msg);
-    // > For the Battery Level, receieved on the "batteryLevelSubscriber"
+    // > For the Battery Level, receieved on the
+    //   "batteryLevelSubscriber"
     void batteryLevelCallback(const std_msgs::Int32& msg);
-    // > For the Flying State, received on the "flyingStateSubscriber"
+
+    // > For the Flying State, received on the
+    //   "flyingStateSubscriber"
     void flyingStateChangedCallback(const std_msgs::Int32& msg);
-    // > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
+
+    // > For the notification that the database was changes,
+    //   received on the "DatabaseChangedSubscriber"
     void databaseChangedCallback(const std_msgs::Int32& msg);
-    // > For the controller currently operating, received on "controllerUsedSubscriber"
+
+    // > For the controller currently operating, received on
+    //   "controllerUsedSubscriber"
     void controllerUsedChangedCallback(const std_msgs::Int32& msg);
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 3df7eddd..d04e939b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -12,10 +12,11 @@
 // Include the standard message types
 #include "std_msgs/Int32.h"
 #include "std_msgs/Float32.h"
-//#include <std_msgs/String.h>
+#include <std_msgs/String.h>
 
 // Include the DFALL message types
 #include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/StringWithHeader.h"
 
 // Include the DFALL service types
 // #include "d_fall_pps/AreaBounds.h"
@@ -102,14 +103,18 @@ private:
     // PUBLISHERS AND SUBSRIBERS
     // > For {take-off,land,motors-off} and controller selection
     ros::Publisher commandPublisher;
+    // > For requesting the loading of yaml files
+    ros::Publisher m_requestLoadYamlFilenamePublisher;
+
 #endif
 
     // --------------------------------------------------- //
     // PRIVATE FUNCTIONS
 
 #ifdef CATKIN_MAKE
-    // Fill the head for a message
+    // Fill the header for a message
     void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
+    void fillStringMessageHeader( d_fall_pps::StringWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index 684801fb..7a7b3e3a 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -1,8 +1,67 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The title displayed at the top of the GUI
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef TOPBANNER_H
 #define TOPBANNER_H
 
 #include <QWidget>
 
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/AreaBounds.h"
+#include "d_fall_pps/CrazyflieContext.h"
+#include "d_fall_pps/CMQuery.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#endif
+
 namespace Ui {
 class TopBanner;
 }
@@ -16,7 +75,57 @@ public:
     ~TopBanner();
 
 private:
+	// --------------------------------------------------- //
+    // PRIVATE VARIABLES
     Ui::TopBanner *ui;
+
+    // > For the type of this node,
+    //   i.e., an agent or a coordinator
+	int m_type = 0;
+
+	// > For the ID of this node
+	int m_ID = 0;
+
+	// The namespace into which node operates
+	std::string m_base_namespace;
+
+
+
+	// --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+    // > For loading the "context" for this agent,
+    //   i.e., the {agentID,cfID,flying zone} tuple
+    void loadCrazyflieContext();
+
+
+
+    #ifdef CATKIN_MAKE
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES FOR ROS
+
+    // > For the "context" of this agent
+    d_fall_pps::CrazyflieContext my_context;
+
+    // PUBLISHERS AND SUBSRIBERS
+
+    // > For changes in the database that defines {agentID,cfID,flying zone} links
+    ros::Subscriber databaseChangedSubscriber;
+    ros::ServiceClient centralManagerDatabaseService;
+
+
+    // --------------------------------------------------- //
+    // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
+
+    // Get the type and ID of this node
+    bool getTypeAndIDParameters();
+
+    // > For the notification that the database was changes,
+    //   received on the "DatabaseChangedSubscriber"
+    void databaseChangedCallback(const std_msgs::Int32& msg);
+
+
+#endif
 };
 
 #endif // TOPBANNER_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 1e842c83..f06c2875 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -50,8 +50,8 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
 
 #ifdef CATKIN_MAKE
     // Get the namespace of this node
-    std::string this_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << this_namespace);
+    std::string base_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << base_namespace);
 
 
     // Get the type and ID of this parameter service
@@ -98,7 +98,7 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
 
 #ifdef CATKIN_MAKE
     // CREATE A NODE HANDLE TO THE BASE NAMESPACE
-    ros::NodeHandle base_nodeHandle(this_namespace);
+    ros::NodeHandle base_nodeHandle(base_namespace);
 
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
@@ -132,10 +132,11 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
 
     // FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
     // INITIALISATIONS ARE COMPLETE
-    if (m_type == TYPE_AGENT)
-    {
+    //if (m_type == TYPE_AGENT)
+    //{
+        // The loading of the "Context" is handled by the "topbanner"
         //loadCrazyflieContext();
-    }
+    //}
 
     // ADD KEYBOARD SHORTCUTS
     // > For "all motors off", press the space bar
@@ -152,17 +153,17 @@ ConnectStartStopBar::~ConnectStartStopBar()
 // > For making the "enable flight" and "disable flight" buttons unavailable
 void ConnectStartStopBar::disableFlyingStateButtons()
 {
-    //ui->motors_off_button->setEnabled(true);
-    //ui->enable_flying_button->setEnabled(false);
-    //ui->disable_flying_button->setEnabled(false);
+    ui->motors_off_button->setEnabled(true);
+    ui->enable_flying_button->setEnabled(false);
+    ui->disable_flying_button->setEnabled(false);
 }
 
 // > For making the "enable flight" and "disable flight" buttons available
 void ConnectStartStopBar::enableFlyingStateButtons()
 {
-    //ui->motors_off_button->setEnabled(true);
-    //ui->enable_flying_button->setEnabled(true);
-    //ui->disable_flying_button->setEnabled(true);
+    ui->motors_off_button->setEnabled(true);
+    ui->enable_flying_button->setEnabled(true);
+    ui->disable_flying_button->setEnabled(true);
 }
 
 
@@ -473,7 +474,6 @@ void ConnectStartStopBar::setFlyingState(int new_flying_state)
 
         case STATE_LAND:
         {
-            //qstr.append("Land");
             // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
             QPixmap flying_state_disabling_pixmap(":/images/flying_state_disabling.png");
             ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index fe437e64..da14cfc0 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -62,9 +62,9 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     m_agentID_as_string = QString::number(m_agentID).rightJustified(3, '0');
 
     // CONVERT THE AGENT ID TO A STRING FOR THE BASE NAMESPACE
-    QString qstr_ros_base_namespace = "/dfall/agent";
-    qstr_ros_base_namespace.append(m_agentID_as_string);
-    std::string ros_base_namespace = qstr_ros_base_namespace.toStdString();
+    QString qstr_base_namespace = "/dfall/agent";
+    qstr_base_namespace.append(m_agentID_as_string);
+    std::string base_namespace = qstr_base_namespace.toStdString();
 
     // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
     // > For keeping track of the current battery state
@@ -90,52 +90,43 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
 
 
 #ifdef CATKIN_MAKE
-    //m_rosNodeThread = new rosNodeThread(argc, argv, "coordinatorRowGUI");
-    //m_rosNodeThread->init();
-
-    //m_ros_namespace = ros::this_node::getNamespace();
-
-    //qRegisterMetaType<ptrToMessage>("ptrToMessage");
-    //QObject::connect(m_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const ptrToMessage&)));
-
-    //ros::NodeHandle nodeHandle(m_ros_namespace);
-
-    // 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");
-
 
     // LET THE USER KNOW WHAT THE BASE NAMESPACE IS
-    ROS_INFO_STREAM("[COORDINATOR ROW GUI] using base namespace: " << ros_base_namespace.c_str() << ", for agentID = " << m_agentID);
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] using base namespace: " << base_namespace.c_str() << ", for agentID = " << m_agentID);
 
     // DEBUGGING FOR NAMESPACES
     //std::string temp_ros_namespace = ros::this_node::getNamespace();
     //ROS_INFO_STREAM("[COORDINATOR ROW GUI] compared to: ros::this_node::getNamespace() = " << temp_ros_namespace.c_str());
 
     // CREATE A NODE HANDLE TO THE BASE NAMESPACE
-    ros::NodeHandle base_nodeHandle(ros_base_namespace);
+    ros::NodeHandle base_nodeHandle(base_namespace);
 
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
     // SUBSCRIBERS AND PUBLISHERS:
+
     // > For Crazyradio commands based on button clicks
     crazyRadioCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
     // > For updating the "rf_status_label" picture
     crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &CoordinatorRow::crazyRadioStatusCallback, this);
+
     // > For updating the current battery voltage
     batteryVoltageSubscriber = base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &CoordinatorRow::batteryVoltageCallback, this);
     // > For updating the current battery state
     //batteryStateSubscriber = base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &CoordinatorRow::batteryStateChangedCallback, this);
     // > For updating the current battery level
     batteryLevelSubscriber = base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &CoordinatorRow::batteryLevelCallback, this);
+
     // > For Flying state commands based on button clicks
     flyingStateCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
     // > For updating the "flying_state_label" picture
     flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/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<CMQuery>("CentralManagerService/Query", false);
+    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+
     // > For updating the controller that is currently operating
     controllerUsedSubscriber = base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
 
@@ -145,9 +136,6 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     // INITIALISATIONS ARE COMPLETE
     loadCrazyflieContext();
 
-    // FOR DEBUGGING:
-    //ui->shouldCoordinate_checkBox->setText(m_agentID_as_string);
-    //ui->shouldCoordinate_checkBox->setText(QString::fromStdString(base_namespace));
 }
 
 CoordinatorRow::~CoordinatorRow()
@@ -546,7 +534,6 @@ void CoordinatorRow::setFlyingState(int new_flying_state)
 
         case STATE_LAND:
         {
-            //qstr.append("Land");
             // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
             QPixmap flying_state_disabling_pixmap(":/images/flying_state_disabling.png");
             ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
@@ -569,6 +556,13 @@ void CoordinatorRow::setFlyingState(int new_flying_state)
 
 
 
+//    ----------------------------------------------------------------------------------
+//     CCCC   OOO   N   N  TTTTT  EEEEE  X   X  TTTTT
+//    C      O   O  NN  N    T    E       X X     T
+//    C      O   O  N N N    T    EEE      X      T
+//    C      O   O  N  NN    T    E       X X     T
+//     CCCC   OOO   N   N    T    EEEEE  X   X    T
+//    ----------------------------------------------------------------------------------
 
 
 
@@ -587,7 +581,7 @@ void CoordinatorRow::loadCrazyflieContext()
 {
     QString qstr_crazyflie_name = "";
 #ifdef CATKIN_MAKE
-    CMQuery contextCall;
+    d_fall_pps::CMQuery contextCall;
     contextCall.request.studentID = m_agentID;
     //ROS_INFO_STREAM("StudentID:" << m_agentID);
 
@@ -596,13 +590,13 @@ void CoordinatorRow::loadCrazyflieContext()
     if(centralManagerDatabaseService.call(contextCall))
     {
         my_context = contextCall.response.crazyflieContext;
-        ROS_INFO_STREAM("[COORDINATOR ROW GUI] CrazyflieContext:\n" << my_context);
+        ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] CrazyflieContext:\n" << my_context);
 
         qstr_crazyflie_name.append(QString::fromStdString(my_context.crazyflieName));
     }
     else
     {
-        ROS_ERROR_STREAM("[COORDINATOR ROW GUI] Failed to load context for agentID = " << m_agentID);
+        ROS_ERROR_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Failed to load context for agentID = " << m_agentID);
     }
     // This updating of the radio only needs to be done by the actual agent's node
     //ros::NodeHandle nh("CrazyRadio");
@@ -624,6 +618,18 @@ void CoordinatorRow::loadCrazyflieContext()
 }
 
 
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
+//    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
+//    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
+//    C      O   O  N  NN    T    R   R  O   O  L      L      E      R   R
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL  LLLLL  EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
 #ifdef CATKIN_MAKE
 // > For the controller currently operating, received on "controllerUsedSubscriber"
 void CoordinatorRow::controllerUsedChangedCallback(const std_msgs::Int32& msg)
@@ -697,7 +703,7 @@ void CoordinatorRow::on_rf_connect_button_clicked()
     msg.shouldCheckForID = false;
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[COORDINATOR ROW GUI] Command to RF reconnect published");
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Connect button clicked");
 #endif
 }
 
@@ -708,7 +714,7 @@ void CoordinatorRow::on_rf_disconnect_button_clicked()
     msg.shouldCheckForID = false;
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("[COORDINATOR ROW GUI] Command to RF disconnect published");
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disconnect button clicked");
 #endif
 }
 
@@ -719,6 +725,7 @@ void CoordinatorRow::on_enable_flying_button_clicked()
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Enable flying button clicked");
 #endif
 }
 
@@ -729,6 +736,7 @@ void CoordinatorRow::on_disable_flying_button_clicked()
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disable flying button clicked");
 #endif
 }
 
@@ -739,6 +747,7 @@ void CoordinatorRow::on_motors_off_button_clicked()
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
+    ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Motors-off button clicked");
 #endif
 }
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 6eaaa3cf..e0c49054 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -31,6 +31,10 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
 
     // CREATE THE COMMAND PUBLISHER
     commandPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
+
+    // CREATE THE REQUEST LOAD YAML FILE PUBLISHER
+    // Get the node handle to this parameter service
+    m_requestLoadYamlFilenamePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::StringWithHeader>("ParameterService/requestLoadYamlFilename", 1);
 #endif
 
 }
@@ -94,17 +98,41 @@ void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 
 void EnableControllerLoadYamlBar::on_load_yaml_safe_button_clicked()
 {
+#ifdef CATKIN_MAKE
 
+#endif
 }
 
 void EnableControllerLoadYamlBar::on_load_yaml_demo_button_clicked()
 {
-
+#ifdef CATKIN_MAKE
+    // Create a local variable for the message
+    d_fall_pps::StringWithHeader yaml_filename_msg;
+    // Set for whom this applies to
+    fillStringMessageHeader(yaml_filename_msg);
+    // Specify the data
+    yaml_filename_msg.data = "DemoController";
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+    // Inform the user that the menu item was selected
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Demo Controller YAML was clicked.");
+#endif
 }
 
 void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
 {
-
+#ifdef CATKIN_MAKE
+    // Create a local variable for the message
+    d_fall_pps::StringWithHeader yaml_filename_msg;
+    // Set for whom this applies to
+    fillStringMessageHeader(yaml_filename_msg);
+    // Specify the data
+    yaml_filename_msg.data = "StudentController";
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+    // Inform the user that the menu item was selected
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Student Controller YAML was clicked.");
+#endif
 }
 
 void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
@@ -215,6 +243,50 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade
 
 
 
+#ifdef CATKIN_MAKE
+// Fill the head for a message
+void EnableControllerLoadYamlBar::fillStringMessageHeader( d_fall_pps::StringWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForID = true;
+            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+
+
+
 
 //    ----------------------------------------------------------------------------------
 //    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 4c71863d..771eed6b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -1,14 +1,295 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The title displayed at the top of the GUI
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "topbanner.h"
 #include "ui_topbanner.h"
 
+
+
+
+
 TopBanner::TopBanner(QWidget *parent) :
     QWidget(parent),
     ui(new Ui::TopBanner)
 {
     ui->setupUi(this);
+
+
+#ifdef CATKIN_MAKE
+    // Get the namespace of this node
+    std::string base_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << base_namespace);
+
+
+    // Get the type and ID of this parameter service
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the TYPE and ID are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[CONNECT START STOP GUI BAR] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+#else
+    // Default as a coordinator when compiling with QtCreator
+    m_type = TYPE_COORDINATOR;
+    m_ID = 1;
+#endif
+
+
+
+#ifdef CATKIN_MAKE
+    // CREATE A NODE HANDLE TO THE BASE NAMESPACE
+    //ros::NodeHandle base_nodeHandle(base_namespace);
+
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle dfall_root_nodeHandle("/dfall");
+
+    // SUBSCRIBER AND SERVICE:
+    if (m_type == TYPE_AGENT)
+    {
+    	// > For changes in the database that defines {agentID,cfID,flying zone} links
+    	databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
+    	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+    }
+#endif
+
+
+    // FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
+    // INITIALISATIONS ARE COMPLETE
+    if (m_type == TYPE_AGENT)
+    {
+    	loadCrazyflieContext();
+    }
+    else if (m_type == TYPE_COORDINATOR)
+    {
+		// Set the label appropriate for a cooridnator
+		QString qstr_title = "Flying Device GUI: for COORDINATOR ID ";
+		qstr_title.append( QString::number(m_ID) );
+		ui->top_banner_label->setText(qstr_title);
+	}
+	else
+	{
+		// Set the label to inform the user of the error
+		QString qstr_title = "Flying Device GUI: for UNKNOWN NODE TYPE";
+		ui->top_banner_label->setText(qstr_title);
+    }
+
 }
 
 TopBanner::~TopBanner()
 {
     delete ui;
 }
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC   OOO   N   N  TTTTT  EEEEE  X   X  TTTTT
+//    C      O   O  NN  N    T    E       X X     T
+//    C      O   O  N N N    T    EEE      X      T
+//    C      O   O  N  NN    T    E       X X     T
+//     CCCC   OOO   N   N    T    EEEEE  X   X    T
+//    ----------------------------------------------------------------------------------
+
+
+
+// RESPONDING TO CHANGES IN THE DATABASE
+#ifdef CATKIN_MAKE
+// > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
+void TopBanner::databaseChangedCallback(const std_msgs::Int32& msg)
+{
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Database Changed Callback called for agentID = " << m_agentID);
+    loadCrazyflieContext();
+}
+#endif
+
+// > For loading the "context" for this agent, i.e., the {agentID,cfID,flying zone} tuple
+void TopBanner::loadCrazyflieContext()
+{
+
+    QString qstr_crazyflie_name = "";
+
+	if (m_type == TYPE_AGENT)
+	{
+
+#ifdef CATKIN_MAKE
+		d_fall_pps::CMQuery contextCall;
+		contextCall.request.studentID = m_ID;
+		//ROS_INFO_STREAM("StudentID:" << m_agentID);
+
+		centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
+
+		if(centralManagerDatabaseService.call(contextCall))
+		{
+			my_context = contextCall.response.crazyflieContext;
+			ROS_INFO_STREAM("[TOP BANNER GUI] CrazyflieContext:\n" << my_context);
+
+			qstr_crazyflie_name.append(QString::fromStdString(my_context.crazyflieName));
+		}
+		else
+		{
+			ROS_ERROR_STREAM("[TOP BANNER GUI] Failed to load context for agentID = " << m_ID);
+		}
+		// This updating of the radio only needs to be done by the actual agent's node
+		//ros::NodeHandle nh("CrazyRadio");
+		//nh.setParam("crazyFlieAddress", m_context.crazyflieAddress);
+#else
+		// Set the Crazyflie Name String to be a question mark
+		qstr_crazyflie_name.append("?");
+#endif
+
+		// Construct and set the string for the checkbox label
+		QString qstr_title = "Flying Device GUI: for AGENT ID ";
+		qstr_title.append( QString::number(m_ID) );
+		qstr_title.append(", connected to ");
+		qstr_title.append(qstr_crazyflie_name);
+		ui->top_banner_label->setText(qstr_title);
+
+	}
+	else
+	{
+#ifdef CATKIN_MAKE
+		ROS_ERROR("[TOP BANNER GUI] loadCrazyflieContext called by a node that is NOT of type AGENT.");
+#endif
+		qstr_crazyflie_name.append("??");
+	}
+
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool TopBanner::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[CONNECT START STOP GUI BAR] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_ID"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_ID"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[CONNECT START STOP GUI BAR] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index 13de6248..7b2850f4 100755
--- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -296,15 +296,13 @@ class PPSRadioClient:
     def crazyRadioCommandCallback(self, msg):
         """Callback to tell CrazyRadio to reconnect"""
 
-        print "[CRAZY RADIO]  DEBUGGING received command"
-
         # Initialise a boolean flag that the command is NOT relevant
         command_is_relevant = False
 
         # Check the header details of the message for it relevance
-        if (!msg.shouldCheckForID):
+        if (msg.shouldCheckForID == False):
             command_is_relevant = True
-        else
+        else:
             for this_ID in msg.agentIDs:
                 if (this_ID == m_agentID):
                     command_is_relevant = True
@@ -398,6 +396,8 @@ if __name__ == '__main__':
     global cf_client
     cf_client = PPSRadioClient()
 
+    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
@@ -410,6 +410,7 @@ if __name__ == '__main__':
 
     rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
 
+    print "[CRAZY RADIO] Node READY :-)"
     rospy.spin()
     rospy.loginfo("[CRAZY RADIO] Turning off crazyflie")
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/Constants.h b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
index ac3ecb91..2962a8b3 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/Constants.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
@@ -30,6 +30,9 @@
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 //    ----------------------------------------------------------------------------------
 //    U   U
 //    U   U
@@ -49,11 +52,54 @@
 
 
 
-// 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
 
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
 // Types of controllers being used:
 #define SAFE_CONTROLLER      1
 #define DEMO_CONTROLLER      2
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
index 7d9f8254..e82252a9 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
@@ -50,7 +50,14 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
 //the generated structs from the msg-files have to be included
+#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/StringWithHeader.h"
 #include "d_fall_pps/ViconData.h"
 #include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
@@ -61,7 +68,18 @@
 // Include the Parameter Service shared definitions
 #include "nodes/Constants.h"
 
-#include <std_msgs/Int32.h>
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+// Need for having a ROS "bag" to store data for post-analysis
+//#include <rosbag/bag.h>
+
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
 
 
 
@@ -77,23 +95,33 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// These constants define the modes that can be used for controller the Crazyflie 2.0,
-// the constants defined here need to be in agreement with those defined in the
-// firmware running on the Crazyflie 2.0.
+// 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:
-// MOTOR_MODE    In this mode the Crazyflie will apply the requested 16-bit per motor
-//               command directly to each of the motors
-// RATE_MODE     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.
-// ANGE_MODE     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_MOTOR   6
-#define CF_COMMAND_TYPE_RATE    7
-#define CF_COMMAND_TYPE_ANGLE   8
+//
+// 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
+
+
+
 
 
 // These constants define the controller used for computing the response in the
@@ -122,6 +150,9 @@
 #define CONTROLLER_MODE_ANGLE_RESPONSE_TEST     6
 
 
+
+
+
 // These constants define the method used for estimating the Inertial
 // frame state.
 // All methods are run at all times, this flag indicates which estimate
@@ -145,10 +176,6 @@
 #define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3
 
 
-// Namespacing the package
-using namespace d_fall_pps;
-
-
 
 
 
@@ -289,9 +316,9 @@ std::vector<float> PMKF_Kinf_for_angles         (2,0.0);
 
 // VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
 // > For the paramter service of this agent
-std::string namespace_to_own_agent_parameter_service;
+std::string m_namespace_to_own_agent_parameter_service;
 // > For the parameter service of the coordinator
-std::string namespace_to_coordinator_parameter_service;
+std::string m_namespace_to_coordinator_parameter_service;
 
 
 // ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
@@ -317,7 +344,10 @@ bool shouldDisplayDebugInfo = false;
 // POSITION
 
 // The ID of this agent, i.e., the ID of this compute
-int my_agentID = 0;
+int m_agentID = 0;
+
+// The ID of this agent, i.e., the ID of this compute
+int m_coordID = 0;
 
 // Boolean indicating whether the (x,y,z,yaw) of this agent should be published or not
 // > The default behaviour is: do not publish,
@@ -429,14 +459,7 @@ void customCommandReceivedCallback(const CustomButton& commandReceived);
 void publish_current_xyz_yaw(float x, float y, float z, float yaw);
 
 // LOAD PARAMETERS
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-void  getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-int   getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-void  getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-int   getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-bool  getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParameters(ros::NodeHandle& nodeHandle);
+void isReadyDemoControllerYamlCallback(const IntWithHeader & msg);
+void fetchDemoControllerYamlParameters(ros::NodeHandle& nodeHandle);
 void processFetchedParameters();
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
index 9793c7ef..c59b6c4b 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -63,7 +63,7 @@
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/CMQuery.h"
 
-// Include the Parameter Service shared definitions
+// Include the shared definitions
 #include "nodes/Constants.h"
 
 // Include other classes
@@ -72,7 +72,12 @@
 // Need for having a ROS "bag" to store data for post-analysis
 //#include <rosbag/bag.h>
 
-#include "d_fall_pps/ControlCommand.h"
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
 
 
 
@@ -88,8 +93,7 @@
 
 
 
-// Namespacing the package
-using namespace d_fall_pps;
+
 
 
 
@@ -244,10 +248,16 @@ ros::Timer timer_land;
 
 
 // > For the LOAD PARAMETERS
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle);
-void fetchClientConfigParameters(ros::NodeHandle& nodeHandle);
+//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
+//void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle);
+//void fetchClientConfigParameters(ros::NodeHandle& nodeHandle);
 
+// > For the LOADING of YAML PARAMETERS
+void isReadySafeControllerYamlCallback(const IntWithHeader & msg);
+void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle);
+
+void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
+void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
 
 
 
@@ -291,17 +301,4 @@ int getControllerUsed();
 //void setBatteryStateTo(int new_battery_state);
 //float movingAverageBatteryFilter(float new_input);
 //void CFBatteryCallback(const std_msgs::Float32& msg);
-void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
-
-
-// > For the LOADING of YAML PARAMETERS
-void isReadySafeControllerYamlCallback(const IntWithHeader & msg);
-void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle);
-
-void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
-void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
-
-
-
-
-
+void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
index 6ead6b7f..343141f7 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
@@ -48,19 +48,35 @@
 #include "ros/ros.h"
 #include <std_msgs/String.h>
 #include <ros/package.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
 #include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
 
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/CrazyflieData.h"
 #include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/Controller.h"
-#include "d_fall_pps/LoadYamlFiles.h"
 
-#include <std_msgs/Int32.h>
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
+
+
+
 
 
 //    ----------------------------------------------------------------------------------
@@ -73,26 +89,36 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// The constants define the modes that can be used for controller the Crazyflie 2.0,
-// the constants defined here need to be in agreement with those defined in the
-// firmware running on the Crazyflie 2.0.
+
+// NOTE: these constants are already defined in the "Constant.h" header file
+//       and are repeated here for convenience
+
+// 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:
-// MOTOR_MODE    In this mode the Crazyflie will apply the requested 16-bit per motor
-//               command directly to each of the motors
-// RATE_MODE     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.
-// ANGE_MODE     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 MOTOR_MODE 6
-#define RATE_MODE  7
-#define ANGLE_MODE 8
+//
+// 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
+
 
-// Namespacing the package
-using namespace d_fall_pps;
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 20368011..8eea640a 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -50,7 +50,14 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
 //the generated structs from the msg-files have to be included
+#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/StringWithHeader.h"
 #include "d_fall_pps/ViconData.h"
 #include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
@@ -58,10 +65,21 @@
 #include "d_fall_pps/DebugMsg.h"
 #include "d_fall_pps/CustomButton.h"
 
-// Include the Parameter Service shared definitions
+// Include the shared definitions
 #include "nodes/Constants.h"
 
-#include <std_msgs/Int32.h>
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+// Need for having a ROS "bag" to store data for post-analysis
+//#include <rosbag/bag.h>
+
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
 
 
 
@@ -77,38 +95,38 @@
 
 // These constants are defined to make the code more readable and adaptable.
 
-// These constants define the modes that can be used for controller the Crazyflie 2.0,
-// the constants defined here need to be in agreement with those defined in the
-// firmware running on the Crazyflie 2.0.
-// The following is a short description about each mode:
-// MOTOR_MODE    In this mode the Crazyflie will apply the requested 16-bit per motor
-//               command directly to each of the motors
-// RATE_MODE     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.
-// ANGE_MODE     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 MOTOR_MODE 6
-#define RATE_MODE  7
-#define ANGLE_MODE 8
-
-// These constants define the controller used for computing the response in the
-// "calculateControlOutput" function
+
+
+// NOTE: these constants are already defined in the "Constant.h" header file
+//       and are repeated here for convenience
+
+// 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:
-// LQR_RATE_MODE      LQR controller based on the state vector:
-//                    [position,velocity,angles]
 //
-// LQR_ANGLE_MODE     LQR controller based on the state vector:
-//                    [position,velocity]
+// CF_COMMAND_TYPE_MOTORS
+//     In this mode the Crazyflie will apply the requested 16-bit per motor
+//     command directly to each of the motors
 //
-#define LQR_RATE_MODE   1   // (DEFAULT)
-#define LQR_ANGLE_MODE  2
+// 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
+
+
 
-// Namespacing the package
-using namespace d_fall_pps;
 
 
 
@@ -122,36 +140,43 @@ using namespace d_fall_pps;
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// The ID of the agent that can coordinate this node
+int m_coordID;
+
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
+
+
+
 // Variables for controller
-float cf_mass_in_grams = 25.0;         // Crazyflie mass in grams
-std::vector<float> motorPoly(3);       // Coefficients of the 16-bit command to thrust conversion
-float control_frequency = 200.0;       // Frequency at which the controller is running
-float cf_weight_in_newtons = 0.0;      // The weight of the Crazyflie in Newtons, i.e., mg
+float yaml_cf_mass_in_grams = 25.0;         // Crazyflie mass in grams
+std::vector<float> yaml_motorPoly(3);       // Coefficients of the 16-bit command to thrust conversion
+float yaml_control_frequency = 200.0;       // Frequency at which the controller is running
+float m_cf_weight_in_newtons = 0.0;      // The weight of the Crazyflie in Newtons, i.e., mg
 
-float previous_stateErrorInertial[9];  // The location error of the Crazyflie at the "previous" time step
+float m_previous_stateErrorInertial[9];  // The location error of the Crazyflie at the "previous" time step
 
-std::vector<float>  setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
 
 
 // The LQR Controller parameters for "LQR_RATE_MODE"
-std::vector<float> gainMatrixRollRate    =  { 0.00,-1.71, 0.00, 0.00,-1.33, 0.00, 5.12, 0.00, 0.00};
-std::vector<float> gainMatrixPitchRate   =  { 1.71, 0.00, 0.00, 1.33, 0.00, 0.00, 0.00, 5.12, 0.00};
-std::vector<float> gainMatrixYawRate     =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.84};
-std::vector<float> gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.08, 0.00, 0.00, 0.00};
+std::vector<float> m_gainMatrixRollRate    =  { 0.00,-1.71, 0.00, 0.00,-1.33, 0.00, 5.12, 0.00, 0.00};
+std::vector<float> m_gainMatrixPitchRate   =  { 1.71, 0.00, 0.00, 1.33, 0.00, 0.00, 0.00, 5.12, 0.00};
+std::vector<float> m_gainMatrixYawRate     =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.84};
+std::vector<float> m_gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.08, 0.00, 0.00, 0.00};
 
 
 // ROS Publisher for debugging variables
-ros::Publisher debugPublisher;
-
-
-// Variable for the namespaces for the paramter services
-// > For the paramter service of this agent
-std::string namespace_to_own_agent_parameter_service;
-// > For the parameter service of the coordinator
-std::string namespace_to_coordinator_parameter_service;
+ros::Publisher m_debugPublisher;
 
-// The ID of this agent, i.e., the ID of this compute
-int my_agentID = 0;
 
 
 // RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
@@ -186,11 +211,12 @@ int my_agentID = 0;
 //    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// These function prototypes are not strictly required for this code to complile, but
-// adding the function prototypes here means the the functions can be written below in
-// any order. If the function prototypes are not included then the function need to
-// written below in an order that ensure each function is implemented before it is
-// called from another function, hence why the "main" function is at the bottom.
+// These function prototypes are not strictly required for this code to
+// complile, but adding the function prototypes here means the the functions
+// can be written below in any order. If the function prototypes are not
+// included then the function need to written below in an order that ensure
+// each function is implemented before it is called from another function,
+// hence why the "main" function is at the bottom.
 
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
@@ -207,15 +233,21 @@ void setpointCallback(const Setpoint& newSetpoint);
 // CUSTOM COMMAND RECEIVED CALLBACK
 void customCommandReceivedCallback(const CustomButton& commandReceived);
 
+
+// > For the LOADING of YAML PARAMETERS
+void isReadyStudentControllerYamlCallback(const IntWithHeader & msg);
+void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle);
+
+
 // LOAD PARAMETERS
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-void processFetchedParameters();
+//float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
+//void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
+//int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
+//void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
+//int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
+//bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
+
+//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
+//void fetchYamlParameters(ros::NodeHandle& nodeHandle);
+//void processFetchedParameters();
 //void customYAMLasMessageCallback(const CustomControllerYAML& newCustomControllerParameters);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index ef9305a7..942ee8ad 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -74,15 +74,6 @@
 			>
 		</node>
 
-		<!-- MPC CONTROLLER -->
-		<node
-			pkg    = "d_fall_pps"
-			name   = "MpcControllerService"
-			output = "screen"
-			type   = "MpcControllerService"
-			>
-		</node>
-
 		<!-- REMOTE CONTROLLER -->
 		<node
 			pkg    = "d_fall_pps"
@@ -134,21 +125,6 @@
 				file    = "$(find d_fall_pps)/param/SafeController.yaml"
 				ns      = "SafeController"
 			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/DemoController.yaml"
-				ns      = "DemoController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/StudentController.yaml"
-				ns      = "StudentController"
-			/>
-			<rosparam
-				command = "load"
-				file    = "$(find d_fall_pps)/param/MpcController.yaml"
-				ns      = "MpcController"
-			/>
 			<rosparam
 				command = "load"
 				file    = "$(find d_fall_pps)/param/RemoteController.yaml"
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
index a4ffa564..d8b8aebf 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
@@ -113,22 +113,30 @@
 //     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
 // 
 // 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:
-//   CF_COMMAND_TYPE_MOTOR
-//   CF_COMMAND_TYPE_RATE
-//   CF_COMMAND_TYPE_ANGLE.
-// > With CF_COMMAND_TYPE_RATE 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.
-// > With CF_COMMAND_TYPE_RATE the ".motorCmd1" to ".motorCmd4" properties of "response.ControlCommand"
-//   are the baseline motor commands requested from the Crazyflie, with the adjustment
-//   for body rates being added on top of this in the firmware (i.e., as per the code
-//   of the "distribute_power" function provided in exercise sheet 2).
-// > With CF_COMMAND_TYPE_RATE the axis convention for the roll, pitch, and yaw body rates returned
-//   in "response.ControlCommand" should use right-hand coordinate axes with x-forward
-//   and z-upwards (i.e., the positive z-axis is aligned with the direction of positive
-//   thrust). To assist, teh following is an ASCII art of this convention:
+// > The allowed values for "onboardControllerType" are in the "Defines"
+//   section in the header file, they are:
+//   - CF_COMMAND_TYPE_MOTORS
+//   - CF_COMMAND_TYPE_RATE
+//   - CF_COMMAND_TYPE_ANGLE
+//
+// > For completeing the class exercises it is only required to use
+//   the CF_COMMAND_TYPE_RATE option.
+//
+// > For the CF_COMMAND_TYPE_RATE optoin:
+//   1) 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.
+//   2) the ".motorCmd1" to ".motorCmd4" properties of
+//      "response.ControlCommand" are the baseline motor commands
+//      requested from the Crazyflie, with the adjustment for body rates
+//      being added on top of this in the firmware (i.e., as per the
+//      code of the "distribute_power" found in the firmware).
+//   3) the axis convention for the roll, pitch, and yaw body rates
+//      returned in "response.ControlCommand" should use right-hand
+//      coordinate axes with x-forward and z-upwards (i.e., the positive
+//      z-axis is aligned with the direction of positive thrust). To
+//      assist, the following is an ASCII art of this convention.
 //
 // ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
 //
@@ -459,7 +467,7 @@ void calculateControlOutput_viaLQR(float stateErrorBody[12], Controller::Request
 			response.controlOutput.motorCmd2  =  0;
 			response.controlOutput.motorCmd3  =  0;
 			response.controlOutput.motorCmd4  =  0;
-			response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+			response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 			break;
 		}
 	}
@@ -542,7 +550,7 @@ void calculateControlOutput_viaLQRforMotors(float stateErrorBody[12], Controller
 
 	
 	// Specify that this controller is a rate controller
-	 response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	 response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -633,7 +641,7 @@ void calculateControlOutput_viaLQRforActuators(float stateErrorBody[12], Control
 
 	
 	// Specify that this controller is a rate controller
-	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -730,7 +738,7 @@ void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller:
 
 	
 	// Specify that this controller is a rate controller
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -816,7 +824,7 @@ void calculateControlOutput_viaLQRforAngles(float stateErrorBody[12], Controller
 
 	
 	// Specify that this controller is a rate controller
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -921,7 +929,7 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 
 	
 	// Specify that this controller is a rate controller
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -1055,7 +1063,7 @@ void calculateControlOutput_viaAngleResponseTest( float stateErrorBody[12], Cont
 
 	
 	// Specify that this controller is a rate controller
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
@@ -1443,94 +1451,97 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+// This function DOES NOT NEED TO BE edited for successful completion
+// ofthe exercise
+void isReadyDemoControllerYamlCallback(const IntWithHeader & msg)
 {
-	// Extract from the "msg" for which controller the and from where to fetch the YAML
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
+	// Continue if the message is relevant
+	if (isRevelant)
 	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT:
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
 		{
-			// Let the user know that this message was received
-			ROS_INFO("[DEMO CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[DEMO CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[DEMO CONTROLLER] Now fetching the DemoController 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("[DEMO CONTROLLER] Now fetching the DemoController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
 
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The DemoControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
+			default:
+			{
+				ROS_ERROR("[STUDENT CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
 		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchDemoControllerYamlParameters(nodeHandle_to_use);
 	}
 }
 
 
+
 // This function CAN BE edited for successful completion of the PPS 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)
+void fetchDemoControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
-	// Here we load the parameters that are specified in the DemoController.yaml file
+	// Here we load the parameters that are specified in the file:
+	// DemoController.yaml file
 
 	// Add the "DemoController" namespace to the "nodeHandle"
-	ros::NodeHandle nodeHandle_for_demoController(nodeHandle, "DemoController");
+	ros::NodeHandle nodeHandle_for_paraMaters(nodeHandle, "DemoController");
 
 	// > The mass of the crazyflie
-	cf_mass = getParameterFloat(nodeHandle_for_demoController , "mass");
+	cf_mass = getParameterFloat(nodeHandle_for_paraMaters , "mass");
 
 	// Display one of the YAML parameters to debug if it is working correctly
 	//ROS_INFO_STREAM("DEBUGGING: mass leaded from loacl file = " << cf_mass );
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	vicon_frequency = getParameterFloat(nodeHandle_for_demoController, "vicon_frequency");
+	vicon_frequency = getParameterFloat(nodeHandle_for_paraMaters, "vicon_frequency");
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	control_frequency = getParameterFloat(nodeHandle_for_demoController, "control_frequency");
+	control_frequency = getParameterFloat(nodeHandle_for_paraMaters, "control_frequency");
 
 	// > The co-efficients of the quadratic conversation from 16-bit motor command to
 	//   thrust force in Newtons
-	getParameterFloatVector(nodeHandle_for_demoController, "motorPoly", motorPoly, 3);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "motorPoly", motorPoly, 3);
 
 	// > The boolean for whether to execute the convert into body frame function
-	shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_demoController, "shouldPerformConvertIntoBodyFrame");
+	shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_paraMaters, "shouldPerformConvertIntoBodyFrame");
 
 	// > The boolean indicating whether the (x,y,z,yaw) of this agent should be published
 	//   or not
-	shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_demoController, "shouldPublishCurrent_xyz_yaw");
+	shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_paraMaters, "shouldPublishCurrent_xyz_yaw");
 
 	// > The boolean indicating whether the (x,y,z,yaw) setpoint of this agent should adapted in
 	//   an attempt to follow the "my_current_xyz_yaw_topic" from another agent
-	shouldFollowAnotherAgent = getParameterBool(nodeHandle_for_demoController, "shouldFollowAnotherAgent");
+	shouldFollowAnotherAgent = getParameterBool(nodeHandle_for_paraMaters, "shouldFollowAnotherAgent");
 
 	// > The ordered vector for ID's that specifies how the agents should follow eachother
 	follow_in_a_line_agentIDs.clear();
-	int temp_number_of_agents_in_a_line = getParameterIntVectorWithUnknownLength(nodeHandle_for_demoController, "follow_in_a_line_agentIDs", follow_in_a_line_agentIDs);
+	int temp_number_of_agents_in_a_line = getParameterIntVectorWithUnknownLength(nodeHandle_for_paraMaters, "follow_in_a_line_agentIDs", follow_in_a_line_agentIDs);
 	// > Double check that the sizes agree
 	if ( temp_number_of_agents_in_a_line != follow_in_a_line_agentIDs.size() )
 	{
@@ -1539,70 +1550,70 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 	}
 
 	// Boolean indiciating whether the "Debug Message" of this agent should be published or not
-	shouldPublishDebugMessage = getParameterBool(nodeHandle_for_demoController, "shouldPublishDebugMessage");
+	shouldPublishDebugMessage = getParameterBool(nodeHandle_for_paraMaters, "shouldPublishDebugMessage");
 
 	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-	shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_demoController, "shouldDisplayDebugInfo");
+	shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paraMaters, "shouldDisplayDebugInfo");
 
 
 	// THE CONTROLLER GAINS:
 
 	// A flag for which controller to use:
-	controller_mode = getParameterInt( nodeHandle_for_demoController , "controller_mode" );
+	controller_mode = getParameterInt( nodeHandle_for_paraMaters , "controller_mode" );
 
 	// A flag for which estimator to use:
-	estimator_method = getParameterInt( nodeHandle_for_demoController , "estimator_method" );
+	estimator_method = getParameterInt( nodeHandle_for_paraMaters , "estimator_method" );
 
 	// The LQR Controller parameters for "LQR_MODE_MOTOR"
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixMotor1",                 gainMatrixMotor1,                 12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixMotor2",                 gainMatrixMotor2,                 12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixMotor3",                 gainMatrixMotor3,                 12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixMotor4",                 gainMatrixMotor4,                 12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixMotor1",                 gainMatrixMotor1,                 12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixMotor2",                 gainMatrixMotor2,                 12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixMotor3",                 gainMatrixMotor3,                 12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixMotor4",                 gainMatrixMotor4,                 12);
 
 	// The LQR Controller parameters for "LQR_MODE_MOTOR"
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixThrust_TwelveStateVector", gainMatrixThrust_TwelveStateVector, 12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixRollTorque",               gainMatrixRollTorque,               12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixPitchTorque",              gainMatrixPitchTorque,              12);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixYawTorque",                gainMatrixYawTorque,                12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixThrust_TwelveStateVector", gainMatrixThrust_TwelveStateVector, 12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixRollTorque",               gainMatrixRollTorque,               12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixPitchTorque",              gainMatrixPitchTorque,              12);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixYawTorque",                gainMatrixYawTorque,                12);
 
 	// The LQR Controller parameters for "LQR_MODE_RATE"
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixThrust_NineStateVector", gainMatrixThrust_NineStateVector, 9);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixRollRate",               gainMatrixRollRate,               9);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixPitchRate",              gainMatrixPitchRate,              9);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixYawRate",                gainMatrixYawRate,                9);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixThrust_NineStateVector", gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixRollRate",               gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixPitchRate",              gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixYawRate",                gainMatrixYawRate,                9);
 	
 	// The LQR Controller parameters for "LQR_MODE_ANGLE"
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixThrust_SixStateVector",  gainMatrixThrust_SixStateVector,  6);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixRollAngle",              gainMatrixRollAngle,              6);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixPitchAngle",             gainMatrixPitchAngle,             6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixThrust_SixStateVector",  gainMatrixThrust_SixStateVector,  6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixRollAngle",              gainMatrixRollAngle,              6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixPitchAngle",             gainMatrixPitchAngle,             6);
 	
 	// The LQR Controller parameters for "LQR_MODE_ANGLE_RATE_NESTED"
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixThrust_SixStateVector_50Hz",  gainMatrixThrust_SixStateVector_50Hz,  6);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixRollAngle_50Hz",              gainMatrixRollAngle_50Hz,              6);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixPitchAngle_50Hz",             gainMatrixPitchAngle_50Hz,             6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixThrust_SixStateVector_50Hz",  gainMatrixThrust_SixStateVector_50Hz,  6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixRollAngle_50Hz",              gainMatrixRollAngle_50Hz,              6);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixPitchAngle_50Hz",             gainMatrixPitchAngle_50Hz,             6);
 
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixRollRate_Nested",             gainMatrixRollRate_Nested,             3);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixPitchRate_Nested",            gainMatrixPitchRate_Nested,            3);
-	getParameterFloatVector(nodeHandle_for_demoController, "gainMatrixYawRate_Nested",              gainMatrixYawRate_Nested,              3);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixRollRate_Nested",             gainMatrixRollRate_Nested,             3);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixPitchRate_Nested",            gainMatrixPitchRate_Nested,            3);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "gainMatrixYawRate_Nested",              gainMatrixYawRate_Nested,              3);
 	
 	// The parameters for the "Angle Reponse Test" controller mode
-	angleResponseTest_pitchAngle_degrees = getParameterFloat(nodeHandle_for_demoController, "angleResponseTest_pitchAngle_degrees");
-	angleResponseTest_distance_meters    = getParameterFloat(nodeHandle_for_demoController, "angleResponseTest_distance_meters");
+	angleResponseTest_pitchAngle_degrees = getParameterFloat(nodeHandle_for_paraMaters, "angleResponseTest_pitchAngle_degrees");
+	angleResponseTest_distance_meters    = getParameterFloat(nodeHandle_for_paraMaters, "angleResponseTest_distance_meters");
 
 	// 16-BIT COMMAND LIMITS
-	cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_demoController, "command_sixteenbit_min");
-	cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_demoController, "command_sixteenbit_max");
+	cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_paraMaters, "command_sixteenbit_min");
+	cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_paraMaters, "command_sixteenbit_max");
 
 
 	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 	// > For the (x,y,z) position
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
 	// > For the (roll,pitch,yaw) angles
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_demoController, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paraMaters, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
@@ -1646,7 +1657,7 @@ void processFetchedParameters()
 	    	for ( int i=0 ; i<follow_in_a_line_agentIDs.size() ; i++ )
 	    	{
 	    		// Check if the current entry matches the ID of this agent
-	    		if (follow_in_a_line_agentIDs[i] == my_agentID)
+	    		if (follow_in_a_line_agentIDs[i] == m_agentID)
 	    		{
 	    			// Set the boolean flag that we have found out own agent ID
 	    			foundMyAgentID = true;
@@ -1681,109 +1692,38 @@ void processFetchedParameters()
 	    	// Check whether we found our own agent ID
 	    	if (!foundMyAgentID)
 	    	{
-                //ROS_INFO("DEBUGGING: not following because my ID was not found");
-	    		// Revert to the default of not following any agent
-    			shouldFollowAnotherAgent = false;
-    			agentID_to_follow = 0;
-	    	}
-    	}
-    	else
-    	{
-    		// As the "follow_in_a_line_agentIDs" vector has length zero, revert to the
-    		// default of not following any agent
-    		shouldFollowAnotherAgent = false;
-    		agentID_to_follow = 0;
-    		//ROS_INFO("DEBUGGING: not following because line vector has length zero");
-    	}
-    }
-    else
-    {
-    	// Set to its default value the integer specifying the ID of the agent that will
-    	// be followed by this agent
+				//ROS_INFO("DEBUGGING: not following because my ID was not found");
+				// Revert to the default of not following any agent
+				shouldFollowAnotherAgent = false;
+				agentID_to_follow = 0;
+			}
+		}
+		else
+		{
+			// As the "follow_in_a_line_agentIDs" vector has length zero, revert to the
+			// default of not following any agent
+			shouldFollowAnotherAgent = false;
+			agentID_to_follow = 0;
+			//ROS_INFO("DEBUGGING: not following because line vector has length zero");
+		}
+	}
+	else
+	{
+		// Set to its default value the integer specifying the ID of the agent that will
+		// be followed by this agent
 		agentID_to_follow = 0;
 		//ROS_INFO("DEBUGGING: not following because I was asked not to follow");
-    }
+	}
 
-    if (shouldFollowAnotherAgent)
-    {
-    	ROS_INFO_STREAM("[DEMO CONTROLLER] This agent (with ID " << my_agentID << ") will now follow agent ID " << agentID_to_follow );
-    }
+	if (shouldFollowAnotherAgent)
+	{
+		ROS_INFO_STREAM("[DEMO CONTROLLER] This agent (with ID " << m_agentID << ") will now follow agent ID " << agentID_to_follow );
+	}
 }
 
 
 
 
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
-//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
-//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
-//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
-//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
-//    ----------------------------------------------------------------------------------
-
-
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val.size();
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
-{
-    bool val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-    
-
-
-
 
 
 //    ----------------------------------------------------------------------------------
@@ -1796,143 +1736,181 @@ bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 
 // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
 int main(int argc, char* argv[]) {
-    
-    // Starting the ROS-node
-    ros::init(argc, argv, "DemoControllerService");
-
-    // 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 "DemoControllerService" node
-    std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[DEMO CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
-
-    // Get the agent ID as the "ROS_NAMESPACE" this computer.
-    // NOTES:
-    // > 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"
-    // > 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");
-    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
-    {
-    	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[DEMO CONTROLLER] Failed to get agentID from PPSClient");
+
+	// Starting the ROS-node
+	ros::init(argc, argv, "DemoControllerService");
+
+	// 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 "DemoControllerService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[DEMO CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
+
+
+
+	// 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
+	//   "PPSClient" node.
+	// > 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 ID of the agent and its coordinator
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[DEMO CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[DEMO CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
 	}
 
 
-	// *********************************************************************************
-	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
+	// 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.
 
-	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+	// 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";
 
-	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-    // namespace string for the parameter service that is running on the machine of this
-    // agent
-    namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
-    // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[DEMO CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[DEMO CONTROLLER] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+	// 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
 
 
-    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-    //       is very important because it specifies that the name is global
-    namespace_to_coordinator_parameter_service = "/ParameterService";
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
 
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-    
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber demoContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "DemoController", 1, isReadyDemoControllerYamlCallback);
+	ros::Subscriber demoContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("DemoController", 1, isReadyDemoControllerYamlCallback);
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
 
-    // PRINT OUT SOME INFORMATION
+	// GIVE YAML VARIABLES AN INITIAL VALUE
 
-    // Let the user know what namespaces are being used for linking to the parameter service
-    ROS_INFO_STREAM("[DEMO CONTROLLER] the namespace strings for accessing the Paramter Services are:");
-    ROS_INFO_STREAM("[DEMO CONTROLLER] namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
-    ROS_INFO_STREAM("[DEMO CONTROLLER] namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
+	// This can be done either here or as part of declaring the variable
+	// in the header file
+	//yaml_cf_mass_in_grams = 25.0;
+
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// The yaml files for the controllers are not added to "Parametr
+	// Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// message containing the filename of the *.yaml file, and
+	// then a message will be received on the above subscribers
+	// when the paramters are ready.
+
+	// Create a publisher for request the yaml load
+	// > created as a local variable
+	// > note importantly that the final argument is "true", this
+	//   enables "latching" on the connection. When a connection is 
+	//   latched, the last message published is saved and
+	//   automatically sent to any future subscribers that connect.
+	ros::Publisher requestLoadYamlFilenamePublisher = nodeHandle_to_own_agent_parameter_service.advertise<StringWithHeader>("requestLoadYamlFilename", 1, true);
+	// Create a local variable for the message
+	StringWithHeader yaml_filename_msg;
+	// Specify the data
+	yaml_filename_msg.data = "DemoController";
+	// Set for whom this applies to
+	yaml_filename_msg.shouldCheckForID = false;
+	// Sleep to make the publisher known to ROS (in seconds)
+	//ros::Duration(1.0).sleep();
+	// Send the message
+	requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 
 
-    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
 
 	// Call the class function that loads the parameters for this class.
-    fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-
-    // *********************************************************************************
-
-
-
-    // Instantiate the instance variable "debugPublisher" to be a "ros::Publisher" that
-    // advertises under the name "DebugTopic" and is a message with the structure
-    // defined in the file "DebugMsg.msg" (located in the "msg" folder).
-    debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
-
-    // Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "Setpoint" topic and calls the class function
-    // "setpointCallback" each time a messaged is received on this topic and the message
-    // is passed as an input argument to the "setpointCallback" class function.
-    ros::Subscriber setpointSubscriber = nodeHandle.subscribe("Setpoint", 1, setpointCallback);
-
-    // Instantiate the local variable "service" to be a "ros::ServiceServer" type
-    // variable that advertises the service called "DemoController". This service has
-    // the input-output behaviour defined in the "Controller.srv" file (located in the
-    // "srv" folder). This service, when called, is provided with the most recent
-    // measurement of the Crazyflie and is expected to respond with the control action
-    // that should be sent via the Crazyradio and requested from the Crazyflie, i.e.,
-    // this is where the "outer loop" controller function starts. When a request is made
-    // of this service the "calculateControlOutput" function is called.
-    ros::ServiceServer service = nodeHandle.advertiseService("DemoController", calculateControlOutput);
-
-    // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
-    // in the "DEFINES" section at the top of this file.
-    ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
-
-    // Instantiate the instance variable "my_current_xyz_yaw_publisher" to be a "ros::Publisher"
-    // that advertises under the name "<my_agentID>/my_current_xyz_yaw_topic" where <my_agentID>
-    // is filled in with the student ID number of this computer. The messages published will
-    // have the structure defined in the file "Setpoint.msg" (located in the "msg" folder).
-    my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
-
-    // Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "StudentCustomButton" topic and calls the class
-    // function "customCommandReceivedCallback" each time a messaged is received on this topic
-    // and the message received is passed as an input argument to the callback function.
-    ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
-
-    // Print out some information to the user.
-    ROS_INFO("[DEMO CONTROLLER] Service ready :-)");
-
-    // Enter an endless while loop to keep the node alive.
-    ros::spin();
-
-    // Return zero if the "ross::spin" is cancelled.
-    return 0;
+	//fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+
+
+
+
+	// PUBLISHERS AND SUBSCRIBERS
+
+	// Instantiate the class variable "m_debugPublisher" to be a
+	// "ros::Publisher". This variable advertises under the name
+	// "DebugTopic" and is a message with the structure defined
+	//  in the file "DebugMsg.msg" (located in the "msg" folder).
+	debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
+
+	// Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
+	// type variable that subscribes to the "Setpoint" topic and calls the class function
+	// "setpointCallback" each time a messaged is received on this topic and the message
+	// is passed as an input argument to the "setpointCallback" class function.
+	ros::Subscriber setpointSubscriber = nodeHandle.subscribe("Setpoint", 1, setpointCallback);
+
+	// Instantiate the local variable "service" to be a "ros::ServiceServer" type
+	// variable that advertises the service called "DemoController". This service has
+	// the input-output behaviour defined in the "Controller.srv" file (located in the
+	// "srv" folder). This service, when called, is provided with the most recent
+	// measurement of the Crazyflie and is expected to respond with the control action
+	// that should be sent via the Crazyradio and requested from the Crazyflie, i.e.,
+	// this is where the "outer loop" controller function starts. When a request is made
+	// of this service the "calculateControlOutput" function is called.
+	ros::ServiceServer service = nodeHandle.advertiseService("DemoController", calculateControlOutput);
+
+	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
+	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
+	//     "using namespace d_fall_pps;"
+	// in the "DEFINES" section at the top of this file.
+	ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
+	// Instantiate the instance variable "my_current_xyz_yaw_publisher" to be a "ros::Publisher"
+	// that advertises under the name "<m_agentID>/my_current_xyz_yaw_topic" where <m_agentID>
+	// is filled in with the student ID number of this computer. The messages published will
+	// have the structure defined in the file "Setpoint.msg" (located in the "msg" folder).
+	my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
+
+	// Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
+	// type variable that subscribes to the "StudentCustomButton" topic and calls the class
+	// function "customCommandReceivedCallback" each time a messaged is received on this topic
+	// and the message received is passed as an input argument to the callback function.
+	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
+
+	// Print out some information to the user.
+	ROS_INFO("[DEMO CONTROLLER] Service ready :-)");
+
+	// Enter an endless while loop to keep the node alive.
+	ros::spin();
+
+	// Return zero if the "ross::spin" is cancelled.
+	return 0;
 }
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 46422732..de1c8b39 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -483,6 +483,7 @@ void commandCallback(const IntWithHeader & msg) {
                 break;
 
         	case CMD_CRAZYFLY_TAKE_OFF:
+                ROS_INFO("[PPS CLIENT] TAKE_OFF Command received");
                 if(flying_state == STATE_MOTORS_OFF)
                 {
                     changeFlyingStateTo(STATE_TAKE_OFF);
@@ -490,12 +491,14 @@ void commandCallback(const IntWithHeader & msg) {
         		break;
 
         	case CMD_CRAZYFLY_LAND:
+                ROS_INFO("[PPS 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");
                 changeFlyingStateTo(STATE_MOTORS_OFF);
                 break;
 
@@ -508,11 +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");
     loadCrazyflieContext();
 }
 
 void emergencyStopCallback(const IntWithHeader & msg)
 {
+    ROS_INFO("[PPS CLIENT] Received message to EMERGENCY STOP");
     commandCallback(msg);
 }
 
@@ -523,6 +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 );
     crazyradio_status = msg.data;
     // RESET THE BATTERY STATE IF DISCONNECTED
     //if (crazyradio_status == CRAZY_RADIO_STATE_DISCONNECTED)
@@ -585,7 +591,9 @@ void safeSetPointCallback(const Setpoint& newSetpoint)
 
 
 void loadSafeController() {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string safeControllerName;
     if(!nodeHandle.getParam("safeController", safeControllerName)) {
@@ -600,7 +608,9 @@ void loadSafeController() {
 
 void loadDemoController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string demoControllerName;
     if(!nodeHandle.getParam("demoController", demoControllerName))
@@ -615,7 +625,9 @@ void loadDemoController()
 
 void loadStudentController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string studentControllerName;
     if(!nodeHandle.getParam("studentController", studentControllerName))
@@ -630,7 +642,9 @@ void loadStudentController()
 
 void loadMpcController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string mpcControllerName;
     if(!nodeHandle.getParam("mpcController", mpcControllerName))
@@ -645,7 +659,9 @@ void loadMpcController()
 
 void loadRemoteController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string remoteControllerName;
     if(!nodeHandle.getParam("remoteController", remoteControllerName))
@@ -660,7 +676,9 @@ void loadRemoteController()
 
 void loadTuningController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string tuningControllerName;
     if(!nodeHandle.getParam("tuningController", tuningControllerName))
@@ -675,7 +693,9 @@ void loadTuningController()
 
 void loadPickerController()
 {
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
     std::string pickerControllerName;
     if(!nodeHandle.getParam("pickerController", pickerControllerName))
@@ -768,15 +788,27 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
     int new_battery_state = msg.data;
 
     // Take action if changed to low battery state
-    if ((flying_state != STATE_MOTORS_OFF) && (new_battery_state == BATTERY_STATE_LOW))
+    if (new_battery_state == BATTERY_STATE_LOW)
     {
-        ROS_INFO("[PPS CLIENT] low level battery triggered, now landing.");
-        changeFlyingStateTo(STATE_LAND);
+        if (flying_state != STATE_MOTORS_OFF)
+        {
+            ROS_INFO("[PPS CLIENT] low level battery triggered, now landing.");
+            changeFlyingStateTo(STATE_LAND);
+        }
+        else
+        {
+            ROS_INFO("[PPS CLIENT] low level battery triggered, please turn off the Crazyflie.");
+        }
     }
-    else if ((flying_state == STATE_MOTORS_OFF) && (new_battery_state == BATTERY_STATE_LOW))
+    else if (new_battery_state == BATTERY_STATE_NORMAL)
     {
-        ROS_INFO("[PPS CLIENT] low level battery triggered, please turn off the Crazyflie.");
+        ROS_INFO("[PPS CLIENT] received message that battery state changed to normal");
     }
+    else
+    {
+        ROS_INFO("[PPS CLIENT] received message that battery state changed to something unknown");
+    }
+    
 }
 
 
@@ -1152,7 +1184,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 clientConfig_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "ClientConfig", 1, isReadyClientConfigYamlCallback);
     ros::Subscriber clientConfig_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("ClientConfig", 1, isReadyClientConfigYamlCallback);
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 0aa0aefe..825f8108 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -264,7 +264,7 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
 
     // Create publisher as a local variable, using the filename
     // as the name of the message
-    ros::Publisher yamlParametersReadyForFetchPublisher = nodeHandle.advertise<IntWithHeader>(yaml_filename_to_load, 1);
+    ros::Publisher yamlParametersReadyForFetchPublisher = nodeHandle.advertise<IntWithHeader>(yaml_filename_to_load, 1, true);
     //ros::spinOnce();
     // Create a local variable for the message
     IntWithHeader yaml_ready_msg;
diff --git a/pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
index 6607ee9a..d5bea535 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
@@ -146,7 +146,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
     // ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
     // ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
 
-    response.controlOutput.onboardControllerType = RATE_MODE;
+    response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 
     previousLocation = request.ownCrazyflie;
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 7f2098be..5c357b31 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -114,20 +114,30 @@
 //     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
 // 
 // 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 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.
-// > In RATE_MODE the ".motorCmd1" to ".motorCmd4" properties of "response.ControlCommand"
-//   are the baseline motor commands requested from the Crazyflie, with the adjustment
-//   for body rates being added on top of this in the firmware (i.e., as per the code
-//   of the "distribute_power" function provided in exercise sheet 2).
-// > In RATE_MODE the axis convention for the roll, pitch, and yaw body rates returned
-//   in "response.ControlCommand" should use right-hand coordinate axes with x-forward
-//   and z-upwards (i.e., the positive z-axis is aligned with the direction of positive
-//   thrust). To assist, teh following is an ASCII art of this convention:
+// > The allowed values for "onboardControllerType" are in the "Defines"
+//   section in the header file, they are:
+//   - CF_COMMAND_TYPE_MOTORS
+//   - CF_COMMAND_TYPE_RATE
+//   - CF_COMMAND_TYPE_ANGLE
+//
+// > For completeing the class exercises it is only required to use
+//   the CF_COMMAND_TYPE_RATE option.
+//
+// > For the CF_COMMAND_TYPE_RATE optoin:
+//   1) 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.
+//   2) the ".motorCmd1" to ".motorCmd4" properties of
+//      "response.ControlCommand" are the baseline motor commands
+//      requested from the Crazyflie, with the adjustment for body rates
+//      being added on top of this in the firmware (i.e., as per the
+//      code of the "distribute_power" found in the firmware).
+//   3) the axis convention for the roll, pitch, and yaw body rates
+//      returned in "response.ControlCommand" should use right-hand
+//      coordinate axes with x-forward and z-upwards (i.e., the positive
+//      z-axis is aligned with the direction of positive thrust). To
+//      assist, the following is an ASCII art of this convention.
 //
 // ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
 //
@@ -173,15 +183,15 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	float stateErrorInertial[9];
 
 	// Fill in the (x,y,z) position error
-	stateErrorInertial[0] = request.ownCrazyflie.x - setpoint[0];
-	stateErrorInertial[1] = request.ownCrazyflie.y - setpoint[1];
-	stateErrorInertial[2] = request.ownCrazyflie.z - setpoint[2];
+	stateErrorInertial[0] = request.ownCrazyflie.x - m_setpoint[0];
+	stateErrorInertial[1] = request.ownCrazyflie.y - m_setpoint[1];
+	stateErrorInertial[2] = request.ownCrazyflie.z - m_setpoint[2];
 
 	// Compute an estimate of the velocity
 	// > As simply the derivative between the current and previous position
-	stateErrorInertial[3] = (stateErrorInertial[0] - previous_stateErrorInertial[0]) * control_frequency;
-	stateErrorInertial[4] = (stateErrorInertial[1] - previous_stateErrorInertial[1]) * control_frequency;
-	stateErrorInertial[5] = (stateErrorInertial[2] - previous_stateErrorInertial[2]) * control_frequency;
+	stateErrorInertial[3] = (stateErrorInertial[0] - m_previous_stateErrorInertial[0]) * yaml_control_frequency;
+	stateErrorInertial[4] = (stateErrorInertial[1] - m_previous_stateErrorInertial[1]) * yaml_control_frequency;
+	stateErrorInertial[5] = (stateErrorInertial[2] - m_previous_stateErrorInertial[2]) * yaml_control_frequency;
 
 	// Fill in the roll and pitch angle measurements directly
 	stateErrorInertial[6] = request.ownCrazyflie.roll;
@@ -191,7 +201,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > This error should be "unwrapped" to be in the range
 	//   ( -pi , pi )
 	// > First, get the yaw error into a local variable
-	float yawError = request.ownCrazyflie.yaw - setpoint[3];
+	float yawError = request.ownCrazyflie.yaw - m_setpoint[3];
 	// > Second, "unwrap" the yaw error to the interval ( -pi , pi )
 	while(yawError > PI) {yawError -= 2 * PI;}
 	while(yawError < -PI) {yawError += 2 * PI;}
@@ -213,7 +223,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > as we have already used previous error we can now update it update it
 	for(int i = 0; i < 9; ++i)
 	{
-		previous_stateErrorInertial[i] = stateErrorInertial[i];
+		m_previous_stateErrorInertial[i] = stateErrorInertial[i];
 	}
 
 
@@ -235,7 +245,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Perform the "-Kx" LQR computation for the yaw rate to respoond with
 	for(int i = 0; i < 9; ++i)
 	{
-		yawRate_forResponse -= gainMatrixYawRate[i] * stateErrorBody[i];
+		yawRate_forResponse -= m_gainMatrixYawRate[i] * stateErrorBody[i];
 	}
 
 	// Put the computed yaw rate into the "response" variable
@@ -260,7 +270,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Perform the "-Kx" LQR computation for the thrust adjustment to respoond with
 	for(int i = 0; i < 9; ++i)
 	{
-		thrustAdjustment -= gainMatrixThrust[i] * stateErrorBody[i];
+		thrustAdjustment -= m_gainMatrixThrust[i] * stateErrorBody[i];
 	}
 
 	// Put the computed thrust adjustment into the "response" variable,
@@ -268,10 +278,10 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > NOTE: remember that the thrust is commanded per motor, so you sohuld
 	//         consider whether the "thrustAdjustment" computed by your
 	//         controller needed to be divided by 4 or not.
-	// > NOTE: the "cf_weight_in_newtons" value is the total thrust required
+	// > NOTE: the "m_cf_weight_in_newtons" value is the total thrust required
 	//         as feed-forward. Assuming the the Crazyflie is symmetric, this
 	//         value is divided by four.
-	float feed_forward_thrust_per_motor = cf_weight_in_newtons / 4.0;
+	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
 	// > NOTE: the function "computeMotorPolyBackward" converts the input argument
 	//         from Newtons to the 16-bit command expected by the Crazyflie.
 	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
@@ -297,7 +307,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Perform the "-Kx" LQR computation for the pitch rate to respoond with
 	for(int i = 0; i < 9; ++i)
 	{
-		pitchRate_forResponse -= gainMatrixPitchRate[i] * stateErrorBody[i];
+		pitchRate_forResponse -= m_gainMatrixPitchRate[i] * stateErrorBody[i];
 	}
 
 	// Put the computed pitch rate into the "response" variable
@@ -322,7 +332,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Perform the "-Kx" LQR computation for the roll rate to respoond with
 	for(int i = 0; i < 9; ++i)
 	{
-		rollRate_forResponse -= gainMatrixRollRate[i] * stateErrorBody[i];
+		rollRate_forResponse -= m_gainMatrixRollRate[i] * stateErrorBody[i];
 	}
 
 	// Put the computed roll rate into the "response" variable
@@ -334,9 +344,9 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 	/*choosing the Crazyflie onBoard controller type.
 	it can either be Motor, Rate or Angle based */
-	// response.controlOutput.onboardControllerType = MOTOR_MODE;
-	response.controlOutput.onboardControllerType = RATE_MODE;
-	// response.controlOutput.onboardControllerType = ANGLE_MODE;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 
 
 
@@ -349,11 +359,11 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
 	//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
 
-    // DEBUGGING CODE:
-    // As part of the D-FaLL-System we have defined a message type names"DebugMsg".
-    // By fill this message with data and publishing it you can display the data in
-    // real time using rpt plots. Instructions for using rqt plots can be found on
-    // the wiki of the D-FaLL-System repository
+	// DEBUGGING CODE:
+	// As part of the D-FaLL-System we have defined a message type names"DebugMsg".
+	// By fill this message with data and publishing it you can display the data in
+	// real time using rpt plots. Instructions for using rqt plots can be found on
+	// the wiki of the D-FaLL-System repository
 
 	// Instantiate a local variable of type "DebugMsg", see the file "DebugMsg.msg"
 	// (located in the "msg" folder) to see the full structure of this message.
@@ -378,41 +388,41 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// debugMsg.value_10 = your_variable_name;
 
 	// Publish the "debugMsg"
-	debugPublisher.publish(debugMsg);
+	m_debugPublisher.publish(debugMsg);
 
 	// An alternate debugging technique is to print out data directly to the
-    // command line from which this node was launched.
-
-    // An example of "printing out" the data from the "request" argument to the
-    // command line. This might be useful for debugging.
-    // ROS_INFO_STREAM("x-coordinates: " << request.ownCrazyflie.x);
-    // ROS_INFO_STREAM("y-coordinates: " << request.ownCrazyflie.y);
-    // ROS_INFO_STREAM("z-coordinates: " << request.ownCrazyflie.z);
-    // ROS_INFO_STREAM("roll: " << request.ownCrazyflie.roll);
-    // ROS_INFO_STREAM("pitch: " << request.ownCrazyflie.pitch);
-    // ROS_INFO_STREAM("yaw: " << request.ownCrazyflie.yaw);
-    // ROS_INFO_STREAM("Delta t: " << request.ownCrazyflie.acquiringTime);
-
-    // An example of "printing out" the control actions computed.
-    // ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
-    // ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
-    // ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
-    // ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
-
-    // An example of "printing out" the "thrust-to-command" conversion parameters.
-    // ROS_INFO_STREAM("motorPoly 0:" << motorPoly[0]);
-    // ROS_INFO_STREAM("motorPoly 0:" << motorPoly[1]);
-    // ROS_INFO_STREAM("motorPoly 0:" << motorPoly[2]);
-
-    // An example of "printing out" the per motor 16-bit command computed.
-    // ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
-    // ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
-    // ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
-    // ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
-
-    // Return "true" to indicate that the control computation was performed successfully
-    return true;
-}
+	// command line from which this node was launched.
+
+	// An example of "printing out" the data from the "request" argument to the
+	// command line. This might be useful for debugging.
+	// ROS_INFO_STREAM("x-coordinates: " << request.ownCrazyflie.x);
+	// ROS_INFO_STREAM("y-coordinates: " << request.ownCrazyflie.y);
+	// ROS_INFO_STREAM("z-coordinates: " << request.ownCrazyflie.z);
+	// ROS_INFO_STREAM("roll: " << request.ownCrazyflie.roll);
+	// ROS_INFO_STREAM("pitch: " << request.ownCrazyflie.pitch);
+	// ROS_INFO_STREAM("yaw: " << request.ownCrazyflie.yaw);
+	// ROS_INFO_STREAM("Delta t: " << request.ownCrazyflie.acquiringTime);
+
+	// An example of "printing out" the control actions computed.
+	// ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
+	// ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
+	// ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
+	// ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
+
+	// An example of "printing out" the "thrust-to-command" conversion parameters.
+	// ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
+	// ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
+	// ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
+
+	// An example of "printing out" the per motor 16-bit command computed.
+	// ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
+	// ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
+	// ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
+	// ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
+
+	// Return "true" to indicate that the control computation was performed successfully
+	return true;
+	}
 
 
 
@@ -457,20 +467,20 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 // This function WILL NEED TO BE edited for successful completion of the PPS exercise
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
 {
-	    // Fill in the (x,y,z) position estimates to be returned
-	    stateBody[0] = stateInertial[0];
-	    stateBody[1] = stateInertial[1];
-	    stateBody[2] = stateInertial[2];
-
-	    // Fill in the (x,y,z) velocity estimates to be returned
-	    stateBody[3] = stateInertial[3];
-	    stateBody[4] = stateInertial[4];
-	    stateBody[5] = stateInertial[5];
-
-	    // Fill in the (roll,pitch,yaw) estimates to be returned
-	    stateBody[6] = stateInertial[6];
-	    stateBody[7] = stateInertial[7];
-	    stateBody[8] = stateInertial[8];
+	// Fill in the (x,y,z) position estimates to be returned
+	stateBody[0] = stateInertial[0];
+	stateBody[1] = stateInertial[1];
+	stateBody[2] = stateInertial[2];
+
+	// Fill in the (x,y,z) velocity estimates to be returned
+	stateBody[3] = stateInertial[3];
+	stateBody[4] = stateInertial[4];
+	stateBody[5] = stateInertial[5];
+
+	// Fill in the (roll,pitch,yaw) estimates to be returned
+	stateBody[6] = stateInertial[6];
+	stateBody[7] = stateInertial[7];
+	stateBody[8] = stateInertial[8];
 }
 
 
@@ -491,10 +501,26 @@ void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float y
 //     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 NEED TO BE edited for successful completion of
+// the exercise
 float computeMotorPolyBackward(float thrust)
 {
-    return (-motorPoly[1] + sqrt(motorPoly[1] * motorPoly[1] - 4 * motorPoly[2] * (motorPoly[0] - thrust))) / (2 * motorPoly[2]);
+	// Compute the 16-but command that would produce the requested
+	// "thrust" based on the quadratic mapping that is described
+	// by the coefficients in the "yaml_motorPoly" variable.
+	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
+
+
+
+	// > Could this formula compute a result "cmd_16bit" that is
+	//   greater than ((2^16)-1)?
+	// > What might happen when such a number is case as a 16-bit
+	//   integer? In other words, what is uint16(cmd_sixteen_bit)?
+
+
+
+	// Return the result
+	return cmd_16bit;
 }
 
 
@@ -518,10 +544,10 @@ float computeMotorPolyBackward(float thrust)
 // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
 void setpointCallback(const Setpoint& newSetpoint)
 {
-    setpoint[0] = newSetpoint.x;
-    setpoint[1] = newSetpoint.y;
-    setpoint[2] = newSetpoint.z;
-    setpoint[3] = newSetpoint.yaw;
+	m_setpoint[0] = newSetpoint.x;
+	m_setpoint[1] = newSetpoint.y;
+	m_setpoint[2] = newSetpoint.z;
+	m_setpoint[3] = newSetpoint.yaw;
 }
 
 
@@ -611,170 +637,100 @@ void customCommandReceivedCallback(const CustomButton& commandReceived)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+// This function DOES NOT NEED TO BE edited for successful completion
+// ofthe exercise
+void isReadyStudentControllerYamlCallback(const IntWithHeader & msg)
 {
-	// Extract from the "msg" for which controller the and from where to fetch the YAML
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
+	// Continue if the message is relevant
+	if (isRevelant)
 	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR:
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
 		{
-			// Let the user know that this message was received
-			ROS_INFO("[STUDENT CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
-
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The StudentControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[STUDENT CONTROLLER] Now fetching the StudentController 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("[STUDENT CONTROLLER] Now fetching the StudentController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
+
+			default:
+			{
+				ROS_ERROR("[STUDENT CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
 		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchStudentControllerYamlParameters(nodeHandle_to_use);
 	}
 }
 
 
-// This function CAN BE edited for successful completion of the PPS 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)
+// This function CAN BE edited for successful completion of the
+// exercise, and the use of parameters fetched from the YAML file
+// is highly recommended to make tuning of your controller easier
+// and quicker.
+void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
-	// Here we load the parameters that are specified in the StudentController.yaml file
+	// Here we load the parameters that are specified in the file:
+	// StudentController.yaml
 
 	// Add the "StudentController" namespace to the "nodeHandle"
-	ros::NodeHandle nodeHandle_for_studentController(nodeHandle, "StudentController");
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "StudentController");
+
+
+
+	// GET THE PARAMETERS:
 
 	// > The mass of the crazyflie
-	cf_mass_in_grams = getParameterFloat(nodeHandle_for_studentController , "mass");
+	yaml_cf_mass_in_grams = getParameterFloat(nodeHandle_for_paramaters , "mass");
 
 	// Display one of the YAML parameters to debug if it is working correctly
-	//ROS_INFO_STREAM("DEBUGGING: mass leaded from loacl file = " << cf_mass_in_grams );
+	//ROS_INFO_STREAM("DEBUGGING: mass leaded from loacl file = " << yaml_cf_mass_in_grams );
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	control_frequency = getParameterFloat(nodeHandle_for_studentController, "control_frequency");
+	yaml_control_frequency = getParameterFloat(nodeHandle_for_paramaters, "control_frequency");
 
 	// > The co-efficients of the quadratic conversation from 16-bit motor command to
 	//   thrust force in Newtons
-	getParameterFloatVector(nodeHandle_for_studentController, "motorPoly", motorPoly, 3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", yaml_motorPoly, 3);
 
 
-	// DEBUGGING: Print out one of the parameters that was loaded
-	ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: the fetched StudentController/mass = " << cf_mass_in_grams);
 
-	// Call the function that computes details an values that are needed from these
-	// parameters loaded above
-	processFetchedParameters();
-
-}
-
-
-// This function CAN BE edited for successful completion of the PPS 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()
-{
-    // Compute the feed-forward force that we need to counteract gravity (i.e., mg)
-    // > in units of [Newtons]
-    cf_weight_in_newtons = cf_mass_in_grams * 9.81/1000.0;
-    
-    // DEBUGGING: Print out one of the computed quantities
-	ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << cf_weight_in_newtons);
-}
+	// > DEBUGGING: Print out one of the parameters that was loaded to
+	//   debug if the fetching of parameters worked correctly
+	ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: the fetched StudentController/mass = " << yaml_cf_mass_in_grams);
 
 
 
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
-//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
-//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
-//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
-//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
-//    ----------------------------------------------------------------------------------
+	// PROCESS THE PARAMTERS
 
+	// > Compute the feed-forward force that we need to counteract
+	//   gravity (i.e., mg) in units of [Newtons]
+	m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81/1000.0;
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val.size();
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
-{
-    bool val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
+	// DEBUGGING: Print out one of the computed quantities
+	ROS_INFO_STREAM("[STUDENT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << m_cf_weight_in_newtons);
 }
-    
 
 
 
@@ -790,101 +746,140 @@ bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
 
 // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
 int main(int argc, char* argv[]) {
-    
-    // Starting the ROS-node
-    ros::init(argc, argv, "StudentControllerService");
-
-    // 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 "StudentControllerService" node
-    std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[STUDENT CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
-
-    // Get the agent ID as the "ROS_NAMESPACE" this computer.
-    // NOTES:
-    // > If you look at the "Agent.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"
-    // > 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");
-    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
-    {
-    	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[STUDENT CONTROLLER] Failed to get agentID from PPSClient");
+
+	// Starting the ROS-node
+	ros::init(argc, argv, "StudentControllerService");
+
+	// 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 "StudentControllerService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[STUDENT CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
+
+
+
+	// 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
+	//   "PPSClient" node.
+	// > 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 ID of the agent and its coordinator
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[STUDENT CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[STUDENT CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
 	}
 
 
-	// *********************************************************************************
-	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
 
+	// 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";
+
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[STUDENT CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[STUDENT CONTROLLER] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
 
-	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
 
-	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-    // namespace string for the parameter service that is running on the machine of this
-    // agent
-    namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
 
-    // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
 
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber safeContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "StudentController", 1, isReadyStudentControllerYamlCallback);
+	ros::Subscriber safeContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("StudentController", 1, isReadyStudentControllerYamlCallback);
 
-    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-    //       is very important because it specifies that the name is global
-    namespace_to_coordinator_parameter_service = "/ParameterService";
 
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-    
+	// GIVE YAML VARIABLES AN INITIAL VALUE
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+	// This can be done either here or as part of declaring the variable
+	// in the header file
+	yaml_cf_mass_in_grams = 25.0;
+	yaml_motorPoly[0] = 5.484560e-4;
+	yaml_motorPoly[1] = 1.032633e-6;
+	yaml_motorPoly[2] = 2.130295e-11;
+	yaml_control_frequency = 200.0;
 
 
-    // PRINT OUT SOME INFORMATION
 
-    // Let the user know what namespaces are being used for linking to the parameter service
-    ROS_INFO_STREAM("[STUDENT CONTROLLER] The namespace string for accessing the Paramter Services are:");
-    ROS_INFO_STREAM("[STUDENT CONTROLLER] namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
-    ROS_INFO_STREAM("[STUDENT CONTROLLER] namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
+	// The yaml files for the controllers are not added to "Parameter
+	// Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// message containing the filename of the *.yaml file, and
+	// then a message will be received on the above subscribers
+	// when the paramters are ready.
 
-    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
+	// Create a publisher for request the yaml load
+	// > created as a local variable
+	// > note importantly that the final argument is "true", this
+	//   enables "latching" on the connection. When a connection is 
+	//   latched, the last message published is saved and
+	//   automatically sent to any future subscribers that connect. 
+    ros::Publisher requestLoadYamlFilenamePublisher = nodeHandle_to_own_agent_parameter_service.advertise<StringWithHeader>("requestLoadYamlFilename", 1, true);
+	// Create a local variable for the message
+    StringWithHeader yaml_filename_msg;
+    // Specify the data
+    yaml_filename_msg.data = "StudentController";
+    // Set for whom this applies to
+    yaml_filename_msg.shouldCheckForID = false;
+    // Sleep to make the publisher known to ROS (in seconds)
+    //ros::Duration(1.0).sleep();
+    // Send the message
+    requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 
-	// Call the class function that loads the parameters for this class.
-    fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
-    // *********************************************************************************
 
 
+    // PUBLISHERS AND SUBSCRIBERS
 
-    // Instantiate the instance variable "debugPublisher" to be a "ros::Publisher" that
-    // advertises under the name "DebugTopic" and is a message with the structure
-    // defined in the file "DebugMsg.msg" (located in the "msg" folder).
-    debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
+    // Instantiate the class variable "m_debugPublisher" to be a
+    // "ros::Publisher". This variable advertises under the name
+    // "DebugTopic" and is a message with the structure defined
+    //  in the file "DebugMsg.msg" (located in the "msg" folder).
+    m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
     // Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
     // type variable that subscribes to the "Setpoint" topic and calls the class function
-- 
GitLab


From 1ddd359e8f5bdd6ca028b896a87da598d8db014b Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 11 Dec 2018 19:20:59 +0100
Subject: [PATCH 14/87] Small changes to make the GUI look nicer. Added an
 emergency stop button. It needs to be connected, given a proper image, and
 made hidden for when launched as an agent

---
 .../forms/connectstartstopbar.ui              | 40 ++++++------
 .../flyingAgentGUI/forms/controllertabs.ui    |  2 +-
 .../forms/defaultcontrollertab.ui             | 24 +++++++
 .../forms/enablecontrollerloadyamlbar.ui      | 20 +++---
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui | 65 +++++++++++--------
 .../GUI_Qt/flyingAgentGUI/forms/topbanner.ui  | 33 ++++++++--
 .../include/defaultcontrollertab.h            |  9 +++
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h | 10 ++-
 .../src/defaultcontrollertab.cpp              | 36 ++++++++++
 .../src/enablecontrollerloadyamlbar.cpp       | 13 +---
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  2 +
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   | 58 +++++++++++++----
 12 files changed, 224 insertions(+), 88 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
index c2e783df..8c1b2fa4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
@@ -47,13 +47,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>750</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -71,8 +71,8 @@
        </property>
        <property name="minimumSize">
         <size>
-         <width>95</width>
-         <height>70</height>
+         <width>72</width>
+         <height>55</height>
         </size>
        </property>
        <property name="maximumSize">
@@ -97,13 +97,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>750</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -117,21 +117,21 @@
         <bool>true</bool>
        </property>
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>180</width>
-         <height>70</height>
+         <width>0</width>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -162,8 +162,8 @@
        </property>
        <property name="minimumSize">
         <size>
-         <width>50</width>
-         <height>70</height>
+         <width>38</width>
+         <height>55</height>
         </size>
        </property>
        <property name="maximumSize">
@@ -188,13 +188,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>750</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -213,13 +213,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>750</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
@@ -237,8 +237,8 @@
        </property>
        <property name="minimumSize">
         <size>
-         <width>90</width>
-         <height>70</height>
+         <width>72</width>
+         <height>55</height>
         </size>
        </property>
        <property name="maximumSize">
@@ -263,13 +263,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>750</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index cfd93a07..c1f3085f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -28,7 +28,7 @@
    <item row="0" column="0">
     <widget class="QTabWidget" name="controller_tabs_widget">
      <property name="currentIndex">
-      <number>2</number>
+      <number>3</number>
      </property>
      <widget class="QWidget" name="default_tab">
       <attribute name="title">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
index 5c0dc364..fc0b70b3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
@@ -54,6 +54,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="4" column="0">
@@ -131,6 +134,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="0" column="1">
@@ -399,6 +405,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="7">
@@ -524,6 +533,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="2" column="2">
@@ -548,6 +560,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="1" column="2">
@@ -588,6 +603,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="4" column="1">
@@ -612,6 +630,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="1">
@@ -636,6 +657,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="0">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index 704e95ab..0537109e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -41,13 +41,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -72,13 +72,13 @@
        <property name="minimumSize">
         <size>
          <width>0</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>16777215</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -106,13 +106,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -246,13 +246,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
@@ -277,13 +277,13 @@
        <property name="minimumSize">
         <size>
          <width>60</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
          <width>180</width>
-         <height>70</height>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index 28300e78..832f4f81 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -54,22 +54,29 @@
         </property>
        </widget>
       </item>
+      <item>
+       <widget class="Line" name="coordinator_to_main_panel_vertical_line">
+        <property name="orientation">
+         <enum>Qt::Vertical</enum>
+        </property>
+       </widget>
+      </item>
       <item>
        <layout class="QVBoxLayout" name="verticalLayout_2">
         <property name="spacing">
          <number>6</number>
         </property>
         <property name="leftMargin">
-         <number>6</number>
+         <number>12</number>
         </property>
         <property name="topMargin">
-         <number>6</number>
+         <number>0</number>
         </property>
         <property name="rightMargin">
          <number>6</number>
         </property>
         <property name="bottomMargin">
-         <number>6</number>
+         <number>0</number>
         </property>
         <item>
          <widget class="TopBanner" name="customWidget_topBanner" native="true">
@@ -93,6 +100,13 @@
           </property>
          </widget>
         </item>
+        <item>
+         <widget class="Line" name="line_1">
+          <property name="orientation">
+           <enum>Qt::Horizontal</enum>
+          </property>
+         </widget>
+        </item>
         <item>
          <widget class="ConnectStartStopBar" name="customWidget_connectStartStopBar" native="true">
           <property name="sizePolicy">
@@ -115,6 +129,13 @@
           </property>
          </widget>
         </item>
+        <item>
+         <widget class="Line" name="line_2">
+          <property name="orientation">
+           <enum>Qt::Horizontal</enum>
+          </property>
+         </widget>
+        </item>
         <item>
          <widget class="EnableControllerLoadYamlBar" name="customWidget_enableControllerLoadYamlBar" native="true">
           <property name="enabled">
@@ -141,33 +162,21 @@
          </widget>
         </item>
         <item>
-         <layout class="QHBoxLayout" name="horizontalLayout">
-          <property name="spacing">
-           <number>6</number>
-          </property>
-          <property name="leftMargin">
-           <number>6</number>
-          </property>
-          <property name="topMargin">
-           <number>6</number>
+         <widget class="Line" name="line_3">
+          <property name="orientation">
+           <enum>Qt::Horizontal</enum>
           </property>
-          <property name="rightMargin">
-           <number>6</number>
-          </property>
-          <property name="bottomMargin">
-           <number>6</number>
+         </widget>
+        </item>
+        <item>
+         <widget class="ControllerTabs" name="customWidget_controller_tabs" native="true">
+          <property name="sizePolicy">
+           <sizepolicy hsizetype="Expanding" vsizetype="Preferred">
+            <horstretch>0</horstretch>
+            <verstretch>0</verstretch>
+           </sizepolicy>
           </property>
-          <item>
-           <widget class="ControllerTabs" name="customWidget_controller_tabs" native="true">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Expanding" vsizetype="Preferred">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-           </widget>
-          </item>
-         </layout>
+         </widget>
         </item>
        </layout>
       </item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
index 0198a2db..75b32f76 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
@@ -6,13 +6,13 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1049</width>
+    <width>1418</width>
     <height>300</height>
    </rect>
   </property>
   <property name="font">
    <font>
-    <pointsize>20</pointsize>
+    <pointsize>18</pointsize>
     <weight>75</weight>
     <bold>true</bold>
    </font>
@@ -27,13 +27,13 @@
       <number>6</number>
      </property>
      <property name="topMargin">
-      <number>6</number>
+      <number>0</number>
      </property>
      <property name="rightMargin">
       <number>6</number>
      </property>
      <property name="bottomMargin">
-      <number>6</number>
+      <number>0</number>
      </property>
      <property name="spacing">
       <number>6</number>
@@ -54,6 +54,31 @@
        </property>
       </widget>
      </item>
+     <item row="0" column="1">
+      <widget class="QPushButton" name="emergency_stop_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="minimumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>ES</string>
+       </property>
+      </widget>
+     </item>
     </layout>
    </item>
   </layout>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 0eecff4b..33ad470c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -2,6 +2,7 @@
 #define DEFAULTCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QTextStream>
 
 namespace Ui {
 class DefaultControllerTab;
@@ -15,6 +16,14 @@ public:
     explicit DefaultControllerTab(QWidget *parent = 0);
     ~DefaultControllerTab();
 
+private slots:
+    void on_lineEdit_setpoint_new_x_returnPressed();
+    void on_lineEdit_setpoint_new_y_returnPressed();
+    void on_lineEdit_setpoint_new_z_returnPressed();
+    void on_lineEdit_setpoint_new_yaw_returnPressed();
+
+    void on_set_setpoint_button_clicked();
+
 private:
     Ui::DefaultControllerTab *ui;
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index 7a7b3e3a..57faad75 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -100,7 +100,7 @@ private:
 
 
 
-    #ifdef CATKIN_MAKE
+#ifdef CATKIN_MAKE
     // --------------------------------------------------- //
     // PRIVATE VARIABLES FOR ROS
 
@@ -123,9 +123,15 @@ private:
     // > For the notification that the database was changes,
     //   received on the "DatabaseChangedSubscriber"
     void databaseChangedCallback(const std_msgs::Int32& msg);
+#endif
 
 
-#endif
+private slots:
+
+    // PRIVATE METHODS FOR BUTTON CALLBACKS
+    // > For the emergency stop button
+    void on_emergency_stop_button_clicked();
+
 };
 
 #endif // TOPBANNER_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index f35ee39e..27430450 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -12,3 +12,39 @@ DefaultControllerTab::~DefaultControllerTab()
 {
     delete ui;
 }
+
+void DefaultControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[DEFAULT CONTROLLER TAB] return pressed for x setpoint";
+#endif
+}
+
+void DefaultControllerTab::on_lineEdit_setpoint_new_y_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void DefaultControllerTab::on_lineEdit_setpoint_new_z_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void DefaultControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void DefaultControllerTab::on_set_setpoint_button_clicked()
+{
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[DEFAULT CONTROLLER TAB] set setpoint button clicked";
+#endif
+}
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index e0c49054..28908655 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -172,17 +172,6 @@ void EnableControllerLoadYamlBar::setAgentIDsToCoordinate(QVector<int> agentIDs
     }
     // Unlock the mutex
     m_agentIDs_toCoordinate_mutex.unlock();
-
-#ifdef CATKIN_MAKE
-#else
-    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
-    QTextStream(stdout) << "[CONNECT START STOP GUI BAR] is coordinating agentIDs:";
-    for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
-    {
-        QTextStream(stdout) << " " << agentIDs[irow];
-    }
-    QTextStream(stdout) << " " << endl;
-#endif
 }
 
 
@@ -385,4 +374,4 @@ bool EnableControllerLoadYamlBar::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 65645bb8..2350a5c6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -121,12 +121,14 @@ void MainWindow::on_actionShowHide_Coordinator_triggered()
     if ( ui->customWidget_coordinator->isHidden() )
     {
         ui->customWidget_coordinator->show();
+        ui->coordinator_to_main_panel_vertical_line->show();
         QString qstr = "Hide Coordinator";
         ui->actionShowHide_Coordinator->setText(qstr);
     }
     else
     {
         ui->customWidget_coordinator->hide();
+        ui->coordinator_to_main_panel_vertical_line->hide();
         QString qstr = "Show Coordinator";
         ui->actionShowHide_Coordinator->setText(qstr);
     }
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 771eed6b..5928885b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -36,7 +36,12 @@
 #include "topbanner.h"
 #include "ui_topbanner.h"
 
+#ifdef CATKIN_MAKE
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
 
+#endif
 
 
 
@@ -45,12 +50,19 @@ TopBanner::TopBanner(QWidget *parent) :
     ui(new Ui::TopBanner)
 {
     ui->setupUi(this);
+    (":/images/rf_connected.png");
+    QPixmap pixmap(":/images/rf_connected.png");
+    QIcon ButtonIcon(pixmap);
+    ui->emergency_stop_button->setText("");
+    ui->emergency_stop_button->setIcon(ButtonIcon);
+    ui->emergency_stop_button->setIconSize(QSize(50,50));
+    //ui->emergency_stop_button->setIconSize(pixmap.rect().size());
 
 
 #ifdef CATKIN_MAKE
     // Get the namespace of this node
     std::string base_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << base_namespace);
+    ROS_INFO_STREAM("[TOP BANNER GUI] ros::this_node::getNamespace() =  " << base_namespace);
 
 
     // Get the type and ID of this parameter service
@@ -59,7 +71,7 @@ TopBanner::TopBanner(QWidget *parent) :
     // Stall if the TYPE and ID are not valid
     if ( !isValid_type_and_ID )
     {
-        ROS_ERROR("[CONNECT START STOP GUI BAR] Node NOT FUNCTIONING :-)");
+        ROS_ERROR("[TOP BANNER GUI] Node NOT FUNCTIONING :-)");
         ros::spin();
     }
 #else
@@ -133,7 +145,7 @@ TopBanner::~TopBanner()
 // > For the notification that the database was changes, received on the "DatabaseChangedSubscriber"
 void TopBanner::databaseChangedCallback(const std_msgs::Int32& msg)
 {
-    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Database Changed Callback called for agentID = " << m_agentID);
+    //ROS_INFO_STEAM("[TOP BANNER GUI] Database Changed Callback called for agentID = " << m_agentID);
     loadCrazyflieContext();
 }
 #endif
@@ -194,6 +206,30 @@ void TopBanner::loadCrazyflieContext()
 
 
 
+//    ----------------------------------------------------------------------------------
+//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
+//    B   B  U   U    T      T    O   O  NN  N  S
+//    BBBB   U   U    T      T    O   O  N N N   SSS
+//    B   B  U   U    T      T    O   O  N  NN      S
+//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+
+void TopBanner::on_emergency_stop_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_RECONNECT;
+    this->crazyRadioCommandPublisher.publish(msg);
+    ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
+#endif
+}
+
+
+
+
 
 //    ----------------------------------------------------------------------------------
 //    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
@@ -220,7 +256,7 @@ bool TopBanner::getTypeAndIDParameters()
     if(!nodeHandle.getParam("type", type_string))
     {
         // Throw an error if the agent ID parameter could not be obtained
-        ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get type");
+        ROS_ERROR("[TOP BANNER GUI] Failed to get type");
     }
 
     // Set the "m_type" class variable based on this string loaded
@@ -237,7 +273,7 @@ bool TopBanner::getTypeAndIDParameters()
         // Set "m_type" to the value indicating that it is invlid
         m_type = TYPE_INVALID;
         return_was_successful = false;
-        ROS_ERROR("[CONNECT START STOP GUI BAR] The 'type' parameter retrieved was not recognised.");
+        ROS_ERROR("[TOP BANNER GUI] The 'type' parameter retrieved was not recognised.");
     }
 
 
@@ -251,12 +287,12 @@ bool TopBanner::getTypeAndIDParameters()
             {
                 // Throw an error if the agent ID parameter could not be obtained
                 return_was_successful = false;
-                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get agentID");
+                ROS_ERROR("[TOP BANNER GUI] Failed to get agentID");
             }
             else
             {
                 // Inform the user about the type and ID
-                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type AGENT with ID = " << m_ID);
+                ROS_INFO_STREAM("[TOP BANNER GUI] Is of type AGENT with ID = " << m_ID);
             }
             break;
         }
@@ -270,12 +306,12 @@ bool TopBanner::getTypeAndIDParameters()
             {
                 // Throw an error if the coord ID parameter could not be obtained
                 return_was_successful = false;
-                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get coordID");
+                ROS_ERROR("[TOP BANNER GUI] Failed to get coordID");
             }
             else
             {
                 // Inform the user about the type and ID
-                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
+                ROS_INFO_STREAM("[TOP BANNER GUI] Is of type COORDINATOR with ID = " << m_ID);
             }
             break;
         }
@@ -284,7 +320,7 @@ bool TopBanner::getTypeAndIDParameters()
         {
             // Throw an error if the type is not recognised
             return_was_successful = false;
-            ROS_ERROR("[CONNECT START STOP GUI BAR] The 'm_type' variable was not recognised.");
+            ROS_ERROR("[TOP BANNER GUI] The 'm_type' variable was not recognised.");
             break;
         }
     }
@@ -292,4 +328,4 @@ bool TopBanner::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
-- 
GitLab


From 30b0edadf77b415d0c055a7479bc0ca002d13bdc Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 12 Dec 2018 11:13:14 +0100
Subject: [PATCH 15/87] Small corrections to be test in the lab

---
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h |  2 +-
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |  8 +++---
 pps_ws/src/d_fall_pps/launch/Config.sh        |  4 +--
 pps_ws/src/d_fall_pps/launch/Teacher.launch   | 26 ++++++++++++++++---
 4 files changed, 29 insertions(+), 11 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index 57faad75..6853169f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -49,7 +49,7 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/AreaBounds.h"
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/CMQuery.h"
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 5928885b..3b5cc3da 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -219,10 +219,10 @@ void TopBanner::loadCrazyflieContext()
 void TopBanner::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
-    fillIntMessageHeader(msg);
-    msg.data = CMD_RECONNECT;
-    this->crazyRadioCommandPublisher.publish(msg);
+    // d_fall_pps::IntWithHeader msg;
+    // fillIntMessageHeader(msg);
+    // msg.data = CMD_RECONNECT;
+    // this->crazyRadioCommandPublisher.publish(msg);
     ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
 #endif
 }
diff --git a/pps_ws/src/d_fall_pps/launch/Config.sh b/pps_ws/src/d_fall_pps/launch/Config.sh
index 26f36eae..3a8fb387 100755
--- a/pps_ws/src/d_fall_pps/launch/Config.sh
+++ b/pps_ws/src/d_fall_pps/launch/Config.sh
@@ -1,7 +1,7 @@
 # TO RUN THE SYSTEM FULLY ON THE LOCAL COMPUTER:
-export ROS_MASTER_URI=http://localhost:11311
+# export ROS_MASTER_URI=http://localhost:11311
 # TO RUN THE SYSTEM ON A DEFAULT CONFIGURATION OF THE NETWROK:
-# export ROS_MASTER_URI=http://teacher:11311
+export ROS_MASTER_URI=http://teacher:11311
 # OTHER NECESSARY ENVIRONMENT VARIABLES:
 export ROS_IP=$(hostname -I | awk '{print $1;}')
 export DFALL_DEFAULT_AGENT_ID=$(cat /etc/dfall_default_agent_id)
diff --git a/pps_ws/src/d_fall_pps/launch/Teacher.launch b/pps_ws/src/d_fall_pps/launch/Teacher.launch
index 21028d0c..609043d1 100755
--- a/pps_ws/src/d_fall_pps/launch/Teacher.launch
+++ b/pps_ws/src/d_fall_pps/launch/Teacher.launch
@@ -1,13 +1,31 @@
 <launch>
-	<node pkg="d_fall_pps" name="CentralManagerService" output="screen" type="CentralManagerService">
+
+	<!-- CENTRAL MANAGER -->
+	<node
+		pkg="d_fall_pps"
+		name="CentralManagerService"
+		output="screen"
+		type="CentralManagerService"
+		>
 	</node>
 
-	<node pkg="d_fall_pps" name="ViconDataPublisher" output="screen" type="ViconDataPublisher">
+	<!-- VICON DATA PUBLISHER -->
+	<node
+		pkg="d_fall_pps"
+		name="ViconDataPublisher"
+		output="screen"
+		type="ViconDataPublisher"
+		>
 		<rosparam command="load" file="$(find d_fall_pps)/param/ViconConfig.yaml" />
 	</node>
 
-	<!-- When we have a GUI, this has to be adapted and included -->
-	<node pkg="d_fall_pps" name="my_GUI" output="screen" type="my_GUI">
+	<!-- TEACHER GUI -->
+	<node
+		pkg="d_fall_pps"
+		name="my_GUI"
+		output="screen"
+		type="my_GUI"
+		>
 	</node>
 
 </launch>
-- 
GitLab


From 63f6111df205c5ab0d6d1534cdd073931fd05373 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 12 Dec 2018 11:31:47 +0100
Subject: [PATCH 16/87] Small adjustments for the teacher node to get the
 namespaces aligned

---
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp           |  2 +-
 .../CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp   | 10 ++++++----
 2 files changed, 7 insertions(+), 5 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
index 2f790f7e..32e7dc02 100755
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
@@ -871,7 +871,7 @@ void MainGUIWindow::on_save_in_DB_button_clicked()
                 tmp_entry.crazyflieContext.localArea.ymax = y_max * FROM_UNITS_TO_METERS;
 
                 tmp_entry.crazyflieContext.localArea.zmin = -0.2;
-                tmp_entry.crazyflieContext.localArea.zmax = 1.2;
+                tmp_entry.crazyflieContext.localArea.zmax = 2.2;
             }
         }
         tmp_db.crazyflieEntries.push_back(tmp_entry);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
index cae1ed0e..ab9fd2c5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
@@ -75,12 +75,14 @@ bool rosNodeThread::init()
     ros::Time::init();
     ros::NodeHandle nh("~");
 
-    m_vicon_subscriber = nh.subscribe("/ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this);
+    ros::NodeHandle nodeHandle_dfall_root("/dfall");
+
+    m_vicon_subscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this);
 
     // clients for db services:
-    m_read_db_client = nh.serviceClient<CMRead>("/CentralManagerService/Read", false);
-    m_update_db_client = nh.serviceClient<CMUpdate>("/CentralManagerService/Update", false);
-    m_command_db_client = nh.serviceClient<CMCommand>("/CentralManagerService/Command", false);
+    m_read_db_client = nodeHandle_dfall_root.serviceClient<CMRead>("CentralManagerService/Read", false);
+    m_update_db_client = nodeHandle_dfall_root.serviceClient<CMUpdate>("CentralManagerService/Update", false);
+    m_command_db_client = nodeHandle_dfall_root.serviceClient<CMCommand>("CentralManagerService/Command", false);
 
     m_pThread->start();
     return true;
-- 
GitLab


From 0ad77e15270e1617c652c2f24514f68d223a2ba3 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 12 Dec 2018 13:18:08 +0100
Subject: [PATCH 17/87] Small corrections for battery monitor to get the flying
 state from the PPS Client

---
 .../d_fall_pps/include/nodes/BatteryMonitor.h |  2 +-
 pps_ws/src/d_fall_pps/launch/Agent.launch     |  2 +-
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   | 20 +++++++++++++------
 3 files changed, 16 insertions(+), 8 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index 1739c05b..9d576b5b 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -191,7 +191,7 @@ float movingAverageBatteryFilter(float new_input);
 
 // > For converting a voltage to a percentage,
 //   depending on the current "my_flying_state" value
-float fromVoltageToPercent(float voltage , float operating_state);
+float fromVoltageToPercent(float voltage , int operating_state);
 // > For converting the percentage to a level
 int convertPercentageToLevel(float percentage);
 // > For updating the battery state based on the battery level
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index 942ee8ad..bb994eb3 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -113,7 +113,7 @@
 			<rosparam
 				command = "load"
 				file    = "$(find d_fall_pps)/param/ClientConfig.yaml"
-				ns      = "PPSClient"
+				ns      = "ClientConfig"
 			/>
 			<rosparam
 				command = "load"
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
index fbcf4cee..24787c0d 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
@@ -161,7 +161,7 @@ float movingAverageBatteryFilter(float new_input)
 
 
 // > For converting a voltage to a percentage, depending on the current "my_flying_state" value
-float fromVoltageToPercent(float voltage , float operating_state )
+float fromVoltageToPercent(float voltage , int operating_state )
 {
 	// INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
 	float voltage_when_full;
@@ -471,26 +471,34 @@ int main(int argc, char* argv[])
 	// PUBLISHERS
 
 	// Publisher for the filtered battery voltage
-	ros::Publisher filteredBatteryVoltagePublisher = nodeHandle.advertise<std_msgs::Float32>("FilteredVoltage",1);
+	filteredBatteryVoltagePublisher = nodeHandle.advertise<std_msgs::Float32>("FilteredVoltage",1);
 
 	// Publisher for the battery level
 	batteryLevelPublisher = nodeHandle.advertise<std_msgs::Int32>("Level",1);
 
 	// Publisher for changes in the battery state
-	ros::Publisher batteryStateChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("ChangedStateTo",1);
+	batteryStateChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("ChangedStateTo",1);
 
 
 
 	// SUBSCRIBERS
 
+	// Get a node handle to the Crazy Radio
+	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);
+
 	// Subscribe to the voltage of the battery
-	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, newBatteryVoltageCallback);
+	ros::Subscriber newBatteryVoltageSubscriber = nodeHandle_to_crazyradio.subscribe("CFBattery", 1, newBatteryVoltageCallback);
 
 	// Subscribe to the status of the Crazyradio: connected, connecting or disconnected
-	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
+	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle_to_crazyradio.subscribe("CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
 	// Subscribe to the flying state of the agent
-	ros::Subscriber agentOperatingStateSubscriber = nodeHandle.subscribe("PPS_Client/flyingState", 1, agentOperatingStateCallback);
+	ros::Subscriber agentOperatingStateSubscriber = nodeHandle_to_ppsclient.subscribe("flyingState", 1, agentOperatingStateCallback);
 
 	// Initialise the operating state
 	m_agent_operating_state = AGENT_OPERATING_STATE_MOTORS_OFF;
-- 
GitLab


From 41840a67283695efe31dc1427c49582e65c23bce Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 12 Dec 2018 16:28:18 +0100
Subject: [PATCH 18/87] Added some comments to the Vicon data Publisher.
 Important to note that the ROS_NAMESPACE environment variable needs to be set
 on the teacher computer

---
 .../src/nodes/StudentControllerService.cpp    |   5 +-
 .../src/nodes/ViconDataPublisher.cpp          | 280 +++++++++++-------
 2 files changed, 179 insertions(+), 106 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 5c357b31..d738c688 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -750,8 +750,9 @@ int main(int argc, char* argv[]) {
 	// Starting the ROS-node
 	ros::init(argc, argv, "StudentControllerService");
 
-	// Create a "ros::NodeHandle" type local variable "nodeHandle" as the current node,
-	// the "~" indcates that "self" is the node handle assigned to this variable.
+	// 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 "StudentControllerService" node
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp b/pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
index 2c9170a6..a6c1f4e6 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
@@ -43,145 +43,128 @@ using namespace ViconDataStreamSDK::CPP;
 using namespace d_fall_pps;
 
 int main(int argc, char* argv[]) {
-    ros::init(argc, argv, "ViconDataPublisher");
-
-    ros::NodeHandle nodeHandle("~");
-    ros::Time::init();
 
-    ros::Publisher viconDataPublisher =
-        nodeHandle.advertise<ViconData>("ViconData", 1);
 
 
-    #ifdef TESTING_FAKE_DATA
-    // Test faking data part
-    float f = 0;
-    int i = 0;
-
-    ROS_INFO("TESTING_FAKE_DATA.................................");
-    while(ros::ok())
-    {
-        if(i % 1000 == 0)
-        {
-        	ROS_INFO("iteration #%d",i);
-    	}
-
-        // Testing piece of code
-        ViconData viconData;
-        UnlabeledMarker marker;
+    // Starting the ROS-node
+    ros::init(argc, argv, "ViconDataPublisher");
 
-        marker.index = 0;
-        marker.x = f;
-        marker.y = 0;
-        marker.z = 0;
 
-        viconData.markers.push_back(marker);
 
+    // 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("~");
 
-        marker.index = 1;
-        marker.x = 0;
-        marker.y = f;
-        marker.z = 0;
 
-        viconData.markers.push_back(marker);
 
-        if(i > 50 && i < 100)
-        {
-            marker.index = 2;
-            marker.x = f;
-            marker.y = f;
-            marker.z = 0;
-            viconData.markers.push_back(marker);
-        }
+    // Initialise ROS time
+    ros::Time::init();
 
-        ros::Duration(0.1).sleep();
-        f += 10/1000.0f;
-        i++;
-        // TODO: Fake CF data
-        CrazyflieData crazyfly;
 
-        crazyfly.occluded = false;
 
-        crazyfly.crazyflieName = "CF1";
-        crazyfly.x = 0;
-        crazyfly.y = 0;
-        crazyfly.z = 0;
-        crazyfly.yaw = 3.14159 * f;
-        viconData.crazyflies.push_back(crazyfly);
+    // PUBLISHER FOR THE MOTION CAPTURE DATA
+    // > Created as a local variable becuase the "looping" of
+    //   ros is handled directly in the "while (ros::ok())"
+    //   loop below, i.e., this variable will not
+    //   go out-of-scope
+    ros::Publisher viconDataPublisher =
+        nodeHandle.advertise<ViconData>("ViconData", 1);
 
-        crazyfly.crazyflieName = "CF2";
-        crazyfly.x = 1;
-        crazyfly.y = 1;
-        crazyfly.z = 0;
-        crazyfly.yaw = -3.14159 * f;
-        viconData.crazyflies.push_back(crazyfly);
 
-        crazyfly.crazyflieName = "CF3";
-        crazyfly.x = 1;
-        crazyfly.y = -1;
-        crazyfly.z = 0;
-        crazyfly.yaw = -3.14159 * f;
 
+#ifdef TESTING_FAKE_DATA
+    testFakeData(viconDataPublisher);
+#else
 
-        if(i > 50 && i < 200)
-        {
-            crazyfly.occluded = true;
-        }
 
-        viconData.crazyflies.push_back(crazyfly);
 
-        viconDataPublisher.publish(viconData); // testing data
-    }
-    #else
+    // CLIENT FOR GETTING DATA FROM THE VICON DATA STREAM SDK
+    // > The "Client" variable type is defined in the header
+    //   "DataStreamClient.h"
+    Client vicon_client;
 
-    Client client;
 
+    // HOSTNAME (IP ADDRESS) OF THE "VICON COMPUTER"
+    // > This is specified in the "ViconConfig.yaml" file
+    // > That yaml file is added to this node during launch
+    // > The "Vicon Computer" runs the "Tacker" software that
+    //   is the heart of the Vicon Motion Capture system
     std::string hostName;
     if(!nodeHandle.getParam("hostName", hostName)) {
         ROS_ERROR("Failed to get hostName");
         return 1;
     }
 
-    ROS_INFO_STREAM("Connecting to " << hostName << " ...");
-    while (!client.IsConnected().Connected) {
-        bool ok = (client.Connect(hostName).Result == Result::Success);
 
-        if (!ok) {
-            ROS_ERROR("Error - connection failed...");
+
+    // CONNECT TO THE HOST (i.e., TO THE "VICON COMPUTER")
+
+    // Inform the user this is about to be attempted
+    ROS_INFO_STREAM("[VICON DATA PUBLISHER] Connecting to Vicon host with name: " << hostName );
+
+    // Attempt to connect in a while loop
+    while (!vicon_client.IsConnected().Connected)
+    {
+        // Get the connection status
+        bool ok = (vicon_client.Connect(hostName).Result == Result::Success);
+
+        if (!ok)
+        {
+            // If failed: inform the user and wait a bit
+            ROS_ERROR("[VICON DATA PUBLISHER] ERROR - connection failed... attempting again in 1 second");
             ros::Duration(1.0).sleep();
-        } else {
-            ROS_INFO("Connected successfully");
+        }
+        else
+        {
+            // If successful: inform the user
+            ROS_INFO("[VICON DATA PUBLISHER] Connected successfully to host");
         }
     }
 
-    //set data stream parameters
-    client.SetStreamMode(ViconDataStreamSDK::CPP::StreamMode::ServerPush); //maybe ServerPush instead of ClientPull for less latency
 
-    client.EnableSegmentData();
-    client.EnableMarkerData();
-    client.EnableUnlabeledMarkerData();
-    client.EnableDeviceData();
 
-    // Set the global up axis, such that Z is up
-    client.SetAxisMapping(Direction::Forward, Direction::Left, Direction::Up);
+    // SPECIFY THE SETTING OF THE VICON CLIENT
+
+    // Set "stream mode" parameter
+    // > OPTIONS: { ServerPush , ClientPull }
+    // > The "ServerPush" option should have the lowest latency
+    vicon_client.SetStreamMode(ViconDataStreamSDK::CPP::StreamMode::ServerPush); 
+
+    // Set what type of data should be provided
+    vicon_client.EnableSegmentData();
+    vicon_client.EnableMarkerData();
+    vicon_client.EnableUnlabeledMarkerData();
+    vicon_client.EnableDeviceData();
+
+    // Set the inertial frame convention such that positive
+    // Z points upwards
+    vicon_client.SetAxisMapping(Direction::Forward, Direction::Left, Direction::Up);
+
+
 
-    while (ros::ok()) {
+    // 
+    while (ros::ok())
+    {
         // Get a frame
-        while (client.GetFrame().Result != Result::Success) {
+        while (vicon_client.GetFrame().Result != Result::Success) {
             // Sleep a little so that we don't lumber the CPU with a busy poll
             ros::Duration(0.001).sleep();
         }
 
+        // Initilise a "ViconData" struct
+        // > This is defined in the "ViconData.msg" file
         ViconData viconData;
 
         // Unlabeled markers, for GUI
-        unsigned int unlabeledMarkerCount = client.GetUnlabeledMarkerCount().MarkerCount;
+        unsigned int unlabeledMarkerCount = vicon_client.GetUnlabeledMarkerCount().MarkerCount;
 
         UnlabeledMarker marker;
         for(int unlabeledMarkerIndex = 0; unlabeledMarkerIndex < unlabeledMarkerCount; unlabeledMarkerIndex++)
         {
 
             Output_GetUnlabeledMarkerGlobalTranslation OutputTranslation =
-                client.GetUnlabeledMarkerGlobalTranslation(unlabeledMarkerIndex);
+                vicon_client.GetUnlabeledMarkerGlobalTranslation(unlabeledMarkerIndex);
 
             marker.index = unlabeledMarkerIndex;
             marker.x = OutputTranslation.Translation[0]/1000.0f;
@@ -191,21 +174,21 @@ int main(int argc, char* argv[]) {
             viconData.markers.push_back(marker);
         }
 
-        unsigned int subjectCount = client.GetSubjectCount().SubjectCount;
+        unsigned int subjectCount = vicon_client.GetSubjectCount().SubjectCount;
 
         // //Process the data and publish on topic
         for (int index = 0; index < subjectCount; index++) {
-       		std::string subjectName = client.GetSubjectName(index).SubjectName;
-            std::string segmentName = client.GetSegmentName(subjectName, 0).SegmentName;
+       		std::string subjectName = vicon_client.GetSubjectName(index).SubjectName;
+            std::string segmentName = vicon_client.GetSegmentName(subjectName, 0).SegmentName;
 
 
             //continue only if the received frame is for the correct crazyflie
             Output_GetSegmentGlobalTranslation outputTranslation =
-                    client.GetSegmentGlobalTranslation(subjectName, segmentName);
+                    vicon_client.GetSegmentGlobalTranslation(subjectName, segmentName);
             //ROS_INFO_STREAM("translation occluded: " << outputTranslation.Occluded);
 
             Output_GetSegmentGlobalRotationQuaternion outputRotation =
-                    client.GetSegmentGlobalRotationQuaternion(subjectName, segmentName);
+                    vicon_client.GetSegmentGlobalRotationQuaternion(subjectName, segmentName);
             //ROS_INFO_STREAM("translation occluded: " << outputRotation.Occluded);
 
             //calculate position and rotation of Crazyflie
@@ -220,7 +203,7 @@ int main(int argc, char* argv[]) {
             double yaw = atan2(2 * (quat_w * quat_z + quat_x * quat_y), 1 - 2 * (quat_y * quat_y + quat_z * quat_z));
 
             //calculate time until frame data was received
-            Output_GetLatencyTotal outputLatencyTotal = client.GetLatencyTotal();
+            Output_GetLatencyTotal outputLatencyTotal = vicon_client.GetLatencyTotal();
             double totalViconLatency;
             if (outputLatencyTotal.Result == Result::Success) {
                 totalViconLatency = outputLatencyTotal.Total;
@@ -228,6 +211,7 @@ int main(int argc, char* argv[]) {
                 totalViconLatency = 0;
             }
 
+            
             //build message
             CrazyflieData cfData;
             cfData.crazyflieName = subjectName;
@@ -246,13 +230,101 @@ int main(int argc, char* argv[]) {
         }
         viconDataPublisher.publish(viconData);
     }
+    // END OF "while (ros::ok())"
 
-    client.DisableSegmentData();
-    client.DisableMarkerData();
-    client.DisableUnlabeledMarkerData();
-    client.DisableDeviceData();
-
-    client.Disconnect();
-    #endif
+    // The code only reaches this point if the while loop is
+    // broken, hence disable and diconnect the Vicon client
+    vicon_client.DisableSegmentData();
+    vicon_client.DisableMarkerData();
+    vicon_client.DisableUnlabeledMarkerData();
+    vicon_client.DisableDeviceData();
 
+    vicon_client.Disconnect();
+#endif
 }
+
+
+
+
+
+void testFakeData(ros::Publisher viconDataPublisher)
+{
+    // Test faking data part
+    float f = 0;
+    int i = 0;
+
+    ROS_INFO("[VICON DATA PUBLISHER] TESTING_FAKE_DATA");
+    while(ros::ok())
+    {
+        if(i % 1000 == 0)
+        {
+            ROS_INFO("iteration #%d",i);
+        }
+
+        // Testing piece of code
+        ViconData viconData;
+        UnlabeledMarker marker;
+
+        marker.index = 0;
+        marker.x = f;
+        marker.y = 0;
+        marker.z = 0;
+
+        viconData.markers.push_back(marker);
+
+
+        marker.index = 1;
+        marker.x = 0;
+        marker.y = f;
+        marker.z = 0;
+
+        viconData.markers.push_back(marker);
+
+        if(i > 50 && i < 100)
+        {
+            marker.index = 2;
+            marker.x = f;
+            marker.y = f;
+            marker.z = 0;
+            viconData.markers.push_back(marker);
+        }
+
+        ros::Duration(0.1).sleep();
+        f += 10/1000.0f;
+        i++;
+        // TODO: Fake CF data
+        CrazyflieData crazyfly;
+
+        crazyfly.occluded = false;
+
+        crazyfly.crazyflieName = "CF1";
+        crazyfly.x = 0;
+        crazyfly.y = 0;
+        crazyfly.z = 0;
+        crazyfly.yaw = 3.14159 * f;
+        viconData.crazyflies.push_back(crazyfly);
+
+        crazyfly.crazyflieName = "CF2";
+        crazyfly.x = 1;
+        crazyfly.y = 1;
+        crazyfly.z = 0;
+        crazyfly.yaw = -3.14159 * f;
+        viconData.crazyflies.push_back(crazyfly);
+
+        crazyfly.crazyflieName = "CF3";
+        crazyfly.x = 1;
+        crazyfly.y = -1;
+        crazyfly.z = 0;
+        crazyfly.yaw = -3.14159 * f;
+
+
+        if(i > 50 && i < 200)
+        {
+            crazyfly.occluded = true;
+        }
+
+        viconData.crazyflies.push_back(crazyfly);
+
+        viconDataPublisher.publish(viconData); // testing data
+    }
+}
\ No newline at end of file
-- 
GitLab


From 176e00d916436ec6238cd6233c89f08a0fcbd036 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 15 Dec 2018 17:53:11 +0100
Subject: [PATCH 19/87] Prepared the Qt side of things for connecting the
 default and student controller tabs with ROS. Next step is to add and test
 the ROS-side code

---
 .../flyingAgentGUI/forms/controllertabs.ui    |   6 +-
 .../forms/defaultcontrollertab.ui             | 307 +++++++++++++---
 .../forms/studentcontrollertab.ui             | 341 +++++++++++++++++-
 .../flyingAgentGUI/include/controllertabs.h   |  55 +++
 .../include/defaultcontrollertab.h            |  50 +++
 .../include/studentcontrollertab.h            |  34 ++
 .../flyingAgentGUI/src/controllertabs.cpp     |  40 ++
 .../src/defaultcontrollertab.cpp              | 284 ++++++++++++++-
 .../src/studentcontrollertab.cpp              |  23 ++
 .../src/d_fall_pps/msg/SetpointWithHeader.msg |   8 +
 10 files changed, 1071 insertions(+), 77 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index c1f3085f..b847e036 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -28,7 +28,7 @@
    <item row="0" column="0">
     <widget class="QTabWidget" name="controller_tabs_widget">
      <property name="currentIndex">
-      <number>3</number>
+      <number>2</number>
      </property>
      <widget class="QWidget" name="default_tab">
       <attribute name="title">
@@ -36,7 +36,7 @@
       </attribute>
       <layout class="QGridLayout" name="gridLayout_2">
        <item row="0" column="0">
-        <widget class="DefaultControllerTab" name="widget" native="true"/>
+        <widget class="DefaultControllerTab" name="default_controller_tab_widget" native="true"/>
        </item>
       </layout>
      </widget>
@@ -46,7 +46,7 @@
       </attribute>
       <layout class="QGridLayout" name="gridLayout_4">
        <item row="0" column="0">
-        <widget class="StudentControllerTab" name="widget_3" native="true"/>
+        <widget class="StudentControllerTab" name="student_controller_tab_widget" native="true"/>
        </item>
       </layout>
      </widget>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
index fc0b70b3..46a0ee55 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1545</width>
-    <height>632</height>
+    <width>1633</width>
+    <height>765</height>
    </rect>
   </property>
   <property name="font">
@@ -19,7 +19,7 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
-   <item row="2" column="10">
+   <item row="3" column="11">
     <spacer name="horizontalSpacer">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
@@ -32,7 +32,7 @@
      </property>
     </spacer>
    </item>
-   <item row="5" column="2">
+   <item row="6" column="3">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -59,7 +59,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="0">
+   <item row="5" column="1">
     <widget class="QLabel" name="label_row_z">
      <property name="maximumSize">
       <size>
@@ -75,7 +75,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="3">
+   <item row="5" column="4">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -99,20 +99,7 @@
      </property>
     </widget>
    </item>
-   <item row="7" column="0">
-    <spacer name="verticalSpacer">
-     <property name="orientation">
-      <enum>Qt::Vertical</enum>
-     </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>20</width>
-       <height>40</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="2" column="1">
+   <item row="3" column="2">
     <widget class="QLineEdit" name="lineEdit_error_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -139,7 +126,7 @@
      </property>
     </widget>
    </item>
-   <item row="0" column="1">
+   <item row="0" column="2">
     <widget class="QLabel" name="label_error_title">
      <property name="maximumSize">
       <size>
@@ -161,7 +148,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="3">
+   <item row="3" column="4">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -185,7 +172,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="4">
+   <item row="3" column="5">
     <spacer name="horizontalSpacer_2">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
@@ -201,12 +188,12 @@
      </property>
     </spacer>
    </item>
-   <item row="4" column="7">
+   <item row="5" column="8">
     <layout class="QHBoxLayout" name="horizontalLayout_2">
      <item>
       <widget class="QPushButton" name="z_increment_minus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -225,7 +212,7 @@
      <item>
       <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -246,7 +233,7 @@
      <item>
       <widget class="QPushButton" name="z_increment_plus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -264,7 +251,7 @@
      </item>
     </layout>
    </item>
-   <item row="3" column="0">
+   <item row="4" column="1">
     <widget class="QLabel" name="label_row_y">
      <property name="maximumSize">
       <size>
@@ -280,7 +267,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="0">
+   <item row="3" column="1">
     <widget class="QLabel" name="label_row_x">
      <property name="maximumSize">
       <size>
@@ -296,12 +283,12 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="7">
+   <item row="4" column="8">
     <layout class="QHBoxLayout" name="horizontalLayout_3">
      <item>
       <widget class="QPushButton" name="y_increment_minus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -320,7 +307,7 @@
      <item>
       <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -341,7 +328,7 @@
      <item>
       <widget class="QPushButton" name="y_increment_plus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -359,7 +346,7 @@
      </item>
     </layout>
    </item>
-   <item row="3" column="3">
+   <item row="4" column="4">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -383,7 +370,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="1">
+   <item row="4" column="2">
     <widget class="QLineEdit" name="lineEdit_error_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -410,12 +397,12 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="7">
+   <item row="6" column="8">
     <layout class="QHBoxLayout" name="horizontalLayout">
      <item>
       <widget class="QPushButton" name="yaw_increment_minus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -434,7 +421,7 @@
      <item>
       <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -455,7 +442,7 @@
      <item>
       <widget class="QPushButton" name="yaw_increment_plus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -473,7 +460,7 @@
      </item>
     </layout>
    </item>
-   <item row="0" column="7">
+   <item row="0" column="8">
     <widget class="QLabel" name="label_increment_title">
      <property name="maximumSize">
       <size>
@@ -495,7 +482,7 @@
      </property>
     </widget>
    </item>
-   <item row="1" column="3">
+   <item row="2" column="4">
     <widget class="QLabel" name="label_new_title_line2">
      <property name="maximumSize">
       <size>
@@ -511,7 +498,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="2">
+   <item row="4" column="3">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -538,7 +525,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="2">
+   <item row="3" column="3">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -565,7 +552,7 @@
      </property>
     </widget>
    </item>
-   <item row="1" column="2">
+   <item row="2" column="3">
     <widget class="QLabel" name="label_current_title_line2">
      <property name="maximumSize">
       <size>
@@ -581,7 +568,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="2">
+   <item row="5" column="3">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -608,7 +595,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="1">
+   <item row="5" column="2">
     <widget class="QLineEdit" name="lineEdit_error_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -635,7 +622,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="1">
+   <item row="6" column="2">
     <widget class="QLineEdit" name="lineEdit_error_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -662,7 +649,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="0">
+   <item row="6" column="1">
     <widget class="QLabel" name="label_row_yaw">
      <property name="maximumSize">
       <size>
@@ -678,7 +665,7 @@
      </property>
     </widget>
    </item>
-   <item row="1" column="1">
+   <item row="2" column="2">
     <widget class="QLabel" name="label_error_title_line2">
      <property name="maximumSize">
       <size>
@@ -687,19 +674,19 @@
       </size>
      </property>
      <property name="text">
-      <string>(meas-ref)</string>
+      <string>meas-ref</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="2" column="7">
+   <item row="3" column="8">
     <layout class="QHBoxLayout" name="horizontalLayout_4">
      <item>
       <widget class="QPushButton" name="x_increment_minus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -718,7 +705,7 @@
      <item>
       <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -739,7 +726,7 @@
      <item>
       <widget class="QPushButton" name="x_increment_plus_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
@@ -757,7 +744,7 @@
      </item>
     </layout>
    </item>
-   <item row="0" column="2">
+   <item row="0" column="3">
     <widget class="QLabel" name="label_current_title">
      <property name="maximumSize">
       <size>
@@ -779,7 +766,7 @@
      </property>
     </widget>
    </item>
-   <item row="1" column="7">
+   <item row="2" column="8">
     <widget class="QLabel" name="label_increment_title_line2">
      <property name="maximumSize">
       <size>
@@ -795,7 +782,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="3">
+   <item row="6" column="4">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -819,7 +806,7 @@
      </property>
     </widget>
    </item>
-   <item row="0" column="3">
+   <item row="0" column="4">
     <widget class="QLabel" name="label_new_title">
      <property name="maximumSize">
       <size>
@@ -841,7 +828,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="2">
+   <item row="7" column="3">
     <widget class="QPushButton" name="default_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -860,7 +847,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="3">
+   <item row="7" column="4">
     <widget class="QPushButton" name="set_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -879,6 +866,206 @@
      </property>
     </widget>
    </item>
+   <item row="3" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_x">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <widget class="QLabel" name="label_measured_title">
+     <property name="font">
+      <font>
+       <weight>75</weight>
+       <bold>true</bold>
+      </font>
+     </property>
+     <property name="text">
+      <string>Measured</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="2" column="0">
+    <widget class="QLabel" name="label_measured_title_line2">
+     <property name="text">
+      <string>Position</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="4" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_y">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="7" column="1">
+    <widget class="QLabel" name="label_row_pitch">
+     <property name="text">
+      <string>pitch [deg]</string>
+     </property>
+    </widget>
+   </item>
+   <item row="5" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_z">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="8" column="1">
+    <widget class="QLabel" name="label_row_roll">
+     <property name="text">
+      <string>roll [deg]</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="6" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_yaw">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="7" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_pitch">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="8" column="0">
+    <widget class="QLineEdit" name="lineEdit_measured_roll">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+    </widget>
+   </item>
+   <item row="9" column="0">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>40</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
   </layout>
  </widget>
  <resources/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index f72ca166..0360a46e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1366</width>
-    <height>703</height>
+    <width>1631</width>
+    <height>760</height>
    </rect>
   </property>
   <property name="font">
@@ -19,6 +19,16 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
+   <item row="1" column="6">
+    <widget class="QLabel" name="label">
+     <property name="text">
+      <string>Setpoint</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
    <item row="7" column="1">
     <widget class="QLabel" name="label_row_pitch">
      <property name="maximumSize">
@@ -57,6 +67,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="2" column="0">
@@ -81,9 +94,12 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
-   <item row="2" column="5">
+   <item row="2" column="7">
     <spacer name="horizontalSpacer">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
@@ -97,7 +113,7 @@
     </spacer>
    </item>
    <item row="8" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_yaw_2">
+    <widget class="QLineEdit" name="lineEdit_measured_roll">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -118,6 +134,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="9" column="0">
@@ -155,6 +174,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="3" column="1">
@@ -174,7 +196,7 @@
     </widget>
    </item>
    <item row="2" column="3">
-    <widget class="QLineEdit" name="lineEdit_current_x">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -195,6 +217,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="4" column="1">
@@ -235,6 +260,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="1" column="0">
@@ -269,6 +297,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="1">
@@ -309,6 +340,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="2">
@@ -333,6 +367,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="2" column="1">
@@ -405,6 +442,9 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="3" column="2">
@@ -429,10 +469,13 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="2" column="4">
-    <widget class="QLineEdit" name="lineEdit_new_x">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -453,7 +496,7 @@
     </widget>
    </item>
    <item row="3" column="3">
-    <widget class="QLineEdit" name="lineEdit_current_y">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -474,10 +517,13 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="4" column="3">
-    <widget class="QLineEdit" name="lineEdit_current_z">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -498,10 +544,13 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="5" column="3">
-    <widget class="QLineEdit" name="lineEdit_current_yaw">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -522,10 +571,13 @@
      <property name="text">
       <string>xx.xx</string>
      </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
    <item row="3" column="4">
-    <widget class="QLineEdit" name="lineEdit_new_y">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -546,7 +598,7 @@
     </widget>
    </item>
    <item row="4" column="4">
-    <widget class="QLineEdit" name="lineEdit_new_z">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -567,7 +619,7 @@
     </widget>
    </item>
    <item row="5" column="4">
-    <widget class="QLineEdit" name="lineEdit_new_yaw">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -644,7 +696,7 @@
    <item row="1" column="2">
     <widget class="QLabel" name="label_error_title_line2">
      <property name="text">
-      <string>(meas - ref)</string>
+      <string>meas-ref</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
@@ -703,6 +755,269 @@
      </property>
     </widget>
    </item>
+   <item row="2" column="5">
+    <spacer name="horizontalSpacer_2">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="sizeType">
+      <enum>QSizePolicy::Fixed</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>20</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="0" column="6">
+    <widget class="QLabel" name="label_2">
+     <property name="font">
+      <font>
+       <weight>75</weight>
+       <bold>true</bold>
+      </font>
+     </property>
+     <property name="text">
+      <string>Increment</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="2" column="6">
+    <layout class="QHBoxLayout" name="horizontalLayout">
+     <item>
+      <widget class="QPushButton" name="x_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="x_increment_plus_button">
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+   <item row="3" column="6">
+    <layout class="QHBoxLayout" name="horizontalLayout_2">
+     <item>
+      <widget class="QPushButton" name="y_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="y_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+   <item row="4" column="6">
+    <layout class="QHBoxLayout" name="horizontalLayout_3">
+     <item>
+      <widget class="QPushButton" name="z_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="z_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+   <item row="5" column="6">
+    <layout class="QHBoxLayout" name="horizontalLayout_4">
+     <item>
+      <widget class="QPushButton" name="yaw_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="yaw_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
   </layout>
  </widget>
  <resources/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 3ce77497..35cb2178 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -2,6 +2,34 @@
 #define CONTROLLERTABS_H
 
 #include <QWidget>
+#include <QVector>
+
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+//#include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/CrazyflieData.h"
+
+// Include the shared definitions
+//#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+//#include "include/Constants_for_Qt_compile.h"
+
+#endif
 
 namespace Ui {
 class ControllerTabs;
@@ -15,8 +43,35 @@ public:
     explicit ControllerTabs(QWidget *parent = 0);
     ~ControllerTabs();
 
+
+signals:
+    void measuredPoseValueChanged(QVector<float> measuredPose);
+
+
 private:
     Ui::ControllerTabs *ui;
+
+
+#ifdef CATKIN_MAKE
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES FOR ROS
+
+    // SUBSRIBER
+    // > For the pose data from a motion capture system
+    ros::Subscriber poseDataSubscriber;
+
+
+    // --------------------------------------------------- //
+    // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
+
+    // > For the controller currently operating, received on
+    //   "controllerUsedSubscriber"
+    void poseDataReceivedCallback(const d_fall_pps::CrazyflieData& msg);
+
+
+#endif
+
+
 };
 
 #endif // CONTROLLERTABS_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 33ad470c..6e95ea70 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -2,8 +2,35 @@
 #define DEFAULTCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QVector>
 #include <QTextStream>
 
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+//#include "include/Constants_for_Qt_compile.h"
+
+#endif
+
 namespace Ui {
 class DefaultControllerTab;
 }
@@ -16,6 +43,11 @@ public:
     explicit DefaultControllerTab(QWidget *parent = 0);
     ~DefaultControllerTab();
 
+
+public slots:
+    void setMeasuredPose(QVector<float> measuredPose);
+
+
 private slots:
     void on_lineEdit_setpoint_new_x_returnPressed();
     void on_lineEdit_setpoint_new_y_returnPressed();
@@ -24,8 +56,26 @@ private slots:
 
     void on_set_setpoint_button_clicked();
 
+    void on_default_setpoint_button_clicked();
+
+    void on_x_increment_plus_button_clicked();
+    void on_x_increment_minus_button_clicked();
+    void on_y_increment_plus_button_clicked();
+    void on_y_increment_minus_button_clicked();
+    void on_z_increment_plus_button_clicked();
+    void on_z_increment_minus_button_clicked();
+    void on_yaw_increment_plus_button_clicked();
+    void on_yaw_increment_minus_button_clicked();
+
 private:
     Ui::DefaultControllerTab *ui;
+
+#ifdef CATKIN_MAKE
+    SetpointWithHeader m_defaultSetpoint;
+#endif
+
+    void publishSetpoint(float x, float y, float z, float yaw);
+
 };
 
 #endif // DEFAULTCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index a56804fd..01af34d8 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -2,6 +2,35 @@
 #define STUDENTCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QVector>
+#include <QTextStream>
+
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+//#include "include/Constants_for_Qt_compile.h"
+
+#endif
+
 
 namespace Ui {
 class StudentControllerTab;
@@ -15,6 +44,11 @@ public:
     explicit StudentControllerTab(QWidget *parent = 0);
     ~StudentControllerTab();
 
+
+public slots:
+    void setMeasuredPose(QVector<float> measuredPose);
+
+
 private:
     Ui::StudentControllerTab *ui;
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 9c7e79ab..4340091b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -6,9 +6,49 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     ui(new Ui::ControllerTabs)
 {
     ui->setupUi(this);
+
+
+
+    // CONNECT THE "MEASURED POST" SIGNAL TO EACH OF
+    // THE TABS
+    // i.e., connect the "measured pose value changed"
+    // signal to the "set measured pose" slots
+    QObject::connect(
+            this , &ControllerTabs::measuredPoseValueChanged ,
+            ui->default_controller_tab_widget , &DefaultControllerTab::setMeasuredPose
+        );
+
+    QObject::connect(
+            this , &ControllerTabs::measuredPoseValueChanged ,
+            ui->student_controller_tab_widget , &StudentControllerTab::setMeasuredPose
+        );
+
 }
 
 ControllerTabs::~ControllerTabs()
 {
     delete ui;
 }
+
+
+
+#ifdef CATKIN_MAKE
+// > For the controller currently operating, received on
+//   "controllerUsedSubscriber"
+void poseDataReceivedCallback(const d_fall_pps::CrazyflieData& msg)
+{
+    // Initialise a Qvector to sending around
+    QVector<float> poseDataForSignal;
+    // Fill in the data
+    poseDataForSignal.push_back(msg.x);
+    poseDataForSignal.push_back(msg.y);
+    poseDataForSignal.push_back(msg.z);
+    poseDataForSignal.push_back(msg.roll);
+    poseDataForSignal.push_back(msg.pitch);
+    poseDataForSignal.push_back(msg.yaw);
+    // Emit the signal
+    emit measuredPoseValueChanged(poseDataForSignal);
+
+
+}
+#endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 27430450..f2b759d7 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -6,6 +6,16 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     ui(new Ui::DefaultControllerTab)
 {
     ui->setupUi(this);
+
+
+
+#ifdef CATKIN_MAKE
+    m_defaultSetpoint.x   = 0.0f;
+    m_defaultSetpoint.y   = 0.0f;
+    m_defaultSetpoint.z   = 0.5f;
+    m_defaultSetpoint.yaw = 0.0f;
+#endif
+
 }
 
 DefaultControllerTab::~DefaultControllerTab()
@@ -13,6 +23,60 @@ DefaultControllerTab::~DefaultControllerTab()
     delete ui;
 }
 
+
+void DefaultControllerTab::setMeasuredPose(QVector<float> measuredPose)
+{
+    // UPDATE THE MEASUREMENT COLUMN
+    ui->lineEdit_measured_x    ->setText(QString::number( measuredPose[0] ));
+    ui->lineEdit_measured_y    ->setText(QString::number( measuredPose[1] ));
+    ui->lineEdit_measured_z    ->setText(QString::number( measuredPose[2] ));
+    ui->lineEdit_measured_roll ->setText(QString::number( measuredPose[3] ));
+    ui->lineEdit_measured_pitch->setText(QString::number( measuredPose[4] ));
+    ui->lineEdit_measured_yaw  ->setText(QString::number( measuredPose[5] ));
+
+    // GET THE CURRENT SETPOINT
+    float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
+    float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
+    float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
+    float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+
+    // UPDATE THE ERROR COLUMN
+    ui->lineEdit_error_x  ->setText(QString::number( measuredPose[0] - curr_x_setpoint   ));
+    ui->lineEdit_error_y  ->setText(QString::number( measuredPose[1] - curr_y_setpoint   ));
+    ui->lineEdit_error_z  ->setText(QString::number( measuredPose[2] - curr_z_setpoint   ));
+    ui->lineEdit_error_yaw->setText(QString::number( measuredPose[5] - curr_yaw_setpoint ));
+}
+
+
+
+void publishSetpoint(float x, float y, float z, float yaw)
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.x   = x;
+    msg.y   = y;
+    msg.z   = z;
+    msg.yaw = yaw;
+
+    // Publish the setpoint
+    this->controllerSetpointPublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Published request for setpoint request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[DEFAULT CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]";
+#endif
+}
+
+
+
 void DefaultControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
 {
     ui->set_setpoint_button->animateClick();
@@ -41,10 +105,228 @@ void DefaultControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed()
 
 void DefaultControllerTab::on_set_setpoint_button_clicked()
 {
-
 #ifdef CATKIN_MAKE
+    // Initialise local variable for each of (x,y,z,yaw)
+    float x = 0.0f, y = 0.0f, z = 0.0f, yaw = 0.0f;
+
+    // Take the new value if available, otherwise use the old value
+    // > For x
+    if(!ui->lineEdit_setpoint_new_x->text().isEmpty())
+        x = (ui->lineEdit_setpoint_new_x->text()).toFloat();
+    else
+        x = (ui->lineEdit_setpoint_current_x->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
+        y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
+    else
+        y = (ui->lineEdit_setpoint_current_y->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
+        z = (ui->lineEdit_setpoint_new_z->text()).toFloat();
+    else
+        z = (ui->lineEdit_setpoint_current_z->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty())
+        yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat();
+    else
+        yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+    // Call the function to publish the setpoint
+    publishSetpoint(x,y,z,yaw);
+
 #else
     // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
     QTextStream(stdout) << "[DEFAULT CONTROLLER TAB] set setpoint button clicked";
 #endif
 }
+
+void DefaultControllerTab::on_default_setpoint_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Call the function to publish the setpoint
+    publishSetpoint(m_defaultSetpoint.x, m_defaultSetpoint.y, m_defaultSetpoint.z, m_defaultSetpoint.yaw );
+#endif
+}
+
+void DefaultControllerTab::on_x_increment_plus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_x->text()).toFloat()
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat()
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat()
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_x_increment_minus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_y_increment_plus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_y_increment_minus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_z_increment_plus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_z_increment_minus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+
+void DefaultControllerTab::on_yaw_increment_plus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
+void DefaultControllerTab::on_yaw_increment_minus_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() - (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+
+    }
+#endif
+}
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index a47ccd3b..f3561d0d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -12,3 +12,26 @@ StudentControllerTab::~StudentControllerTab()
 {
     delete ui;
 }
+
+void StudentControllerTab::setMeasuredPose(QVector<float> measuredPose)
+{
+    // UPDATE THE MEASUREMENT COLUMN
+    ui->lineEdit_measured_x    ->setText(QString::number( measuredPose[0] ));
+    ui->lineEdit_measured_y    ->setText(QString::number( measuredPose[1] ));
+    ui->lineEdit_measured_z    ->setText(QString::number( measuredPose[2] ));
+    ui->lineEdit_measured_roll ->setText(QString::number( measuredPose[3] ));
+    ui->lineEdit_measured_pitch->setText(QString::number( measuredPose[4] ));
+    ui->lineEdit_measured_yaw  ->setText(QString::number( measuredPose[5] ));
+
+    // GET THE CURRENT SETPOINT
+    float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
+    float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
+    float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
+    float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+
+    // UPDATE THE ERROR COLUMN
+    ui->lineEdit_error_x  ->setText(QString::number( measuredPose[0] - curr_x_setpoint      ));
+    ui->lineEdit_error_y  ->setText(QString::number( measuredPose[1] - curr_y_setpoint   ));
+    ui->lineEdit_error_z  ->setText(QString::number( measuredPose[2] - curr_z_setpoint   ));
+    ui->lineEdit_error_yaw->setText(QString::number( measuredPose[5] - curr_yaw_setpoint ));
+}
diff --git a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
new file mode 100644
index 00000000..9198063b
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
@@ -0,0 +1,8 @@
+float64 x
+float64 y
+float64 z
+float64 yaw
+bool isChecked
+uint32 buttonID
+bool shouldCheckForAgentID
+uint8[] agentIDs
\ No newline at end of file
-- 
GitLab


From d1627dea6b5e07f81353d8b3929c23b9edb552a8 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 17 Dec 2018 14:35:56 +0100
Subject: [PATCH 20/87] Default controller tab partially integrated with ROS
 and ready for testing

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   1 +
 .../flyingAgentGUI/include/controllertabs.h   |  28 +-
 .../include/defaultcontrollertab.h            |  40 ++-
 .../include/studentcontrollertab.h            |   2 +-
 .../flyingAgentGUI/src/controllertabs.cpp     | 178 ++++++++++++-
 .../src/defaultcontrollertab.cpp              | 242 ++++++++++++++++--
 .../src/studentcontrollertab.cpp              |  39 +--
 7 files changed, 465 insertions(+), 65 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 8fb21f1c..c77fe171 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -209,6 +209,7 @@ add_message_files(
   IntWithHeader.msg
   FloatWithHeader.msg
   StringWithHeader.msg
+  SetpointWithHeader.msg
   #------------------------
   DebugMsg.msg
   CustomButton.msg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 35cb2178..7ca9fbfc 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -2,6 +2,7 @@
 #define CONTROLLERTABS_H
 
 #include <QWidget>
+#include <QMutex>
 #include <QVector>
 
 #ifdef CATKIN_MAKE
@@ -18,6 +19,7 @@
 //#include "d_fall_pps/IntWithHeader.h"
 //#include "d_fall_pps/SetpointWithHeader.h"
 #include "d_fall_pps/CrazyflieData.h"
+#include "d_fall_pps/ViconData.h"
 
 // Include the shared definitions
 //#include "nodes/Constants.h"
@@ -45,12 +47,27 @@ public:
 
 
 signals:
-    void measuredPoseValueChanged(QVector<float> measuredPose);
+    void measuredPoseValueChanged(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
 
 
 private:
     Ui::ControllerTabs *ui;
 
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES
+
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
 
 #ifdef CATKIN_MAKE
     // --------------------------------------------------- //
@@ -58,17 +75,20 @@ private:
 
     // SUBSRIBER
     // > For the pose data from a motion capture system
-    ros::Subscriber poseDataSubscriber;
+    ros::Subscriber m_poseDataSubscriber;
+#endif
 
 
+#ifdef CATKIN_MAKE
     // --------------------------------------------------- //
     // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
 
     // > For the controller currently operating, received on
     //   "controllerUsedSubscriber"
-    void poseDataReceivedCallback(const d_fall_pps::CrazyflieData& msg);
-
+    void poseDataReceivedCallback(const d_fall_pps::ViconData& viconData);
 
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
 #endif
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 6e95ea70..6ee01b2e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -2,6 +2,7 @@
 #define DEFAULTCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QMutex>
 #include <QVector>
 #include <QTextStream>
 
@@ -45,7 +46,7 @@ public:
 
 
 public slots:
-    void setMeasuredPose(QVector<float> measuredPose);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
 
 
 private slots:
@@ -70,8 +71,43 @@ private slots:
 private:
     Ui::DefaultControllerTab *ui;
 
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES
+
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+
+
+#ifdef CATKIN_MAKE
+    // Variable for storing the default setpoint
+    d_fall_pps::SetpointWithHeader m_defaultSetpoint;
+
+    // PUBLISHER
+    // > For requesting the setpoint to be changed
+    ros::Publisher requestSetpointChangePublisher;
+#endif
+
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+
 #ifdef CATKIN_MAKE
-    SetpointWithHeader m_defaultSetpoint;
+    // Fill the header for a message
+    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
 #endif
 
     void publishSetpoint(float x, float y, float z, float yaw);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 01af34d8..c3c57fc1 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -46,7 +46,7 @@ public:
 
 
 public slots:
-    void setMeasuredPose(QVector<float> measuredPose);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
 
 
 private:
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 4340091b..5d5318c9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -23,6 +23,38 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->student_controller_tab_widget , &StudentControllerTab::setMeasuredPose
         );
 
+
+
+#ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[CONTROLLER TABS GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[CONTROLLER TABS GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE A NODE HANDLE TO THE D-FaLL ROOT
+    ros::NodeHandle nodeHandle_dfall_root("/dfall");
+
+    // CREATE THE SUBSCRIBER TO THE MOTION CAPTURE DATA
+    m_poseDataSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, &ControllerTabs::poseDataReceivedCallback, this);
+
+#endif
+
 }
 
 ControllerTabs::~ControllerTabs()
@@ -35,20 +67,142 @@ ControllerTabs::~ControllerTabs()
 #ifdef CATKIN_MAKE
 // > For the controller currently operating, received on
 //   "controllerUsedSubscriber"
-void poseDataReceivedCallback(const d_fall_pps::CrazyflieData& msg)
+void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& viconData)
 {
-    // Initialise a Qvector to sending around
-    QVector<float> poseDataForSignal;
-    // Fill in the data
-    poseDataForSignal.push_back(msg.x);
-    poseDataForSignal.push_back(msg.y);
-    poseDataForSignal.push_back(msg.z);
-    poseDataForSignal.push_back(msg.roll);
-    poseDataForSignal.push_back(msg.pitch);
-    poseDataForSignal.push_back(msg.yaw);
-    // Emit the signal
-    emit measuredPoseValueChanged(poseDataForSignal);
+    for(std::vector<d_fall_pps::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
+    {
+        d_fall_pps::CrazyflieData pose_in_global_frame = *it;
 
+        if(pose_in_global_frame.crazyflieName == "CF05")
+        {
+            emit measuredPoseValueChanged(
+                    pose_in_global_frame.x,
+                    pose_in_global_frame.y,
+                    pose_in_global_frame.z,
+                    pose_in_global_frame.roll,
+                    pose_in_global_frame.pitch,
+                    pose_in_global_frame.yaw,
+                    pose_in_global_frame.occluded
+                );
+        }
+    }
+
+
+    // OLD STYLE    
+    // // Initialise a Qvector to sending around
+    // QVector<float> poseDataForSignal;
+    // // Fill in the data
+    // poseDataForSignal.push_back(msg.x);
+    // poseDataForSignal.push_back(msg.y);
+    // poseDataForSignal.push_back(msg.z);
+    // poseDataForSignal.push_back(msg.roll);
+    // poseDataForSignal.push_back(msg.pitch);
+    // poseDataForSignal.push_back(msg.yaw);
+    // // Emit the signal
+    // emit measuredPoseValueChanged(poseDataForSignal);
 
 }
 #endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool ControllerTabs::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[DEFAULT CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[DEFAULT CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index f2b759d7..2e9040f3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -10,6 +10,32 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
 
 
 #ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[DEFAULT CONTROLLER TAB GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE COMMAND PUBLISHER
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("DefaultControllerService/RequestSetpointChange", 1);
+
+
+    // Set the default setpoint
     m_defaultSetpoint.x   = 0.0f;
     m_defaultSetpoint.y   = 0.0f;
     m_defaultSetpoint.z   = 0.5f;
@@ -24,39 +50,42 @@ DefaultControllerTab::~DefaultControllerTab()
 }
 
 
-void DefaultControllerTab::setMeasuredPose(QVector<float> measuredPose)
+void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
 {
-    // UPDATE THE MEASUREMENT COLUMN
-    ui->lineEdit_measured_x    ->setText(QString::number( measuredPose[0] ));
-    ui->lineEdit_measured_y    ->setText(QString::number( measuredPose[1] ));
-    ui->lineEdit_measured_z    ->setText(QString::number( measuredPose[2] ));
-    ui->lineEdit_measured_roll ->setText(QString::number( measuredPose[3] ));
-    ui->lineEdit_measured_pitch->setText(QString::number( measuredPose[4] ));
-    ui->lineEdit_measured_yaw  ->setText(QString::number( measuredPose[5] ));
-
-    // GET THE CURRENT SETPOINT
-    float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
-    float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
-    float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
-    float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
-
-    // UPDATE THE ERROR COLUMN
-    ui->lineEdit_error_x  ->setText(QString::number( measuredPose[0] - curr_x_setpoint   ));
-    ui->lineEdit_error_y  ->setText(QString::number( measuredPose[1] - curr_y_setpoint   ));
-    ui->lineEdit_error_z  ->setText(QString::number( measuredPose[2] - curr_z_setpoint   ));
-    ui->lineEdit_error_yaw->setText(QString::number( measuredPose[5] - curr_yaw_setpoint ));
+    if (!occluded)
+    {
+        // UPDATE THE MEASUREMENT COLUMN
+        ui->lineEdit_measured_x    ->setText(QString::number( x     ));
+        ui->lineEdit_measured_y    ->setText(QString::number( y     ));
+        ui->lineEdit_measured_z    ->setText(QString::number( z     ));
+        ui->lineEdit_measured_roll ->setText(QString::number( roll  ));
+        ui->lineEdit_measured_pitch->setText(QString::number( pitch ));
+        ui->lineEdit_measured_yaw  ->setText(QString::number( yaw   ));
+
+        // GET THE CURRENT SETPOINT
+        float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
+        float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
+        float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
+        float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+
+        // UPDATE THE ERROR COLUMN
+        ui->lineEdit_error_x  ->setText(QString::number( x   - curr_x_setpoint   ));
+        ui->lineEdit_error_y  ->setText(QString::number( y   - curr_y_setpoint   ));
+        ui->lineEdit_error_z  ->setText(QString::number( z   - curr_z_setpoint   ));
+        ui->lineEdit_error_yaw->setText(QString::number( yaw - curr_yaw_setpoint ));
+    }
 }
 
 
 
-void publishSetpoint(float x, float y, float z, float yaw)
+void DefaultControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    SetpointWithHeader msg;
+    d_fall_pps::SetpointWithHeader msg;
 
     // Fill the header of the message
-    fillSetpointHeader( msg );
+    fillSetpointMessageHeader( msg );
 
     // Fill in the (x,y,z,yaw) values
     msg.x   = x;
@@ -65,10 +94,10 @@ void publishSetpoint(float x, float y, float z, float yaw)
     msg.yaw = yaw;
 
     // Publish the setpoint
-    this->controllerSetpointPublisher.publish(msg);
+    this->requestSetpointChangePublisher.publish(msg);
 
     // Inform the user about the change
-    ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Published request for setpoint request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
+    ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
 #else
     // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
     QTextStream(stdout) << "[DEFAULT CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]";
@@ -156,9 +185,9 @@ void DefaultControllerTab::on_x_increment_plus_button_clicked()
     {
         // Call the function to publish the setpoint
         publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_x->text()).toFloat()
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat()
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat()
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
                 (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
             );
     }
@@ -330,3 +359,160 @@ void DefaultControllerTab::on_yaw_increment_minus_button_clicked()
     }
 #endif
 }
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the head for a message
+void DefaultControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool DefaultControllerTab::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[DEFAULT CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[DEFAULT CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[DEFAULT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index f3561d0d..9cb9fe7b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -13,25 +13,28 @@ StudentControllerTab::~StudentControllerTab()
     delete ui;
 }
 
-void StudentControllerTab::setMeasuredPose(QVector<float> measuredPose)
+void StudentControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
 {
-    // UPDATE THE MEASUREMENT COLUMN
-    ui->lineEdit_measured_x    ->setText(QString::number( measuredPose[0] ));
-    ui->lineEdit_measured_y    ->setText(QString::number( measuredPose[1] ));
-    ui->lineEdit_measured_z    ->setText(QString::number( measuredPose[2] ));
-    ui->lineEdit_measured_roll ->setText(QString::number( measuredPose[3] ));
-    ui->lineEdit_measured_pitch->setText(QString::number( measuredPose[4] ));
-    ui->lineEdit_measured_yaw  ->setText(QString::number( measuredPose[5] ));
+    if (!occluded)
+    {
+        // UPDATE THE MEASUREMENT COLUMN
+        ui->lineEdit_measured_x    ->setText(QString::number( x     ));
+        ui->lineEdit_measured_y    ->setText(QString::number( y     ));
+        ui->lineEdit_measured_z    ->setText(QString::number( z     ));
+        ui->lineEdit_measured_roll ->setText(QString::number( roll  ));
+        ui->lineEdit_measured_pitch->setText(QString::number( pitch ));
+        ui->lineEdit_measured_yaw  ->setText(QString::number( yaw   ));
 
-    // GET THE CURRENT SETPOINT
-    float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
-    float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
-    float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
-    float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+        // GET THE CURRENT SETPOINT
+        float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
+        float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
+        float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
+        float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
 
-    // UPDATE THE ERROR COLUMN
-    ui->lineEdit_error_x  ->setText(QString::number( measuredPose[0] - curr_x_setpoint      ));
-    ui->lineEdit_error_y  ->setText(QString::number( measuredPose[1] - curr_y_setpoint   ));
-    ui->lineEdit_error_z  ->setText(QString::number( measuredPose[2] - curr_z_setpoint   ));
-    ui->lineEdit_error_yaw->setText(QString::number( measuredPose[5] - curr_yaw_setpoint ));
+        // UPDATE THE ERROR COLUMN
+        ui->lineEdit_error_x  ->setText(QString::number( x   - curr_x_setpoint   ));
+        ui->lineEdit_error_y  ->setText(QString::number( y   - curr_y_setpoint   ));
+        ui->lineEdit_error_z  ->setText(QString::number( z   - curr_z_setpoint   ));
+        ui->lineEdit_error_yaw->setText(QString::number( yaw - curr_yaw_setpoint ));
+    }
 }
-- 
GitLab


From f994efb8bfeb16b9a863b5a3f6cd1e97eb9884b0 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 17 Dec 2018 15:08:16 +0100
Subject: [PATCH 21/87] Vicon data now displaying in the default controller
 tab. Needs to be cleaned up and generalised

---
 .../src/defaultcontrollertab.cpp              | 47 +++++++++++++------
 1 file changed, 33 insertions(+), 14 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 2e9040f3..3b2c3896 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -54,25 +54,44 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
 {
     if (!occluded)
     {
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+        QString qstr = "";
         // UPDATE THE MEASUREMENT COLUMN
-        ui->lineEdit_measured_x    ->setText(QString::number( x     ));
-        ui->lineEdit_measured_y    ->setText(QString::number( y     ));
-        ui->lineEdit_measured_z    ->setText(QString::number( z     ));
-        ui->lineEdit_measured_roll ->setText(QString::number( roll  ));
-        ui->lineEdit_measured_pitch->setText(QString::number( pitch ));
-        ui->lineEdit_measured_yaw  ->setText(QString::number( yaw   ));
+        if (x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_x    ->setText(qstr + QString::number( x, 'f', 3));
+        if (y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_y    ->setText(qstr + QString::number( y, 'f', 3));
+        if (z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_z    ->setText(qstr + QString::number( z, 'f', 3));
+
+        if (roll < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_roll ->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        if (pitch < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
+        if (yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_yaw  ->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
 
         // GET THE CURRENT SETPOINT
-        float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
-        float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
-        float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
-        float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+        float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
+        float error_y   = y   - (ui->lineEdit_setpoint_current_y->text()  ).toFloat();
+        float error_z   = z   - (ui->lineEdit_setpoint_current_z->text()  ).toFloat();
+        float error_yaw = yaw - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
         // UPDATE THE ERROR COLUMN
-        ui->lineEdit_error_x  ->setText(QString::number( x   - curr_x_setpoint   ));
-        ui->lineEdit_error_y  ->setText(QString::number( y   - curr_y_setpoint   ));
-        ui->lineEdit_error_z  ->setText(QString::number( z   - curr_z_setpoint   ));
-        ui->lineEdit_error_yaw->setText(QString::number( yaw - curr_yaw_setpoint ));
+        if (error_x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_x  ->setText(qstr + QString::number( error_x, 'f', 3));
+        if (error_y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_y  ->setText(qstr + QString::number( error_y, 'f', 3));
+        if (error_z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_z  ->setText(qstr + QString::number( error_z, 'f', 3));
+
+        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+    }
+    else
+    {
+        //ui->label_measured_title->setTextColor(Qt::green);
+        //ui->label_measured_title_line2
     }
 }
 
-- 
GitLab


From 66a57af569a6ef224628b3dc89b82f779d50fc92 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 17 Dec 2018 18:51:48 +0100
Subject: [PATCH 22/87] Added things to GUI: red rectangles to indicated an
 occluded measurement, and unavailable image for battery and flying state

---
 .../GUI_Qt/flyingAgentGUI/flyingagentgui.qrc  |    6 +-
 .../forms/defaultcontrollertab.ui             |  177 ++-
 .../forms/studentcontrollertab.ui             | 1037 +++++++++--------
 .../images/battery_unavailable.png            |  Bin 0 -> 2775 bytes
 .../images/flying_state_unavilable.png        |  Bin 0 -> 4797 bytes
 .../include/defaultcontrollertab.h            |    2 +-
 .../src/connectstartstopbar.cpp               |    2 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |    2 +-
 .../src/defaultcontrollertab.cpp              |   20 +-
 9 files changed, 694 insertions(+), 552 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavilable.png

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
index 0f6e7d8e..ebe28271 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
@@ -6,14 +6,16 @@
         <file>images/battery_80.png</file>
         <file>images/battery_empty.png</file>
         <file>images/battery_full.png</file>
+        <file>images/battery_unknown.png</file>
+        <file>images/battery_unavailable.png</file>
         <file>images/rf_connected.png</file>
         <file>images/rf_connecting.png</file>
         <file>images/rf_disconnected.png</file>
-        <file>images/battery_unknown.png</file>
         <file>images/flying_state_disabling.png</file>
         <file>images/flying_state_enabling.png</file>
         <file>images/flying_state_flying.png</file>
         <file>images/flying_state_off.png</file>
         <file>images/flying_state_unknown.png</file>
+        <file>images/flying_state_unavilable.png</file>
     </qresource>
-</RCC>
+</RCC>
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
index 46a0ee55..64921ccc 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
@@ -19,7 +19,7 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
-   <item row="3" column="11">
+   <item row="3" column="13">
     <spacer name="horizontalSpacer">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
@@ -32,7 +32,7 @@
      </property>
     </spacer>
    </item>
-   <item row="6" column="3">
+   <item row="6" column="5">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -59,7 +59,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="1">
+   <item row="5" column="3">
     <widget class="QLabel" name="label_row_z">
      <property name="maximumSize">
       <size>
@@ -75,7 +75,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="4">
+   <item row="5" column="6">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -99,7 +99,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="2">
+   <item row="3" column="4">
     <widget class="QLineEdit" name="lineEdit_error_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -126,7 +126,7 @@
      </property>
     </widget>
    </item>
-   <item row="0" column="2">
+   <item row="0" column="4">
     <widget class="QLabel" name="label_error_title">
      <property name="maximumSize">
       <size>
@@ -148,7 +148,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="4">
+   <item row="3" column="6">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -172,7 +172,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="5">
+   <item row="3" column="7">
     <spacer name="horizontalSpacer_2">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
@@ -188,7 +188,7 @@
      </property>
     </spacer>
    </item>
-   <item row="5" column="8">
+   <item row="5" column="10">
     <layout class="QHBoxLayout" name="horizontalLayout_2">
      <item>
       <widget class="QPushButton" name="z_increment_minus_button">
@@ -251,7 +251,7 @@
      </item>
     </layout>
    </item>
-   <item row="4" column="1">
+   <item row="4" column="3">
     <widget class="QLabel" name="label_row_y">
      <property name="maximumSize">
       <size>
@@ -267,7 +267,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="1">
+   <item row="3" column="3">
     <widget class="QLabel" name="label_row_x">
      <property name="maximumSize">
       <size>
@@ -283,7 +283,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="8">
+   <item row="4" column="10">
     <layout class="QHBoxLayout" name="horizontalLayout_3">
      <item>
       <widget class="QPushButton" name="y_increment_minus_button">
@@ -346,7 +346,7 @@
      </item>
     </layout>
    </item>
-   <item row="4" column="4">
+   <item row="4" column="6">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -370,7 +370,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="2">
+   <item row="4" column="4">
     <widget class="QLineEdit" name="lineEdit_error_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -397,7 +397,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="8">
+   <item row="6" column="10">
     <layout class="QHBoxLayout" name="horizontalLayout">
      <item>
       <widget class="QPushButton" name="yaw_increment_minus_button">
@@ -460,7 +460,7 @@
      </item>
     </layout>
    </item>
-   <item row="0" column="8">
+   <item row="0" column="10">
     <widget class="QLabel" name="label_increment_title">
      <property name="maximumSize">
       <size>
@@ -482,7 +482,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="4">
+   <item row="2" column="6">
     <widget class="QLabel" name="label_new_title_line2">
      <property name="maximumSize">
       <size>
@@ -498,7 +498,7 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="3">
+   <item row="4" column="5">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -525,7 +525,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="3">
+   <item row="3" column="5">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -552,7 +552,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="3">
+   <item row="2" column="5">
     <widget class="QLabel" name="label_current_title_line2">
      <property name="maximumSize">
       <size>
@@ -568,7 +568,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="3">
+   <item row="5" column="5">
     <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -595,7 +595,7 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="2">
+   <item row="5" column="4">
     <widget class="QLineEdit" name="lineEdit_error_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -622,7 +622,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="2">
+   <item row="6" column="4">
     <widget class="QLineEdit" name="lineEdit_error_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -649,7 +649,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="1">
+   <item row="6" column="3">
     <widget class="QLabel" name="label_row_yaw">
      <property name="maximumSize">
       <size>
@@ -665,7 +665,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="2">
+   <item row="2" column="4">
     <widget class="QLabel" name="label_error_title_line2">
      <property name="maximumSize">
       <size>
@@ -681,7 +681,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="8">
+   <item row="3" column="10">
     <layout class="QHBoxLayout" name="horizontalLayout_4">
      <item>
       <widget class="QPushButton" name="x_increment_minus_button">
@@ -744,7 +744,7 @@
      </item>
     </layout>
    </item>
-   <item row="0" column="3">
+   <item row="0" column="5">
     <widget class="QLabel" name="label_current_title">
      <property name="maximumSize">
       <size>
@@ -766,7 +766,7 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="8">
+   <item row="2" column="10">
     <widget class="QLabel" name="label_increment_title_line2">
      <property name="maximumSize">
       <size>
@@ -782,7 +782,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="4">
+   <item row="6" column="6">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -806,7 +806,7 @@
      </property>
     </widget>
    </item>
-   <item row="0" column="4">
+   <item row="0" column="6">
     <widget class="QLabel" name="label_new_title">
      <property name="maximumSize">
       <size>
@@ -828,7 +828,7 @@
      </property>
     </widget>
    </item>
-   <item row="7" column="3">
+   <item row="7" column="5">
     <widget class="QPushButton" name="default_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -847,7 +847,7 @@
      </property>
     </widget>
    </item>
-   <item row="7" column="4">
+   <item row="7" column="6">
     <widget class="QPushButton" name="set_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -866,7 +866,7 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="0">
+   <item row="3" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -890,7 +890,7 @@
      </property>
     </widget>
    </item>
-   <item row="0" column="0">
+   <item row="0" column="1">
     <widget class="QLabel" name="label_measured_title">
      <property name="font">
       <font>
@@ -906,17 +906,14 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="0">
-    <widget class="QLabel" name="label_measured_title_line2">
+   <item row="7" column="3">
+    <widget class="QLabel" name="label_row_pitch">
      <property name="text">
-      <string>Position</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+      <string>pitch [deg]</string>
      </property>
     </widget>
    </item>
-   <item row="4" column="0">
+   <item row="4" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -940,14 +937,7 @@
      </property>
     </widget>
    </item>
-   <item row="7" column="1">
-    <widget class="QLabel" name="label_row_pitch">
-     <property name="text">
-      <string>pitch [deg]</string>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="0">
+   <item row="5" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -971,7 +961,7 @@
      </property>
     </widget>
    </item>
-   <item row="8" column="1">
+   <item row="8" column="3">
     <widget class="QLabel" name="label_row_roll">
      <property name="text">
       <string>roll [deg]</string>
@@ -981,7 +971,7 @@
      </property>
     </widget>
    </item>
-   <item row="6" column="0">
+   <item row="6" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -1005,7 +995,7 @@
      </property>
     </widget>
    </item>
-   <item row="7" column="0">
+   <item row="7" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_pitch">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -1029,7 +1019,7 @@
      </property>
     </widget>
    </item>
-   <item row="8" column="0">
+   <item row="8" column="1">
     <widget class="QLineEdit" name="lineEdit_measured_roll">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -1053,7 +1043,7 @@
      </property>
     </widget>
    </item>
-   <item row="9" column="0">
+   <item row="10" column="1">
     <spacer name="verticalSpacer">
      <property name="orientation">
       <enum>Qt::Vertical</enum>
@@ -1066,6 +1056,85 @@
      </property>
     </spacer>
    </item>
+   <item row="2" column="1">
+    <layout class="QHBoxLayout" name="horizontalLayout_5">
+     <property name="spacing">
+      <number>0</number>
+     </property>
+     <property name="leftMargin">
+      <number>0</number>
+     </property>
+     <property name="topMargin">
+      <number>0</number>
+     </property>
+     <property name="rightMargin">
+      <number>0</number>
+     </property>
+     <property name="bottomMargin">
+      <number>0</number>
+     </property>
+     <item>
+      <widget class="QFrame" name="red_frame_position_left">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>10</width>
+         <height>16777215</height>
+        </size>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">background-color:red;</string>
+       </property>
+       <property name="frameShape">
+        <enum>QFrame::StyledPanel</enum>
+       </property>
+       <property name="frameShadow">
+        <enum>QFrame::Raised</enum>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLabel" name="label_measured_title_line2">
+       <property name="text">
+        <string>Position</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QFrame" name="red_frame_position_right">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>10</width>
+         <height>16777215</height>
+        </size>
+       </property>
+       <property name="styleSheet">
+        <string notr="true">background-color:red;</string>
+       </property>
+       <property name="frameShape">
+        <enum>QFrame::StyledPanel</enum>
+       </property>
+       <property name="frameShadow">
+        <enum>QFrame::Raised</enum>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
   </layout>
  </widget>
  <resources/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index 0360a46e..c21c48a5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -19,61 +19,8 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
-   <item row="1" column="6">
-    <widget class="QLabel" name="label">
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="1">
-    <widget class="QLabel" name="label_row_pitch">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>pitch [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_x">
+   <item row="5" column="3">
+    <widget class="QLineEdit" name="lineEdit_error_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -100,60 +47,128 @@
     </widget>
    </item>
    <item row="2" column="7">
-    <spacer name="horizontalSpacer">
+    <layout class="QHBoxLayout" name="horizontalLayout">
+     <item>
+      <widget class="QPushButton" name="x_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="x_increment_plus_button">
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+   <item row="2" column="6">
+    <spacer name="horizontalSpacer_2">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
      </property>
+     <property name="sizeType">
+      <enum>QSizePolicy::Fixed</enum>
+     </property>
      <property name="sizeHint" stdset="0">
       <size>
-       <width>40</width>
+       <width>20</width>
        <height>20</height>
       </size>
      </property>
     </spacer>
    </item>
-   <item row="8" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_roll">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
+   <item row="5" column="2">
+    <widget class="QLabel" name="label_row_yaw">
      <property name="maximumSize">
       <size>
-       <width>180</width>
+       <width>16777215</width>
        <height>60</height>
       </size>
      </property>
+     <property name="text">
+      <string>yaw [deg]</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="4">
+    <widget class="QLabel" name="label_current_title">
      <property name="font">
       <font>
-       <family>Courier</family>
+       <weight>75</weight>
+       <bold>true</bold>
       </font>
      </property>
      <property name="text">
-      <string>xx.xx</string>
+      <string>Current</string>
      </property>
-     <property name="readOnly">
-      <bool>true</bool>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="9" column="0">
-    <spacer name="verticalSpacer">
-     <property name="orientation">
-      <enum>Qt::Vertical</enum>
+   <item row="0" column="1">
+    <widget class="QLabel" name="label_measured_title">
+     <property name="font">
+      <font>
+       <weight>75</weight>
+       <bold>true</bold>
+      </font>
      </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>20</width>
-       <height>40</height>
-      </size>
+     <property name="text">
+      <string>Measured</string>
      </property>
-    </spacer>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
    </item>
-   <item row="4" column="2">
-    <widget class="QLineEdit" name="lineEdit_error_z">
+   <item row="7" column="4">
+    <widget class="QPushButton" name="default_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -166,20 +181,12 @@
        <height>60</height>
       </size>
      </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
      <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
+      <string>Default</string>
      </property>
     </widget>
    </item>
-   <item row="3" column="1">
+   <item row="3" column="2">
     <widget class="QLabel" name="label_row_y">
      <property name="maximumSize">
       <size>
@@ -195,8 +202,8 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="3">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
+   <item row="4" column="5">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -214,16 +221,10 @@
        <family>Courier</family>
       </font>
      </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
     </widget>
    </item>
-   <item row="4" column="1">
-    <widget class="QLabel" name="label_row_z">
+   <item row="8" column="2">
+    <widget class="QLabel" name="label_row_roll">
      <property name="maximumSize">
       <size>
        <width>16777215</width>
@@ -231,52 +232,25 @@
       </size>
      </property>
      <property name="text">
-      <string>z [m]</string>
+      <string>roll [deg]</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="5" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="1" column="0">
-    <widget class="QLabel" name="label_measured_title_line2">
+   <item row="1" column="5">
+    <widget class="QLabel" name="label_new_title_line2">
      <property name="text">
-      <string>Position</string>
+      <string>Setpoint</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="3" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_y">
+   <item row="2" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -302,33 +276,91 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="1">
-    <widget class="QLabel" name="label_row_yaw">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
+   <item row="0" column="5">
+    <widget class="QLabel" name="label_new_title">
+     <property name="font">
+      <font>
+       <weight>75</weight>
+       <bold>true</bold>
+      </font>
      </property>
      <property name="text">
-      <string>yaw [deg]</string>
+      <string>New</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="2" column="2">
-    <widget class="QLineEdit" name="lineEdit_error_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
+   <item row="4" column="7">
+    <layout class="QHBoxLayout" name="horizontalLayout_3">
+     <item>
+      <widget class="QPushButton" name="z_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="z_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
+   </item>
+   <item row="2" column="3">
+    <widget class="QLineEdit" name="lineEdit_error_x">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
+     </property>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
        <height>60</height>
       </size>
      </property>
@@ -345,8 +377,8 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="2">
-    <widget class="QLineEdit" name="lineEdit_error_yaw">
+   <item row="3" column="3">
+    <widget class="QLineEdit" name="lineEdit_error_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -372,40 +404,124 @@
      </property>
     </widget>
    </item>
-   <item row="2" column="1">
-    <widget class="QLabel" name="label_row_x">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>x [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
+   <item row="5" column="7">
+    <layout class="QHBoxLayout" name="horizontalLayout_4">
+     <item>
+      <widget class="QPushButton" name="yaw_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="yaw_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
    </item>
-   <item row="8" column="1">
-    <widget class="QLabel" name="label_row_roll">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>roll [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
+   <item row="3" column="7">
+    <layout class="QHBoxLayout" name="horizontalLayout_2">
+     <item>
+      <widget class="QPushButton" name="y_increment_minus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>-</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>140</width>
+         <height>60</height>
+        </size>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QPushButton" name="y_increment_plus_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>60</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>+</string>
+       </property>
+      </widget>
+     </item>
+    </layout>
    </item>
-   <item row="0" column="0">
-    <widget class="QLabel" name="label_measured_title">
+   <item row="0" column="3">
+    <widget class="QLabel" name="label_error_title">
      <property name="font">
       <font>
        <weight>75</weight>
@@ -413,15 +529,15 @@
       </font>
      </property>
      <property name="text">
-      <string>Measured</string>
+      <string>Error</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="7" column="0">
-    <widget class="QLineEdit" name="lineEdit_measured_pitch">
+   <item row="7" column="5">
+    <widget class="QPushButton" name="set_setpoint_button">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -434,21 +550,23 @@
        <height>60</height>
       </size>
      </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
+     <property name="text">
+      <string>Set New</string>
      </property>
+    </widget>
+   </item>
+   <item row="1" column="3">
+    <widget class="QLabel" name="label_error_title_line2">
      <property name="text">
-      <string>xx.xx</string>
+      <string>meas-ref</string>
      </property>
-     <property name="readOnly">
-      <bool>true</bool>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="3" column="2">
-    <widget class="QLineEdit" name="lineEdit_error_y">
+   <item row="2" column="5">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -466,16 +584,10 @@
        <family>Courier</family>
       </font>
      </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
     </widget>
    </item>
-   <item row="2" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
+   <item row="5" column="5">
+    <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -495,8 +607,8 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="3">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
+   <item row="4" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -522,8 +634,31 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="3">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
+   <item row="2" column="8">
+    <spacer name="horizontalSpacer">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>40</width>
+       <height>20</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="1" column="7">
+    <widget class="QLabel" name="label">
+     <property name="text">
+      <string>Setpoint</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="8" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_roll">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -549,8 +684,8 @@
      </property>
     </widget>
    </item>
-   <item row="5" column="3">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
+   <item row="7" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_pitch">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -576,7 +711,39 @@
      </property>
     </widget>
    </item>
-   <item row="3" column="4">
+   <item row="7" column="2">
+    <widget class="QLabel" name="label_row_pitch">
+     <property name="maximumSize">
+      <size>
+       <width>16777215</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="text">
+      <string>pitch [deg]</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="2" column="2">
+    <widget class="QLabel" name="label_row_x">
+     <property name="maximumSize">
+      <size>
+       <width>16777215</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="text">
+      <string>x [m]</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="3" column="5">
     <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
@@ -597,8 +764,8 @@
      </property>
     </widget>
    </item>
-   <item row="4" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
+   <item row="3" column="4">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -616,10 +783,39 @@
        <family>Courier</family>
       </font>
      </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
+   <item row="1" column="4">
+    <widget class="QLabel" name="label_current_title_2">
+     <property name="text">
+      <string>Setpoint</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="9" column="1">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>40</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
    <item row="5" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -637,10 +833,16 @@
        <family>Courier</family>
       </font>
      </property>
+     <property name="text">
+      <string>xx.xx</string>
+     </property>
+     <property name="readOnly">
+      <bool>true</bool>
+     </property>
     </widget>
    </item>
-   <item row="7" column="3">
-    <widget class="QPushButton" name="default_setpoint_button">
+   <item row="4" column="4">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -653,13 +855,37 @@
        <height>60</height>
       </size>
      </property>
+     <property name="font">
+      <font>
+       <family>Courier</family>
+      </font>
+     </property>
      <property name="text">
-      <string>Default</string>
+      <string>xx.xx</string>
+     </property>
+     <property name="readOnly">
+      <bool>true</bool>
      </property>
     </widget>
    </item>
-   <item row="7" column="4">
-    <widget class="QPushButton" name="set_setpoint_button">
+   <item row="4" column="2">
+    <widget class="QLabel" name="label_row_z">
+     <property name="maximumSize">
+      <size>
+       <width>16777215</width>
+       <height>60</height>
+      </size>
+     </property>
+     <property name="text">
+      <string>z [m]</string>
+     </property>
+     <property name="alignment">
+      <set>Qt::AlignCenter</set>
+     </property>
+    </widget>
+   </item>
+   <item row="3" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_y">
      <property name="sizePolicy">
       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
        <horstretch>0</horstretch>
@@ -672,347 +898,178 @@
        <height>60</height>
       </size>
      </property>
-     <property name="text">
-      <string>Set New</string>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="2">
-    <widget class="QLabel" name="label_error_title">
      <property name="font">
       <font>
-       <weight>75</weight>
-       <bold>true</bold>
+       <family>Courier</family>
       </font>
      </property>
      <property name="text">
-      <string>Error</string>
+      <string>xx.xx</string>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="readOnly">
+      <bool>true</bool>
      </property>
     </widget>
    </item>
-   <item row="1" column="2">
-    <widget class="QLabel" name="label_error_title_line2">
-     <property name="text">
-      <string>meas-ref</string>
+   <item row="5" column="1">
+    <widget class="QLineEdit" name="lineEdit_measured_yaw">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
      </property>
-    </widget>
-   </item>
-   <item row="0" column="3">
-    <widget class="QLabel" name="label_current_title">
      <property name="font">
       <font>
-       <weight>75</weight>
-       <bold>true</bold>
+       <family>Courier</family>
       </font>
      </property>
      <property name="text">
-      <string>Current</string>
+      <string>xx.xx</string>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="readOnly">
+      <bool>true</bool>
      </property>
     </widget>
    </item>
-   <item row="1" column="3">
-    <widget class="QLabel" name="label_current_title_2">
-     <property name="text">
-      <string>Setpoint</string>
+   <item row="2" column="4">
+    <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="maximumSize">
+      <size>
+       <width>180</width>
+       <height>60</height>
+      </size>
      </property>
-    </widget>
-   </item>
-   <item row="0" column="4">
-    <widget class="QLabel" name="label_new_title">
      <property name="font">
       <font>
-       <weight>75</weight>
-       <bold>true</bold>
+       <family>Courier</family>
       </font>
      </property>
      <property name="text">
-      <string>New</string>
+      <string>xx.xx</string>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="readOnly">
+      <bool>true</bool>
      </property>
     </widget>
    </item>
-   <item row="1" column="4">
-    <widget class="QLabel" name="label_new_title_line2">
+   <item row="0" column="7">
+    <widget class="QLabel" name="label_2">
+     <property name="font">
+      <font>
+       <weight>75</weight>
+       <bold>true</bold>
+      </font>
+     </property>
      <property name="text">
-      <string>Setpoint</string>
+      <string>Increment</string>
      </property>
      <property name="alignment">
       <set>Qt::AlignCenter</set>
      </property>
     </widget>
    </item>
-   <item row="2" column="5">
-    <spacer name="horizontalSpacer_2">
-     <property name="orientation">
-      <enum>Qt::Horizontal</enum>
-     </property>
-     <property name="sizeType">
-      <enum>QSizePolicy::Fixed</enum>
+   <item row="4" column="3">
+    <widget class="QLineEdit" name="lineEdit_error_z">
+     <property name="sizePolicy">
+      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+       <horstretch>0</horstretch>
+       <verstretch>0</verstretch>
+      </sizepolicy>
      </property>
-     <property name="sizeHint" stdset="0">
+     <property name="maximumSize">
       <size>
-       <width>20</width>
-       <height>20</height>
+       <width>180</width>
+       <height>60</height>
       </size>
      </property>
-    </spacer>
-   </item>
-   <item row="0" column="6">
-    <widget class="QLabel" name="label_2">
      <property name="font">
       <font>
-       <weight>75</weight>
-       <bold>true</bold>
+       <family>Courier</family>
       </font>
      </property>
      <property name="text">
-      <string>Increment</string>
+      <string>xx.xx</string>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="readOnly">
+      <bool>true</bool>
      </property>
     </widget>
    </item>
-   <item row="2" column="6">
-    <layout class="QHBoxLayout" name="horizontalLayout">
-     <item>
-      <widget class="QPushButton" name="x_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>-</string>
-       </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>140</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QPushButton" name="x_increment_plus_button">
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>+</string>
-       </property>
-      </widget>
-     </item>
-    </layout>
-   </item>
-   <item row="3" column="6">
-    <layout class="QHBoxLayout" name="horizontalLayout_2">
-     <item>
-      <widget class="QPushButton" name="y_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>-</string>
-       </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>140</width>
-         <height>60</height>
-        </size>
-       </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QPushButton" name="y_increment_plus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>+</string>
-       </property>
-      </widget>
-     </item>
-    </layout>
-   </item>
-   <item row="4" column="6">
-    <layout class="QHBoxLayout" name="horizontalLayout_3">
+   <item row="1" column="1">
+    <layout class="QHBoxLayout" name="horizontalLayout_5">
+     <property name="spacing">
+      <number>0</number>
+     </property>
+     <property name="leftMargin">
+      <number>0</number>
+     </property>
+     <property name="topMargin">
+      <number>0</number>
+     </property>
+     <property name="rightMargin">
+      <number>0</number>
+     </property>
+     <property name="bottomMargin">
+      <number>0</number>
+     </property>
      <item>
-      <widget class="QPushButton" name="z_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
+      <widget class="QFrame" name="red_frame_position_left">
        <property name="maximumSize">
         <size>
-         <width>60</width>
-         <height>60</height>
+         <width>10</width>
+         <height>16777215</height>
         </size>
        </property>
-       <property name="text">
-        <string>-</string>
+       <property name="styleSheet">
+        <string notr="true">background-color:red;</string>
        </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
+       <property name="frameShape">
+        <enum>QFrame::StyledPanel</enum>
        </property>
-       <property name="maximumSize">
-        <size>
-         <width>140</width>
-         <height>60</height>
-        </size>
+       <property name="frameShadow">
+        <enum>QFrame::Raised</enum>
        </property>
       </widget>
      </item>
      <item>
-      <widget class="QPushButton" name="z_increment_plus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
+      <widget class="QLabel" name="label_measured_title_line2">
        <property name="text">
-        <string>+</string>
+        <string>Position</string>
        </property>
-      </widget>
-     </item>
-    </layout>
-   </item>
-   <item row="5" column="6">
-    <layout class="QHBoxLayout" name="horizontalLayout_4">
-     <item>
-      <widget class="QPushButton" name="yaw_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="text">
-        <string>-</string>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
      <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
+      <widget class="QFrame" name="red_frame_position_right">
        <property name="maximumSize">
         <size>
-         <width>140</width>
-         <height>60</height>
+         <width>10</width>
+         <height>16777215</height>
         </size>
        </property>
-      </widget>
-     </item>
-     <item>
-      <widget class="QPushButton" name="yaw_increment_plus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
+       <property name="styleSheet">
+        <string notr="true">background-color:red;</string>
        </property>
-       <property name="maximumSize">
-        <size>
-         <width>60</width>
-         <height>60</height>
-        </size>
+       <property name="frameShape">
+        <enum>QFrame::StyledPanel</enum>
        </property>
-       <property name="text">
-        <string>+</string>
+       <property name="frameShadow">
+        <enum>QFrame::Raised</enum>
        </property>
       </widget>
      </item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
new file mode 100644
index 0000000000000000000000000000000000000000..71765cfe18b1d7a915b7f92daf06df3b6558521f
GIT binary patch
literal 2775
zcmb7FXE+-Q7fuwlqDD|VG+H$)YTT;5Vy|jyRclmHE2yeHBh*$!8zWqM)T&i6LaZxV
zT6%4&M6@XRVg;Z3<NN>JAMZKmeV%jvobevCrMV%9MSukW0Dz3(de#@-=mLREj2HGx
zmOLK-K+o@~t83}4YpCn@%nxbf|Jc>t(B0P^>FH{1r~?3~rl#6DJr%MAYjg#AT!RvA
zp50Ces?-EYfU@u3E@|nET3Ar_%{5Y<6(_k-w~2WpL{-JE(-I4P%WwtqTkt?nTQo%S
zKUd~7TI64|NX&kLNNThk##xe5%D3{>6!Seh8yDTT!}l>eg<;zr9y<)Aj_L=wnP4Dq
zLA@*=Y&8&-o}@0F5sxb7V=O^f2}?UwnbIj+u!gicEa~=#Isg52;jE~x%|Mt35+Lf*
zyk5zgln&gjupN62e0iKHs!6sNp}LUT6to89U$(Ef&fo(zB2zt|tjVlSB{A6AcqP5z
zNdIf_(17hk;r+C8v6<IaHR%V|<!$gnaijmv<Fg{4zNZQMKKP1>{34C`oyU$R(n=B=
zD^>$0)mcRbG^SN=pNJ1a%X7JJGdVRGGv*fy8p=6$^c-vFE?47<%IaE^#UeN2mG@;<
zWs@dUHb!mwzSUG`55DVrKG3FQzqhAG-;3^aDEK{uJn^w9+}rp;Rw@_^3)Q0?e+-3F
zBalUZ{MrmB?Z@ZJUZ(x|CMS+(ATBAY#6X+6v3k}xZ_IIt-%H?!QIuR(DZ7LGcPF26
z(u4^cpUM|e6W*=k80+G5z2+2Tbb}pZjn%7Ei&@zY^45{nAdxS;C_F*ACMF68YG!7T
z%)5o^W-)tkiPKF|i*bqf+taEzc19Su4$PnIT=IlZaHIF`-kp~G@jhIC&e`y=bKFro
zu|>)ar4h^9BtT26<(+c>U6bJG%B>kGqe7>7ogc#WcihB7m=QHI00tBfO}=YJ%@%6n
zcH24rX8cV5;a!#K(~qwdt;^r)FZ|KcRs85&QOeZOW~Nq#{X^olv709hPTe$ubED&?
zjEdEVRenq-f_UV7v_*qarD<Me%Ta5H-)+bt`@g!HOz}UTJqQf374TvF&b#|Le-J$=
zydUs;4ROUFGIu0@qk-ad*UnFl-Jtdj!?D-VeSY&)y;@2f1=S+ceIr8hl+ZmMF&Z%*
zL5%2gqRUhp!+giB$oY!~Iuoc~`vUe$VZ5PN+dMXNy=#rdu07)s;YIc<uUI{X?cHEw
za@Dc=7L!}Ib;4UDU#Kq3?kc)oapH)RyAMR4G}2Mb&TMV(ZTjcj6u$3gri#<%eg)Na
zdzGVn@1PyAUn2h6;)k^-hmD#IcU9vT?JKC}^5?}qbSE_7uT{QH*5pao#RxjPsXM+~
zpmClMlgVrsfd*x%+yXKwsq$*#uxZ*;8`P|iy&%KRA|;*j7S?rz+d<Co-3ePSPV@KA
z6S>v27C^30bj;8-->Va&mlqjS_v2@q=K6#);o+>yUk-j!dyZi*B2T|;&JP6EZpcQr
zs;FUlmUe=sHMGua03NAPz~Z8C+e?nDI~Q8P><_mK1OWKB{sGXVX!1fz7~PEYwC}wD
z{=zuHWo^Mj8$vxcHY3(xD?cbU$y1$4Vjw{$8Cw_|D?;u=6}RnXo9?EBZBFW19F$a$
zV%6ybM8!!G?ZyR31?o(R5`6UnDw^CqCk=RvC$Tmn%>?6GsOXLNr#=iDFX)bJelqd%
zNL4KeiFA<=4-N`i<KyLJ@1=T|SdupNo?Y@ezx+HZ@l+6l!7SZy5p+|`VS=BYo?5uO
zyQkvMTJ@CXT@Tg{58F$-x=zXsw@nm&rtqY50y;sT-GSITRR7BE?(*{Teqs5cwduiN
z@)#4g@|L3Fey|W-T1#c+@aV)u$Y`Y7^N^6b)>fsqs@r8Dki$V)%C#LeD8LH<xuGL1
zB_(6emC1D0-yb^{RNA$SSPUS@#~B(Ldipv@NJwmB8;(|2U8L33y)+GZXtQ}c86QFW
zsw;Ike}2@r1fO?LAS)T>-deCPMFNGSq!dojj6YQ}LAOFD!T0o>bjXdz<Nb_3q?;58
zJ1W!A+m9O?8g_0i-XUy3qnSP2+&-e%4<lsc`+K7*s$WdA1<T6H@&W|CXq;wdW_Dp=
zVSEZyzDKDp9bf0>x}L%YARrJ(owWiNkIeQ=XdcZ1Wc`{H!EUWnD3prQ(o(|@8Ih&W
z6%wSxH$>KO0HmKJ^Pb&qcUx7}rd(Rt(88}^Nb0LsA7hjKiVyP~`Y?u=;OW8cNbx-n
zpY%G>8re!eeA3Dsl}crExG@=Ug^lfADPA~%ZfkgKbX2BudW1+!12iE%O7)D7k8gOf
z97DXly~jGE&T*|c+;(d~cXc&ckx3Jq42Q1Rf9Ks}fWGIhe^-~7$jCZ+-`t$|n%=GL
zKX-eAU^gWt-;>GYS~A%yJ4zHAmG(2{w%%}H5+rsF$})0%{Bmi?fyh|@Ad&ETZJ$6$
zoPy<SzIwPgJNptPzUfr4Zk0%|4-E}{7-0NnY;4R-`?J9entro$=48^k)0gc&w)gij
zh`*CenZ8vIl3Gyx)Ess>b(@?++*n_Soqr0kP1LUW<P^w%$>4xmZ@qXMrp3WyK=ega
zl^_~rS&ZHzz*#z692}KTq0ErRMuAjM0)aqZQ(njd8Z<>~W2YbskFL0gFCh?!{4F-F
zRI0a^SDp(8efxEo&ZLIX`vac;mEVK{ficMj|BeE<x*|;EJ>}#CmKwl$CcZpVuD*Lo
z+Wpd9)1#xt$gnWtbV^a~r?_YWAwC=%KrDA&^rEQxAdy)<8Twoaj+RR@=-_tGq4Cv3
zRxp=GKa>S6wnCRMkbeuU;{tEj5(~I)ip{vnC1(kL$DAz*O^pA4)4pMhI)}QOoAFAQ
zASDOwW*5DvkWf@qyuOh01}#dz{MM$X2}Vwt%0aoR!IxI#WM%)>-*}_X^|?&`ZCoD7
zUr~E9&4B~NVkE}Q#B}d=7C0+9T1)@hzoP*30`5;cp(h?54F8N|VM#@zl(M|sTPFB`
zKTa=-(b2&{5DuY09)-WVzKu4Yy`jH<D;J!_Y0_dT_D^`VtT?j7t!y7Y3>kbWA~FH5
zo>71|;*N}iIeybzGgfb2ZZ#KUrrwPMZ|Pr;smrl_oDl@?KTwJru)T-PpjRl)fM$HM
z(hS;S=&*ocT6RT#=oVyszoG&ykQyrcIc@Znc6NpvX_dG$AL&2yDQtdjZqC;VvIo9;
zv8fN84*=U0x6X>bOZ$z}Xdm^@=Qzt+IyyEn;d%2tDMyks_`Hc@ge7ej6c4z#F*_70
zV526eA*&@c8A7KQvtphh>T(qCmO0nPRF$r99L0Y+mHk0H;*NrX0_Tx*ctM9M&t+Ut
z7FJh=;4HR4B9o6(U#M~iy5L6m0Go!xP0uW~Pxa{|P`#n7DEqRBfck8$Un1-c2;llo
zalcp(@F_TY@dGgPFEmujvY(bcv3xY;<K~P-Mo;n{ui^>|3nze5<Uk3=k;GX14rooY
ycQO(G>FyS~?%jM(&n2QT#lji#QY6pui0|Q8_5%j(%DIat1TfM!*Q?ig6#HL6J3{;b

literal 0
HcmV?d00001

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavilable.png b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavilable.png
new file mode 100644
index 0000000000000000000000000000000000000000..60f6878b603abc0ba5dd375765ff06ad36a397ab
GIT binary patch
literal 4797
zcmV;u5<=~XP)<h;3K|Lk000e1NJLTq004&o003(U1^@s6U15>)000CTX+uL$YePpv
zZ)|UJQ*dEpWk+RhWpZg_Qb$4n062|}Rb6NtRTMtEb7vzY&QokOg><Mt4J8eeRy3is
zx_{l>Hg1+lHrgWSWcKdPn90sKGrRqvPeo9CG3uKX#J{(IASm?@+di}}l?o-=)F3E6
zwD^Ni=!>T7nL9I?X}YoAW$t|Qo$sD|?zw001?ah|SeB6#0T!CBEf+H4bBB+JJu8re
zhoBb*p;u8ID_yBf0ya+zcePvJL&AGs+11_tpRKn>9TgyPA7ZoSs0)aX0r00)%XR^J
z`jH<$>RKN5V(7OqK*TS4xZz{h!*f1<jcI1&EaKCM1yxgOh?fwL%*FUd4Er&#)?c7a
zYU`@#<)UJnb={z`aPMLMpKZZth4XF0r_Y(6K7{XKT>C3ECFkK$#7nA@pGN!$;%jYv
zwjAKwmYb0gKL(K8-kPtb5${A?tlI~wzMrJ6wTdBr=Y%%%EaEMQ&o}4FQ^DA)s*}Z>
z!FI&AHCpoWI|RUqx?7s@$8!5^Q=anY<?1z>%X@i5{QA6kNcMelpE>R6eCYFpmMsVT
zrI(b06~u#xf1yS}_UGdMvD``!0~u-><w<`olA{h=FXLTprs&U03>P=lA4?YN`hilQ
z|3tHka)7T{2CGqwjZfMwx$5irQN_*|e4l)UHmiYuz74Yp1t^#>hrJ3-SOXDcC_o0^
z7T9R1gAN8V6s;5)ieI5-7aQlmJn}lUna#nz!j%5V$X|o`xX!dHWQRV27P1=rj;t2b
zW$~+pTw@bIek?ZvKPDL<64`^#UNTAck#RBsB6*5DP4<%<vJ+(Q`q)ZrMP58N*8RMU
zGg79TMcp~HyP#nIGb&76Q`f944z`9P%PIQ>UA_FqU$I>2EH_cM;u)Q~SI+rg`Rn{L
z_AC5qq~L$#SMj%U$6Cz0vP{G5Y*=%5RT^yu;}-DInZ=349rJPV<W~<yewN9Z=dbi#
zJXvop4o0k(1^R0FRvAu>M6C3K^oO)8y(fJr{l>k`ead~!ea?NsT>_Ci%bnxC;Vy6=
zb6>{xYV#Ue-+LB$7`JEXmTRm^AtP)R9u{)KHsMiWGV&)32xCG~*nyU<>-!d;FP=Re
z4r3qYr~6#KE>;1F`>_J_P5xC?ROxV(DIHdCO*p<m6O1H7WQ>$HRQI@7^PwV@Pvuf+
z5K}u-6REM(K@W$srgorh0{i?O)v0c>QtHxU-hBdD(>iYJ4b2sIOVX2K8m~4gmYVA5
zh^QEb$V`rCQ-|7ZS{nuL-t>?3n=-o(6I(7vocj#GzCZEo`!3>+v;dYIfPu#&ZWzzX
z2i^rZ^Mu;6+rb@?NPG+6)c5T6zxpzGe*M(x+{AON=PiJ>H#?ob-|uwRK0yDg0B4PV
z0id6JRRdfL?*IS*32;bRa{vGr5&!@f5&>tQ(oz5b4oXQxK~#7F?VZ<;6w4KdYnPmJ
zT5`@oG9VBl2<Z}ZC2aZOKG=_z{{b8>tU!Qd1d=5zKUjW5mMmLBen9)=EBs(&mbkD>
z&amX1b9Q}gYTVOPox}9ZR7pKuUEN(>b?P^#&N+3es_x5|FG3f#Y}qojbLY-KllOii
zj|p{kbwlO3PWP-yt1Jr0Hh(1Bvt6El`1I-1UpH*na8_4?Iwv^Ru3g)0;J|_3*Voto
zR=&_p_mWAgDhj|I{_^?r=XH&ZjrZ&|D*}h)77bmxbZL?g{K)>0iB~@bB$K!!xyg^$
zty_0Q)wTeRufRAUZ;Vnm&AH|%@J52<oAvA0H&b&99CRgv2M_*_ye{Dw0|pEbGiS~e
z{rmS99XoccIcim7g<rjTC9Yk&CeEBWBV>0{R7DAn2k+m%pTB9-rgp2fkuh|@Sg>G$
zSiE?#=+L1<Q3mFsm;z6qKDB5hyJXR+Qzs$WbMXT?yy6c(ckW!#)YK#%KYm;&p)C6#
zsfheZCVX4BdGqF>vQk&%MUn8iYSk(+XU?3$OD0lE0fhO}r%#La_V&U}fFX%10Lp|3
z6GTHpL*ZT?Bk$h56FYbA6ad^2zN!DJt`-4f(xgcS7!FD~FQp17T3T9)fWb2W27<%7
zB}aC?mb+^}yk^as5^g8!@r!y{TI?7_Vd>JPMc3w{m;yBZfddD`y?aHPU(rLOM~}8R
zNKs-=FW_#ICr@^kZcV*pgX8U~J$m#I2%#qEDe&^;OVQlitYgE47o?3yj2kzua9s(J
zQKO2LREdl32&BX8h40?IyZzF{Z4^LoJ96ZR`0(L_EwwZ{a^y(SwQJYX8#zwVwL9R*
zzi6EUqTarJTeP*cm8gEsq9KqXh*m?eRM~2%NSbxHeEG6CdsaLAQ1aOkBSwgB-HPP<
zl4mL<!GOb~rF5#Q$K%$m@#Bj`IKRg|?|=OGQ5-vV%+h`^KyqM5>DRBHK;TU~7;v~y
z7*&;q@zO|~uOjvL?Ag<q9O;_xBi}rF^r+<h-o1O5q@|Hyz@eckswxemF$`&*{(n+Z
zvIZQhwY60X48AsWDBct42LlcVjZsw(A3iKzzkcnw<9#_~$PkglKN?^hKYm=?y?a;t
zLB65WEVK{DOf=xI5iqE#YI~&+oj7q~As#2fVA#!@H(j&Hifd2+1CFoF5L8vwwHjvf
zzJ2@ZZiPy_c=4jRdiAR3I|dw{<VpT!7*$pG^(43kgLmi8pVwtyNTWMRqU$PT=o6`F
z&Jjgbb<z_*m$<_XbR(xuopNSfa-AjD;Nvw5jwq^XNo&c3xEczoG6HCjV89WCN->{_
zs;W9a+ow+-AwB4v$$_u2VH`br)EegZdx@cSj9*!Xn&TW%RaIT1#Nis)P_U&q-Sl+d
zAq`cTahohdO@Skhs_JYMETK`^JODj(=#aoX9yCP#R?z%)&*csr{F9`EtHo;hr>KL%
ztACC<+tXC#boWS$qpGUB?PoL;`?u`(yy6(w4jw${JM3@IgE5tIc$MV_98aD+u~a$w
zVYG<6hX)TH2+E9O4+l=zesREr@cH)b+fda*t|9NNL)pQB)_@v!<Hn7w>mKWSURKOl
z8EamC@#2N$ugWdOtpE!S;ObiQTI{5<f&(X9Mn0cCdltJQ)tmv~;IIcYr8I%Tw=xF@
zG6ntr_3PJ*=1bTsZsP6~VA=!1X%;@JnSujQ;8FGF%^UaHn>!^GVBBWVph1>Rg?QQ=
zLlqzsa3ElwJbBXM7V5+1>`npP4AD*i1ZTKKIYK7jpueOWF+ooO8XpiaM#GuuA$bUy
zfCGb3uU@@MgsMCcpd4ku6b=y7pdGZyW5@&?s9g&eF0^#~Fg}@iBv_O((fEvuZ~%zB
za0b7+WC9Kf0qdMMZ=QJm{JAy#|Ni~^RVSDtC@P-|R80;9NIb?XF=Pe~MI4+}nEp>-
zY=IF{)LVpBWf`@{c}}GhCpfSFmm2<8C-wWK+3yoq2NqJgi*i^p!`D368<~T{UMw{i
z!=7g1`Jq7e2K)Tf-IT<K0<k#<lZqKEgPq24eDNu#xm^YdL;?q6A$RWF5f2|eEKK|v
zJ9exAM;RJ0%}<5~2f`zheh?&0sBQ{`mN^(&H^8WFP^j940tYH2b39C_91758m<;?D
zoYB=NRJVeh5q1u#?xQ9x8456;_R^(G*02NsKq<i1!f*wkz=;`eHADdd20DiNr%s(}
zJ?B@7P~e~-ZXqedlw1BLy_5p`_U#Mha>ySWue)>S&WUN$rdc5Ivfc*nRxo#C`Zggy
z6o@*M50^P{;)K|}d$+ZUF|L}r5EvX@Ttk<!NlTvsn&lxweH6t4H%&ldU&UBu5(pf;
zsC!vuV$S8E0MjFqn9qV|9<qru1OkWQ8cwq1;~D{U$&w|BEdQXZkuNxqGmtm@f)Pml
zD3s29<c<|9RtQ!xOgi|2!`L;FCVBGt0gz?OmWf4+7A3Y|9i{XH2ddAlTem{j1}?&2
z96JiQNy4EsH81#5fblIBxt~9Oej;n3dfGX{a1B6!QHBFoKxL6*T~4!Ki*LIo_5gAS
zyIx@Ix^UrwrK*OVeyIxM3J%nqFjEwn9_XARIBeLkK$bXF7;{dJ0yt7(=mIDx6mapd
z^Mzc&aplUDg4s1}kwGs78#881*jLT-2~z-&Oqnu8p!U)euv#HYKm-X|aL^^N2UwJV
zhcy#?E5*Y)N*ycl9lCb72n)`r{oQo74SU_R;K25di8V}sTYyl6BD)iAm^{q0=~IAq
zqK!BhNQIMd)`b#qz=pzd4d!CZo;}-e3mt`XoQ6!u!RReAi8GXd!});MH9%tcmtB4g
zxA3A=zV9)&Mz>sMWN?7E>C>lI+>S)~Zl-*dE;Klp0X}2K3~P0}d{xDiCTR);1_#{+
z1}#(~W7JBz8S<H5AaJlw1YJl{8_ndC6sA;83V4D8Fd%TUK&lC~M*%H3kSj2j7%ims
z0Aa6j2{<r*EnmLesHS!*)o8o~9MHkoETW--VFw1eutG9LfCFC(&TK-AU8s^mWtBF^
zlx4(|X`;^cLRFDx&6;I()9Shs&ITL_v=XkA0K?610<MvU8(#uN_sqh8!;?JzH(3Ln
zJyW~}DzOjI)l^zA;E2&;I72Zx$jiAJnFFn_5`zIp#8$%vkHatEu2-oRWdjbs)^*%x
zQZn4a=@RL9%(`SAY9)Ka8F1)Y)g=v875Rb{je-OmYLZl65qJS7d2*yJ#~5$~X=VA0
zpQ`H2hOQ(@u7QfYfB*i1S3lna91RT(mRqLt`$=3Ia0H;DpQ@_M0$?DFCK24W{(_6(
zg_l+^;P9br5LMNg1^?)z_Cuj7VNW=>rM8loNbM}Yx;EfYl+c`msH&RREY%g0dECH8
zi0mTiwwe-LBPs5rE2{yAjw&*ZedRA+yy$Y*Jy|(Lxjzx?4n{REb3D1E$u-E|fCDPn
zLKs!m_F5r|nH-mgIDs;>w6qk~cy-GQKi)Kh0f&vcVO3SztA%KsU8>0hYb&em_^Hcm
zFc24ng+jYT3^=|LCakKeqbF)*+?jqD*qDs&7t-b$eBXdW5+RDJs%t!)uj2$}p9P(~
zp0>O}J!&2tQB+kO0BEc@+i@ZMGI>2nfIG$cR*-M-OihC$s;a6ZZX8*oy}jMij&%9z
z(z4(he79!75mi;yH5OAhm{J%euyPU$$A$?t4-O1KNbFb!k>HhID`$IL5mlve?H6a|
zp(x8)sc$*YQDqIv(bm@H%+B)~<62Z8dS<M-nLEy*oOG{Vy&8G(7)?D>O~P1($((}$
zw;*u<%xVT+jzYRZGlxjMWB(KAo{gK9D{!DSVEl127sst^TJL+g2qyhaHg9%r;0zd7
zu3VY8Q&BF!LDzxv44zeH^}+CPV*9i-yv@oA4z>eBg`@9PtTH@lYV!>|+5rW^DO;SU
z5y}D%<O(G8B!$8>h?A#0={i_%4b6yy4UN+dnS+CFgMC6?y?T{)-6}qR#!pyr2QY9>
zqwDY@Qs&@5MK!?CHwl(cKtMOak*2SPz68aonS(>k;5R!l2+ITx7;xI*oP>i=ar4Hz
z0vvDTQE))WLR(--O8QK!ltC9vjaSX`zm2yz#w+9ob$D%|m34`A?G8Au%VV-C47LUy
zOuK($$eDvpe$ZC%uEt*ytp#Tn0&%6qsIyA99{BoWzh_Sm8h0}$>C#o2I`a(`=ga}^
z;E;3^$PFCC)pJ41mF07~1#3G>!nVjl7r=o*2lbMFcNPJb>gPdC7X*mdwkiuLUDcb#
zTQN9|9zELn*Rxh9te>U3(H^QL@Mk=G_H0pgBrYz%IsPV(pWE;3*|W!Tl4YyOatExX
ztf;I4+eKs*aJ)h7hMNu_KD@BfFWN&jErrE=7`8yM2MLb9*SEH|{vZ>N+i##vG&ME3
zE-7GtHtjh7R0UE$4wH0Q)c5S%4LN~sqFMrfyyoWSqUuOsunp*+>tsZ1-MV#&>?i*%
z6YA_w;ZU-A^=fOK>~i*($UvCb6-ex5OfwE`;9Pu{`Xdt|Pvl9Ej9P!{wRi7car}4@
zU$C;1_5RiR_3L+7;2>rD_U+$uvhF&5SXHnbMi@si%w<9p02ppV77`f$Xl!i!PM*IM
zz`=L7ZQJ&H`49PZLS-=7R2T&$9{wraCV#qP#}3RJq6i!$NPzrO0^|=e+JkEos-FT9
z6rW|A|4~kf_|2|ey9(P=mw*FONEu|f>|1{)U;0kIRDPAE`rD^mHT)#oc#kw+G;Z9u
zvDH}!EjZLeTefWJDee0!WCr7<UeENZ>QU}hC2Q;~+wzO7@*{a_mumXIHf`GEI!Wfg
Xor1sWxHYe500000NkvXXu0mjfcNGNh

literal 0
HcmV?d00001

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 6ee01b2e..7c1fde73 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -28,7 +28,7 @@
 
 #else
 // Include the shared definitions
-//#include "include/Constants_for_Qt_compile.h"
+#include "include/Constants_for_Qt_compile.h"
 
 #endif
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index f06c2875..107748a6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -391,7 +391,7 @@ void ConnectStartStopBar::setBatteryImageBasedOnLevel(int battery_level)
         case BATTERY_LEVEL_UNAVAILABLE:
         {
             new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE;
-            qstr_new_image.append("battery_unknown.png");
+            qstr_new_image.append("battery_unavailable.png");
             break;
         }
         default:
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index da14cfc0..0b1f05ce 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -451,7 +451,7 @@ void CoordinatorRow::setBatteryImageBasedOnLevel(int battery_level)
         case BATTERY_LEVEL_UNAVAILABLE:
         {
             new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE;
-            qstr_new_image.append("battery_unknown.png");
+            qstr_new_image.append("battery_unavailable.png");
             break;
         }
         default:
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 3b2c3896..cd3a84ee 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -7,6 +7,11 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
 {
     ui->setupUi(this);
 
+    // Hide the two red frames that are used to indcated
+    // when pose data is occluded
+    ui->red_frame_position_left->setVisible(false);
+    ui->red_frame_position_right->setVisible(false);
+
 
 
 #ifdef CATKIN_MAKE
@@ -87,11 +92,20 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
 
         if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+
+        // Ensure the red frames are not visible
+        if ( ui->red_frame_position_left->isVisible() )
+            ui->red_frame_position_left->setVisible(true);
+        if ( ui->red_frame_position_right->isVisible() )
+            ui->red_frame_position_right->setVisible(true);
     }
     else
     {
-        //ui->label_measured_title->setTextColor(Qt::green);
-        //ui->label_measured_title_line2
+        // Make visible the red frames to indicate occluded
+        if ( !(ui->red_frame_position_left->isVisible()) )
+            ui->red_frame_position_left->setVisible(true);
+        if ( !(ui->red_frame_position_right->isVisible()) )
+            ui->red_frame_position_right->setVisible(true);
     }
 }
 
@@ -534,4 +548,4 @@ bool DefaultControllerTab::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
-- 
GitLab


From a0441e9f87b0b32da78e55c401f09c7777af1b62 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 17 Dec 2018 21:21:47 +0100
Subject: [PATCH 23/87] GUI STUFF: The top banner and motion capture pose data
 is now connected to the properly to the coordinator

---
 .../flyingAgentGUI/include/controllertabs.h   |  15 ++
 .../include/defaultcontrollertab.h            |   1 +
 .../flyingAgentGUI/include/mainwindow.h       |   6 +
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h |  28 ++-
 .../flyingAgentGUI/src/controllertabs.cpp     | 115 +++++++++---
 .../src/defaultcontrollertab.cpp              |  39 +++-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  21 +++
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   | 171 +++++++++++++-----
 8 files changed, 313 insertions(+), 83 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 7ca9fbfc..7aad04c8 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -46,8 +46,14 @@ public:
     ~ControllerTabs();
 
 
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+    void setObjectNameForDisplayingPoseData( QString object_name );
+
+
 signals:
     void measuredPoseValueChanged(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSignal();
 
 
 private:
@@ -68,6 +74,15 @@ private:
     bool m_shouldCoordinateAll = true;
     QMutex m_agentIDs_toCoordinate_mutex;
 
+    // The object name for which motion capture pose data
+    // will be "emitted" using the "measuredPoseValueChanged"
+    // signal
+    std::string m_object_name_for_emitting_pose_data;
+
+    // Flag for whether pose data should be emitted, this is
+    // to save looking through the data when it is unnecessary
+    bool m_should_search_pose_data_for_object_name = false;
+
 
 #ifdef CATKIN_MAKE
     // --------------------------------------------------- //
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 7c1fde73..c8a3a4a9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -47,6 +47,7 @@ public:
 
 public slots:
     void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSlot();
 
 
 private slots:
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index baeea54b..5721fffd 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -89,6 +89,12 @@ private:
     // > For the ID of this node
     int m_ID = 0;
 
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+    
+
 #ifdef CATKIN_MAKE
     rosNodeThread* m_rosNodeThread;
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index 6853169f..e5e76eea 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -37,6 +37,8 @@
 #define TOPBANNER_H
 
 #include <QWidget>
+#include <QMutex>
+#include <QTimer>
 
 #ifdef CATKIN_MAKE
 #include <ros/ros.h>
@@ -74,6 +76,15 @@ public:
     explicit TopBanner(QWidget *parent = 0);
     ~TopBanner();
 
+
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+
+
+signals:
+    void objectNameForDisplayingPoseDataValueChanged( QString object_name );
+
+
 private:
 	// --------------------------------------------------- //
     // PRIVATE VARIABLES
@@ -86,9 +97,18 @@ private:
 	// > For the ID of this node
 	int m_ID = 0;
 
+	// For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
 	// The namespace into which node operates
 	std::string m_base_namespace;
 
+	// The object name for which motion capture pose data
+    // will be "emitted" using the "measuredPoseValueChanged"
+    // signal
+    QString m_object_name_for_emitting_pose_data;
 
 
 	// --------------------------------------------------- //
@@ -96,7 +116,9 @@ private:
 
     // > For loading the "context" for this agent,
     //   i.e., the {agentID,cfID,flying zone} tuple
-    void loadCrazyflieContext();
+    void loadCrazyflieContext(int ID_to_request_from_database , int emit_after_milliseconds);
+
+    
 
 
 
@@ -132,6 +154,10 @@ private slots:
     // > For the emergency stop button
     void on_emergency_stop_button_clicked();
 
+    // > For emitting a signal with the object name after
+    //   some small delay
+    void emitObjectNameForDisplayingPoseDataValueChanged();
+
 };
 
 #endif // TOPBANNER_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 5d5318c9..aafb53da 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -8,6 +8,9 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     ui->setupUi(this);
 
 
+    // Initialise the object name as blank
+    m_object_name_for_emitting_pose_data = "";
+
 
     // CONNECT THE "MEASURED POST" SIGNAL TO EACH OF
     // THE TABS
@@ -24,6 +27,16 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
         );
 
 
+    // CONNECT THE "MEASUREMENTS UNAVAILABLE" SIGNAL TO
+    // EACH OF THE TABS
+    QObject::connect(
+            this , &ControllerTabs::poseDataUnavailableSignal ,
+            ui->default_controller_tab_widget , &DefaultControllerTab::poseDataUnavailableSlot
+        );
+
+    
+
+
 
 #ifdef CATKIN_MAKE
 
@@ -64,45 +77,95 @@ ControllerTabs::~ControllerTabs()
 
 
 
+
+void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
+{
+    if (object_name.isEmpty())
+    {
+        // Set the class variable accordingly
+        m_object_name_for_emitting_pose_data = "";
+        // Update the flag accordingly
+        m_should_search_pose_data_for_object_name = false;
+        // Emit a signal to let the tabs know
+        emit poseDataUnavailableSignal();
+        // Inform the user
+        ROS_INFO("[CONTROLLER TABS GUI] No longer emitting pose data for any object.");
+    }
+    else
+    {
+        // Set the class variable accordingly
+        m_object_name_for_emitting_pose_data = object_name.toStdString();
+        // Update the flag accordingly
+        m_should_search_pose_data_for_object_name = true;
+        // Inform the user
+        #ifdef CATKIN_MAKE
+            ROS_INFO_STREAM("[CONTROLLER TABS GUI] now emitting data for object named: " << m_object_name_for_emitting_pose_data );
+        #endif
+    }
+}
+
+
 #ifdef CATKIN_MAKE
 // > For the controller currently operating, received on
 //   "controllerUsedSubscriber"
 void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& viconData)
 {
-    for(std::vector<d_fall_pps::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
+    if (m_should_search_pose_data_for_object_name)
     {
-        d_fall_pps::CrazyflieData pose_in_global_frame = *it;
-
-        if(pose_in_global_frame.crazyflieName == "CF05")
+        for(std::vector<d_fall_pps::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
         {
-            emit measuredPoseValueChanged(
-                    pose_in_global_frame.x,
-                    pose_in_global_frame.y,
-                    pose_in_global_frame.z,
-                    pose_in_global_frame.roll,
-                    pose_in_global_frame.pitch,
-                    pose_in_global_frame.yaw,
-                    pose_in_global_frame.occluded
-                );
+            d_fall_pps::CrazyflieData pose_in_global_frame = *it;
+
+            if(pose_in_global_frame.crazyflieName == m_object_name_for_emitting_pose_data)
+            {
+                emit measuredPoseValueChanged(
+                        pose_in_global_frame.x,
+                        pose_in_global_frame.y,
+                        pose_in_global_frame.z,
+                        pose_in_global_frame.roll,
+                        pose_in_global_frame.pitch,
+                        pose_in_global_frame.yaw,
+                        pose_in_global_frame.occluded
+                    );
+            }
         }
     }
+}
+#endif
+
 
 
-    // OLD STYLE    
-    // // Initialise a Qvector to sending around
-    // QVector<float> poseDataForSignal;
-    // // Fill in the data
-    // poseDataForSignal.push_back(msg.x);
-    // poseDataForSignal.push_back(msg.y);
-    // poseDataForSignal.push_back(msg.z);
-    // poseDataForSignal.push_back(msg.roll);
-    // poseDataForSignal.push_back(msg.pitch);
-    // poseDataForSignal.push_back(msg.yaw);
-    // // Emit the signal
-    // emit measuredPoseValueChanged(poseDataForSignal);
 
+
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void ControllerTabs::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
 }
-#endif
 
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index cd3a84ee..56aaf802 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -63,18 +63,18 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
         QString qstr = "";
         // UPDATE THE MEASUREMENT COLUMN
         if (x < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_x    ->setText(qstr + QString::number( x, 'f', 3));
+        ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', 3));
         if (y < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_y    ->setText(qstr + QString::number( y, 'f', 3));
+        ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', 3));
         if (z < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_z    ->setText(qstr + QString::number( z, 'f', 3));
+        ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
 
         if (roll < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_roll ->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
         if (pitch < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
         if (yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_yaw  ->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
 
         // GET THE CURRENT SETPOINT
         float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
@@ -84,20 +84,20 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
 
         // UPDATE THE ERROR COLUMN
         if (error_x < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_x  ->setText(qstr + QString::number( error_x, 'f', 3));
+        ui->lineEdit_error_x->setText(qstr + QString::number( error_x, 'f', 3));
         if (error_y < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_y  ->setText(qstr + QString::number( error_y, 'f', 3));
+        ui->lineEdit_error_y->setText(qstr + QString::number( error_y, 'f', 3));
         if (error_z < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_z  ->setText(qstr + QString::number( error_z, 'f', 3));
+        ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', 3));
 
         if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
 
         // Ensure the red frames are not visible
         if ( ui->red_frame_position_left->isVisible() )
-            ui->red_frame_position_left->setVisible(true);
+            ui->red_frame_position_left->setVisible(false);
         if ( ui->red_frame_position_right->isVisible() )
-            ui->red_frame_position_right->setVisible(true);
+            ui->red_frame_position_right->setVisible(false);
     }
     else
     {
@@ -110,6 +110,25 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
 }
 
 
+void DefaultControllerTab::poseDataUnavailableSlot()
+{
+    ui->lineEdit_measured_x->setText("xx.xx");
+    ui->lineEdit_measured_y->setText("xx.xx");
+    ui->lineEdit_measured_z->setText("xx.xx");
+
+    ui->lineEdit_measured_roll->setText("xx.xx");
+    ui->lineEdit_measured_pitch->setText("xx.xx");
+    ui->lineEdit_measured_yaw->setText("xx.xx");
+
+    ui->lineEdit_error_x->setText("xx.xx");
+    ui->lineEdit_error_y->setText("xx.xx");
+    ui->lineEdit_error_z->setText("xx.xx");
+    ui->lineEdit_error_yaw->setText("xx.xx");
+
+
+}
+
+
 
 void DefaultControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 2350a5c6..cfd33ca8 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -107,6 +107,27 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
             ui->customWidget_enableControllerLoadYamlBar , &EnableControllerLoadYamlBar::setAgentIDsToCoordinate
             );
 
+    QObject::connect(
+            ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
+            ui->customWidget_topBanner , &TopBanner::setAgentIDsToCoordinate
+            );
+
+    QObject::connect(
+            ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
+            ui->customWidget_controller_tabs , &ControllerTabs::setAgentIDsToCoordinate
+            );
+
+    // CONNECT SIGNAL/SLOT FOR PASSING THE OBJECT NAME FOR WHICH
+    // POSE DATA SHOULD BE DISPLAYED
+    // This is passed from the "top banner" to the "controller tabs"
+    // because the "top banner" is in charge of fetching the object
+    // name from the database, and the "controller tabs" are where
+    // the pose data is displayed
+    QObject::connect(
+            ui->customWidget_topBanner , &TopBanner::objectNameForDisplayingPoseDataValueChanged ,
+            ui->customWidget_controller_tabs , &ControllerTabs::setObjectNameForDisplayingPoseData
+            );
+
 }
 
 MainWindow::~MainWindow()
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 3b5cc3da..b0e31846 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -59,6 +59,9 @@ TopBanner::TopBanner(QWidget *parent) :
     //ui->emergency_stop_button->setIconSize(pixmap.rect().size());
 
 
+    m_object_name_for_emitting_pose_data = "";
+
+
 #ifdef CATKIN_MAKE
     // Get the namespace of this node
     std::string base_namespace = ros::this_node::getNamespace();
@@ -89,13 +92,9 @@ TopBanner::TopBanner(QWidget *parent) :
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
-    // SUBSCRIBER AND SERVICE:
-    if (m_type == TYPE_AGENT)
-    {
-    	// > For changes in the database that defines {agentID,cfID,flying zone} links
-    	databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
-    	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
-    }
+	// > For changes in the database that defines {agentID,cfID,flying zone} links
+	databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
+	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
 #endif
 
 
@@ -103,7 +102,7 @@ TopBanner::TopBanner(QWidget *parent) :
     // INITIALISATIONS ARE COMPLETE
     if (m_type == TYPE_AGENT)
     {
-    	loadCrazyflieContext();
+    	loadCrazyflieContext(m_ID,1000);
     }
     else if (m_type == TYPE_COORDINATOR)
     {
@@ -146,61 +145,86 @@ TopBanner::~TopBanner()
 void TopBanner::databaseChangedCallback(const std_msgs::Int32& msg)
 {
     //ROS_INFO_STEAM("[TOP BANNER GUI] Database Changed Callback called for agentID = " << m_agentID);
-    loadCrazyflieContext();
+    loadCrazyflieContext(m_ID,0);
 }
 #endif
 
+
+
+void TopBanner::emitObjectNameForDisplayingPoseDataValueChanged()
+{
+    emit objectNameForDisplayingPoseDataValueChanged( m_object_name_for_emitting_pose_data );
+    ROS_INFO_STREAM("[TOP BANNER GUI] Object name \"" << m_object_name_for_emitting_pose_data.toStdString() << "\" emitted for the controller tabs.");
+}
+
+
 // > For loading the "context" for this agent, i.e., the {agentID,cfID,flying zone} tuple
-void TopBanner::loadCrazyflieContext()
+void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_after_milliseconds)
 {
 
     QString qstr_crazyflie_name = "";
 
-	if (m_type == TYPE_AGENT)
+#ifdef CATKIN_MAKE
+	d_fall_pps::CMQuery contextCall;
+	contextCall.request.studentID = ID_to_request_from_database;
+	//ROS_INFO_STREAM("StudentID:" << m_agentID);
+
+	centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
+
+	if(centralManagerDatabaseService.call(contextCall))
 	{
+		my_context = contextCall.response.crazyflieContext;
+		ROS_INFO_STREAM("[TOP BANNER GUI] CrazyflieContext:\n" << my_context);
 
-#ifdef CATKIN_MAKE
-		d_fall_pps::CMQuery contextCall;
-		contextCall.request.studentID = m_ID;
-		//ROS_INFO_STREAM("StudentID:" << m_agentID);
-
-		centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
-
-		if(centralManagerDatabaseService.call(contextCall))
-		{
-			my_context = contextCall.response.crazyflieContext;
-			ROS_INFO_STREAM("[TOP BANNER GUI] CrazyflieContext:\n" << my_context);
-
-			qstr_crazyflie_name.append(QString::fromStdString(my_context.crazyflieName));
-		}
-		else
-		{
-			ROS_ERROR_STREAM("[TOP BANNER GUI] Failed to load context for agentID = " << m_ID);
-		}
-		// This updating of the radio only needs to be done by the actual agent's node
-		//ros::NodeHandle nh("CrazyRadio");
-		//nh.setParam("crazyFlieAddress", m_context.crazyflieAddress);
-#else
-		// Set the Crazyflie Name String to be a question mark
-		qstr_crazyflie_name.append("?");
-#endif
+		qstr_crazyflie_name.append(QString::fromStdString(my_context.crazyflieName));
 
-		// Construct and set the string for the checkbox label
-		QString qstr_title = "Flying Device GUI: for AGENT ID ";
-		qstr_title.append( QString::number(m_ID) );
-		qstr_title.append(", connected to ");
-		qstr_title.append(qstr_crazyflie_name);
-		ui->top_banner_label->setText(qstr_title);
+        m_object_name_for_emitting_pose_data = QString::fromStdString(my_context.crazyflieName);
 
+        // Emit the crazyflie name
+        // > This signal is connected to the "controller tabs" widget
+        //   and is used for filtering with motion capture data to
+        //   display in the tabs for each controller
+        if (emit_after_milliseconds == 0)
+        {
+            emit objectNameForDisplayingPoseDataValueChanged( QString::fromStdString(my_context.crazyflieName) );
+            ROS_INFO_STREAM("[TOP BANNER GUI] Object name \"" << my_context.crazyflieName << "\" emitted for the controller tabs.");
+        }
+        else
+        {
+            QTimer::singleShot(emit_after_milliseconds, this, SLOT( emitObjectNameForDisplayingPoseDataValueChanged() ) );
+        }
 	}
 	else
 	{
-#ifdef CATKIN_MAKE
-		ROS_ERROR("[TOP BANNER GUI] loadCrazyflieContext called by a node that is NOT of type AGENT.");
-#endif
-		qstr_crazyflie_name.append("??");
+		ROS_ERROR_STREAM("[TOP BANNER GUI] Failed to load context for agentID = " << m_ID);
+
+        m_object_name_for_emitting_pose_data = "";
+
+        if (emit_after_milliseconds == 0)
+        {
+            QString qstr = "";
+            emit objectNameForDisplayingPoseDataValueChanged( qstr );
+            ROS_INFO_STREAM("[TOP BANNER GUI] emitted for the controller tabs that no object name is available.");
+        }
+        else
+        {
+            QTimer::singleShot(emit_after_milliseconds, this, SLOT( emitObjectNameForDisplayingPoseDataValueChanged() ) );
+        }
 	}
+	// This updating of the radio only needs to be done by the actual agent's node
+	//ros::NodeHandle nh("CrazyRadio");
+	//nh.setParam("crazyFlieAddress", m_context.crazyflieAddress);
+#else
+	// Set the Crazyflie Name String to be a question mark
+	qstr_crazyflie_name.append("?");
+#endif
 
+	// Construct and set the string for the checkbox label
+	QString qstr_title = "Flying Device GUI: for AGENT ID ";
+	qstr_title.append( QString::number(m_ID) );
+	qstr_title.append(", connected to ");
+	qstr_title.append(qstr_crazyflie_name);
+	ui->top_banner_label->setText(qstr_title);
 }
 
 
@@ -231,6 +255,61 @@ void TopBanner::on_emergency_stop_button_clicked()
 
 
 
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void TopBanner::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+    // If there is only one agent to coordinate,
+    // then load the context for that agent
+    if (agentIDs.length() == 1)
+    {
+        loadCrazyflieContext(agentIDs[0],0);
+    }
+    else
+    {
+        // Set the label appropriate for a cooridnator
+        QString qstr_title = "Flying Device GUI: for COORDINATOR ID ";
+        qstr_title.append( QString::number(m_ID) );
+        ui->top_banner_label->setText(qstr_title);
+
+        // Update the class variable for the name
+        m_object_name_for_emitting_pose_data = "";
+        // Emit the empty name as a signal
+        QString qstr = "";
+        emit objectNameForDisplayingPoseDataValueChanged( qstr );
+    }
+}
+
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
 //     I   D   D     &           T     Y Y   P   P  E
-- 
GitLab


From 61dd59596e402b365207e2a521bc01b4ce45ad7f Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 17 Dec 2018 23:04:12 +0100
Subject: [PATCH 24/87] The coordinator row and (dis-)connect,  start-stop bar
 are now fully connected and fully generalised for operating as both an agent
 and a coordinator GUI

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   1 +
 .../GUI_Qt/flyingAgentGUI/flyingagentgui.qrc  |   2 +-
 ...lable.png => flying_state_unavailable.png} | Bin
 .../include/Constants_for_Qt_compile.h        |   9 +-
 .../include/connectstartstopbar.h             |   1 +
 .../flyingAgentGUI/include/coordinatorrow.h   |  17 ++++
 .../src/connectstartstopbar.cpp               |  86 +++++++++++++++++-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  60 +++++++++++-
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   |  19 ++++
 .../src/d_fall_pps/include/nodes/Constants.h  |   9 +-
 .../src/d_fall_pps/include/nodes/PPSClient.h  |   7 +-
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp |  23 +++++
 pps_ws/src/d_fall_pps/srv/IntIntService.srv   |   3 +
 13 files changed, 224 insertions(+), 13 deletions(-)
 rename pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/{flying_state_unavilable.png => flying_state_unavailable.png} (100%)
 create mode 100644 pps_ws/src/d_fall_pps/srv/IntIntService.srv

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index c77fe171..09af57d2 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -224,6 +224,7 @@ add_message_files(
 # )
 add_service_files(
   FILES
+  IntIntService.srv
   Controller.srv
   CMRead.srv
   CMQuery.srv
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
index ebe28271..fd7f30a5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
@@ -16,6 +16,6 @@
         <file>images/flying_state_flying.png</file>
         <file>images/flying_state_off.png</file>
         <file>images/flying_state_unknown.png</file>
-        <file>images/flying_state_unavilable.png</file>
+        <file>images/flying_state_unavailable.png</file>
     </qresource>
 </RCC>
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavilable.png b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavilable.png
rename to pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
index ac3ecb91..93f79577 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
@@ -79,10 +79,11 @@
 #define CMD_CRAZYFLY_MOTORS_OFF      13
 
 // Flying states
-#define STATE_MOTORS_OFF 1
-#define STATE_TAKE_OFF   2
-#define STATE_FLYING     3
-#define STATE_LAND       4
+#define STATE_MOTORS_OFF     1
+#define STATE_TAKE_OFF       2
+#define STATE_FLYING         3
+#define STATE_LAND           4
+#define STATE_UNAVAILABLE    5
 
 
 // Commands for CrazyRadio
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 4b8d2284..6bf867c8 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -53,6 +53,7 @@
 #include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/AreaBounds.h"
 #include "d_fall_pps/CrazyflieContext.h"
+#include "d_fall_pps/IntIntService.h"
 #include "d_fall_pps/CMQuery.h"
 
 // Include the shared definitions
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 6d0a3943..854b26d6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -52,6 +52,7 @@
 #include "d_fall_pps/AreaBounds.h"
 #include "d_fall_pps/CrazyflieContext.h"
 #include "d_fall_pps/CMQuery.h"
+#include "d_fall_pps/IntIntService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -155,6 +156,14 @@ private:
     //   i.e., the {agentID,cfID,flying zone} tuple
     void loadCrazyflieContext();
 
+    // > For requesting the current flying state
+    //   i.e., using the service advertised by the PPS client
+    void getCurrentFlyingState();
+
+    // > For requesting the current state of the Crazy Radio
+    //   i.e., using the service advertised by the PPS client
+    void getCurrentCrazyRadioState();
+
     // > For updating the text in the UI element of
     //   "controller_enabled_label"
     void setControllerEnabled(int new_controller);
@@ -192,6 +201,14 @@ private:
     // > For updating the controller that is currently operating
     ros::Subscriber controllerUsedSubscriber;
 
+    // > For requesting the current flying state,
+    //   this is used only for initialising the icon
+    ros::ServiceClient getCurrentFlyingStateService;
+
+    // > For requesting the current state of the Crazy Radio,
+    //   this is used only for initialising the icon
+    ros::ServiceClient getCurrentCrazyRadioStateService;
+
 
     // --------------------------------------------------- //
     // PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 107748a6..217d153c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
@@ -86,7 +86,7 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
     setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
 
     // SET THE STARTING FLYING STATE STATUS TO BE: MOTORS OFF
-    setFlyingState(CMD_CRAZYFLY_MOTORS_OFF);
+    setFlyingState(STATE_UNAVAILABLE);
 
     // ENSURE THE F:YING STATE BUTTONS ARE AVAILABLE FOR A COORDINATOR
     if (m_type == TYPE_COORDINATOR)
@@ -101,7 +101,7 @@ ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
     ros::NodeHandle base_nodeHandle(base_namespace);
 
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
-    ros::NodeHandle dfall_root_nodeHandle("/dfall");
+    //ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
     // SUBSCRIBERS AND PUBLISHERS:
 
@@ -481,6 +481,15 @@ void ConnectStartStopBar::setFlyingState(int new_flying_state)
             break;
         }
 
+        case STATE_UNAVAILABLE:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_disabling_pixmap(":/images/flying_state_unavailable.png");
+            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
         default:
         {
             // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
@@ -593,6 +602,79 @@ void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
     // Unlock the mutex
     m_agentIDs_toCoordinate_mutex.unlock();
 
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // > Request the current flying state
+        ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
+        d_fall_pps::IntIntService getFlyingStateCall;
+        getFlyingStateCall.request.data = 0;
+        getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
+        if(getCurrentFlyingStateService.call(getFlyingStateCall))
+        {
+            setFlyingState(getFlyingStateCall.response.data);
+        }
+        else
+        {
+            setFlyingState(STATE_UNAVAILABLE);
+        }
+
+        // > Request the current status of the crazy radio
+        ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
+        d_fall_pps::IntIntService getCrazyRadioCall;
+        getCrazyRadioCall.request.data = 0;
+        getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
+        if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
+        {
+            setCrazyRadioStatus(getCrazyRadioCall.response.data);
+        }
+        else
+        {
+            setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+        }
+
+        // > For updating the "rf_status_label" picture
+        crazyRadioStatusSubscriber = agent_base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &ConnectStartStopBar::crazyRadioStatusCallback, this);
+
+        // > For updating the current battery voltage
+        batteryVoltageSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &ConnectStartStopBar::batteryVoltageCallback, this);
+
+        // > For updating the current battery state
+        //batteryStateSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &ConnectStartStopBar::batteryStateChangedCallback, this);
+
+        // > For updating the current battery level
+        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);
+    }
+    else
+    {
+        // Unsubscribe
+        crazyRadioStatusSubscriber.shutdown();
+        batteryVoltageSubscriber.shutdown();
+        //batteryStateSubscriber.shutdown();
+        batteryLevelSubscriber.shutdown();
+        flyingStateSubscriber.shutdown();
+
+        // Set information back to the default
+        setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+        setBatteryVoltageText(-1.0f);
+        setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
+        setFlyingState(STATE_UNAVAILABLE);
+
+    }
+#endif
+
+
 #ifdef CATKIN_MAKE
 #else
     // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 0b1f05ce..702388f2 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -83,7 +83,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
     
     // SET THE STARTING FLYING STATE STATUS TO BE: MOTORS OFF
-    setFlyingState(CMD_CRAZYFLY_MOTORS_OFF);
+    setFlyingState(STATE_UNAVAILABLE);
     
     // SET THE DEFAULT NAME FOR THE SELECTED CONTROLLER
     setControllerEnabled(SAFE_CONTROLLER);
@@ -130,12 +130,26 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     // > For updating the controller that is currently operating
     controllerUsedSubscriber = base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &CoordinatorRow::controllerUsedChangedCallback, this);
 
+    // > For requesting the current flying state,
+    //   this is used only for initialising the icon
+    getCurrentFlyingStateService = base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
+
+    // > For requesting the current state of the Crazy Radio,
+    //   this is used only for initialising the icon
+    getCurrentCrazyRadioStateService = base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
+
 #endif
 
     // FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
     // INITIALISATIONS ARE COMPLETE
     loadCrazyflieContext();
 
+    // > Request the current flying state
+    getCurrentFlyingState();
+
+    // > Request the current state of the Crazy Radio
+    getCurrentCrazyRadioState();
+
 }
 
 CoordinatorRow::~CoordinatorRow()
@@ -541,6 +555,15 @@ void CoordinatorRow::setFlyingState(int new_flying_state)
             break;
         }
 
+        case STATE_UNAVAILABLE:
+        {
+            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
+            QPixmap flying_state_disabling_pixmap(":/images/flying_state_unavailable.png");
+            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
+            ui->flying_state_label->setScaledContents(true);
+            break;
+        }
+
         default:
         {
             // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
@@ -619,6 +642,41 @@ void CoordinatorRow::loadCrazyflieContext()
 
 
 
+void CoordinatorRow::getCurrentFlyingState()
+{
+    d_fall_pps::IntIntService getFlyingStateCall;
+    getFlyingStateCall.request.data = 0;
+    getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
+    if(getCurrentFlyingStateService.call(getFlyingStateCall))
+    {
+        setFlyingState(getFlyingStateCall.response.data);
+    }
+    else
+    {
+        setFlyingState(STATE_UNAVAILABLE);
+    }
+}
+
+
+
+
+void CoordinatorRow::getCurrentCrazyRadioState()
+{
+    d_fall_pps::IntIntService getCrazyRadioCall;
+    getCrazyRadioCall.request.data = 0;
+    getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
+    if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
+    {
+        setCrazyRadioStatus(getCrazyRadioCall.response.data);
+    }
+    else
+    {
+        setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+    }
+}
+
+
+
 
 //    ----------------------------------------------------------------------------------
 //     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index 7b2850f4..2a66010a 100755
--- a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -38,6 +38,7 @@ import rospy
 from std_msgs.msg import Int32
 from d_fall_pps.msg import ControlCommand
 from d_fall_pps.msg import IntWithHeader
+from d_fall_pps.srv import IntIntService
 
 
 # General import
@@ -333,6 +334,16 @@ class PPSRadioClient:
                     print "[CRAZY RADIO] received command to DISCONNECT (current status is DISCONNECTED)"
                     #self.status_pub.publish(DISCONNECTED)
 
+
+
+    def getCurrentCrazyRadioStatusServiceCallback(self, req):
+        """Callback to service the request for the connection status"""
+        # Directly return the current status
+        return self._status
+
+
+
+
 def controlCommandCallback(data):
     """Callback for controller actions"""
     #rospy.loginfo("controller callback : %s, %s, %s", data.roll, data.pitch, data.yaw)
@@ -352,6 +363,8 @@ def controlCommandCallback(data):
 
 
 
+
+
 if __name__ == '__main__':
 
     # Starting the ROS-node
@@ -406,6 +419,12 @@ if __name__ == '__main__':
     rospy.Subscriber("/dfall/coord" + coordID_as_string + "/PPSClient/crazyRadioCommand", IntWithHeader, cf_client.crazyRadioCommandCallback)
 
 
+    # Advertise a Serice for the current status
+    # of the Crazy Radio connect
+    s = rospy.Service(node_name + "/getCurrentCrazyRadioStatus", IntIntService , cf_client.getCurrentCrazyRadioStatusServiceCallback)
+
+
+
     time.sleep(1.0)
 
     rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
diff --git a/pps_ws/src/d_fall_pps/include/nodes/Constants.h b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
index 2962a8b3..33898352 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/Constants.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
@@ -125,10 +125,11 @@
 #define CMD_CRAZYFLY_MOTORS_OFF      13
 
 // Flying states
-#define STATE_MOTORS_OFF 1
-#define STATE_TAKE_OFF   2
-#define STATE_FLYING     3
-#define STATE_LAND       4
+#define STATE_MOTORS_OFF     1
+#define STATE_TAKE_OFF       2
+#define STATE_FLYING         3
+#define STATE_LAND           4
+#define STATE_UNAVAILABLE    5
 
 
 // Commands for CrazyRadio
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
index c59b6c4b..7efa2a65 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -62,6 +62,7 @@
 // Include the DFALL service types
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/CMQuery.h"
+#include "d_fall_pps/IntIntService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -301,4 +302,8 @@ int getControllerUsed();
 //void setBatteryStateTo(int new_battery_state);
 //float movingAverageBatteryFilter(float new_input);
 //void CFBatteryCallback(const std_msgs::Float32& msg);
-void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
\ No newline at end of file
+void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
+
+
+// > For the FLYING STATE
+bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index de1c8b39..79bd5ce3 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -911,6 +911,25 @@ void CFBatteryCallback(const std_msgs::Float32& msg)
 
 
 
+
+
+
+
+bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response)
+{
+    // Put the flying state into the response variable
+    response.data = flying_state;
+    // Return
+    return true;
+}
+
+
+
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
 //    L      O   O   A A   D   D
@@ -1346,6 +1365,10 @@ int main(int argc, char* argv[])
     setControllerUsed(SAFE_CONTROLLER);
     setInstantController(SAFE_CONTROLLER); //initialize this also, so we notify GUI
 
+
+    // Advertise the service for the current flying state
+    ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("getCurrentFlyingState", getCurrentFlyingStateServiceCallback);
+
     
 
     // Open a ROS "bag" to store data for post-analysis
diff --git a/pps_ws/src/d_fall_pps/srv/IntIntService.srv b/pps_ws/src/d_fall_pps/srv/IntIntService.srv
new file mode 100644
index 00000000..641afd72
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/srv/IntIntService.srv
@@ -0,0 +1,3 @@
+uint32 data
+---
+uint32 data
-- 
GitLab


From ca3b48852ac9f143fb7d1fcc822b0021f65ce100 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 18 Dec 2018 14:15:30 +0100
Subject: [PATCH 25/87] Setpoint changes now generalised through the GUI for
 the Default controller. Needs more extensive testing. Next step is to get
 that current controller state when the corrdinator is coordinating only one
 agent

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   5 +
 .../include/Constants_for_Qt_compile.h        |  46 +-
 .../flyingAgentGUI/include/controllertabs.h   |   1 +
 .../include/defaultcontrollertab.h            |  11 +-
 .../flyingAgentGUI/src/controllertabs.cpp     |  30 +-
 .../src/defaultcontrollertab.cpp              | 204 +++-
 .../src/enablecontrollerloadyamlbar.cpp       |  13 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  14 +-
 .../src/d_fall_pps/include/nodes/Constants.h  |  32 +-
 .../include/nodes/DefaultControllerService.h  | 237 +++++
 .../include/nodes/ParameterService.h          |   9 +-
 .../include/nodes/StudentControllerService.h  |   5 +-
 pps_ws/src/d_fall_pps/launch/Agent.launch     |   9 +
 .../src/d_fall_pps/msg/SetpointWithHeader.msg |   2 +-
 .../d_fall_pps/param/DefaultController.yaml   |  16 +
 .../src/nodes/DefaultControllerService.cpp    | 962 ++++++++++++++++++
 .../d_fall_pps/src/nodes/ParameterService.cpp | 173 +---
 .../src/nodes/StudentControllerService.cpp    |  52 +-
 .../d_fall_pps/srv/LoadYamlFromFilename.srv   |   3 +
 19 files changed, 1595 insertions(+), 229 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
 create mode 100644 pps_ws/src/d_fall_pps/param/DefaultController.yaml
 create mode 100644 pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
 create mode 100644 pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 09af57d2..81579ef9 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -230,6 +230,7 @@ add_service_files(
   CMQuery.srv
   CMUpdate.srv
   CMCommand.srv
+  LoadYamlFromFilename.srv
 )
 
 ## Generate actions in the 'action' folder
@@ -326,6 +327,8 @@ add_executable(PPSClient                 src/nodes/PPSClient.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(BatteryMonitor            src/nodes/BatteryMonitor.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
+add_executable(DefaultControllerService  src/nodes/DefaultControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(SafeControllerService     src/nodes/SafeControllerService.cpp)
 add_executable(DemoControllerService     src/nodes/DemoControllerService.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
@@ -412,6 +415,7 @@ endif()
 
 add_dependencies(PPSClient                 d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(BatteryMonitor            d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(DefaultControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(SafeControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(DemoControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(StudentControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
@@ -463,6 +467,7 @@ endif()
 
 target_link_libraries(PPSClient                 ${catkin_LIBRARIES})
 target_link_libraries(BatteryMonitor            ${catkin_LIBRARIES})
+target_link_libraries(DefaultControllerService  ${catkin_LIBRARIES})
 target_link_libraries(SafeControllerService     ${catkin_LIBRARIES})
 target_link_libraries(DemoControllerService     ${catkin_LIBRARIES})
 target_link_libraries(StudentControllerService  ${catkin_LIBRARIES})
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
index 93f79577..d96707d4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
@@ -49,6 +49,38 @@
 
 
 
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+
+
 // Types PPS firmware
 #define CF_COMMAND_TYPE_MOTORS 6
 #define CF_COMMAND_TYPE_RATE   7
@@ -145,12 +177,16 @@
 
 
 
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
 
-// The types, i.e., agent or coordinator
-#define TYPE_INVALID      -1
-#define TYPE_COORDINATOR   1
-#define TYPE_AGENT         2
-
+// For standard buttons in the GUI
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
 
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 7aad04c8..a4d11624 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -52,6 +52,7 @@ public slots:
 
 
 signals:
+    void agentIDsToCoordinateChanged(QVector<int> agentIDs , bool shouldCoordinateAll);
     void measuredPoseValueChanged(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
     void poseDataUnavailableSignal();
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index c8a3a4a9..68edb4ea 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -46,6 +46,7 @@ public:
 
 
 public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
     void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
     void poseDataUnavailableSlot();
 
@@ -90,12 +91,13 @@ private:
 
 
 #ifdef CATKIN_MAKE
-    // Variable for storing the default setpoint
-    d_fall_pps::SetpointWithHeader m_defaultSetpoint;
-
     // PUBLISHER
     // > For requesting the setpoint to be changed
     ros::Publisher requestSetpointChangePublisher;
+
+    // SUBSCRIBER
+    // > For being notified when the setpoint is changed
+    ros::Subscriber setpointChangedSubscriber;
 #endif
 
 
@@ -104,6 +106,9 @@ private:
 
 
 #ifdef CATKIN_MAKE
+    // For receiving message that the setpoint was changed
+    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+
     // Fill the header for a message
     void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index aafb53da..d7140128 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -34,6 +34,17 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->default_controller_tab_widget , &DefaultControllerTab::poseDataUnavailableSlot
         );
 
+
+    // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
+    // WITH THE LIST OF AGENT IDs TO COORDINATE
+    // This is passed from this "controller tabs widget" to
+    // each of the controller tabs. The signal is simply
+    // "passed through"
+    QObject::connect(
+            this , &ControllerTabs::agentIDsToCoordinateChanged ,
+            ui->default_controller_tab_widget , &DefaultControllerTab::setAgentIDsToCoordinate
+        );
+
     
 
 
@@ -148,23 +159,8 @@ void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& vicon
 
 void ControllerTabs::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
 {
-
-    // Lock the mutex
-    m_agentIDs_toCoordinate_mutex.lock();
-    // Add the "coordinate all" flag
-    m_shouldCoordinateAll = shouldCoordinateAll;
-    // Clear the previous list of agent IDs
-    m_vector_of_agentIDs_toCoordinate.clear();
-    // Copy across the agent IDs, if necessary
-    if (!shouldCoordinateAll)
-    {
-        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
-        {
-            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
-        }
-    }
-    // Unlock the mutex
-    m_agentIDs_toCoordinate_mutex.unlock();
+    // Simply pass on the signal to the tabs
+    emit agentIDsToCoordinateChanged( agentIDs , shouldCoordinateAll );
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 56aaf802..147a43ba 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -36,15 +36,16 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     // CREATE A NODE HANDLE TO THIS GUI
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
-    // CREATE THE COMMAND PUBLISHER
+    // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
     requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("DefaultControllerService/RequestSetpointChange", 1);
 
+    // SUBSCRIBE TO SETPOINT CHANGES
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("DefaultControllerService/SetpointChanged", 1, &DefaultControllerTab::setpointChangedCallback, this);
+    }
 
-    // Set the default setpoint
-    m_defaultSetpoint.x   = 0.0f;
-    m_defaultSetpoint.y   = 0.0f;
-    m_defaultSetpoint.z   = 0.5f;
-    m_defaultSetpoint.yaw = 0.0f;
 #endif
 
 }
@@ -130,6 +131,83 @@ void DefaultControllerTab::poseDataUnavailableSlot()
 
 
 
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC  H   H    A    N   N   GGGG  EEEEE  DDDD
+//    C      H   H   A A   NN  N  G      E      D   D
+//    C      HHHHH  A   A  N N N  G      EEE    D   D
+//    C      H   H  AAAAA  N  NN  G   G  E      D   D
+//     CCCC  H   H  A   A  N   N   GGGG  EEEEE  DDDD
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void DefaultControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+{
+    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+    QString qstr = "";
+
+    // EXTRACT THE SETPOINT
+    float x = newSetpoint.x;
+    float y = newSetpoint.y;
+    float z = newSetpoint.z;
+    float yaw = newSetpoint.yaw;
+
+    // UPDATE THE SETPOINT COLUMN
+    if (x < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_x->setText(qstr + QString::number( x, 'f', 3));
+    if (y < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_y->setText(qstr + QString::number( y, 'f', 3));
+    if (z < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3));
+
+    if (yaw < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 3));
+}
+#endif
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    RRRR   EEEEE   QQQ   U   U  EEEEE   SSSS  TTTTT     N   N  EEEEE  W     W
+//    R   R  E      Q   Q  U   U  E      S        T       NN  N  E      W     W
+//    RRRR   EEE    Q   Q  U   U  EEE     SSS     T       N N N  EEE    W     W 
+//    R   R  E      Q  Q   U   U  E          S    T       N  NN  E       W W W
+//    R   R  EEEEE   QQ Q   UUU   EEEEE  SSSS     T       N   N  EEEEE    W W
+//
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//    ----------------------------------------------------------------------------------
+
+
 void DefaultControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
 #ifdef CATKIN_MAKE
@@ -143,7 +221,7 @@ void DefaultControllerTab::publishSetpoint(float x, float y, float z, float yaw)
     msg.x   = x;
     msg.y   = y;
     msg.z   = z;
-    msg.yaw = yaw;
+    msg.yaw = yaw * DEG2RAD;
 
     // Publish the setpoint
     this->requestSetpointChangePublisher.publish(msg);
@@ -224,8 +302,23 @@ void DefaultControllerTab::on_set_setpoint_button_clicked()
 void DefaultControllerTab::on_default_setpoint_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    // Call the function to publish the setpoint
-    publishSetpoint(m_defaultSetpoint.x, m_defaultSetpoint.y, m_defaultSetpoint.z, m_defaultSetpoint.yaw );
+    // Publish this as a blank setpoint with the 
+    // "buttonID" field set appropriately
+
+    // Initialise the message as a local variable
+    d_fall_pps::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.buttonID = REQUEST_DEFAULT_SETPOINT_BUTTON_ID;
+
+    // Publish the default setpoint button press
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Published request for setpoint change to the default");
 #endif
 }
 
@@ -416,6 +509,99 @@ void DefaultControllerTab::on_yaw_increment_minus_button_clicked()
 
 
 
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // // > Request the current flying state
+        // ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
+        // d_fall_pps::IntIntService getFlyingStateCall;
+        // getFlyingStateCall.request.data = 0;
+        // getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
+        // if(getCurrentFlyingStateService.call(getFlyingStateCall))
+        // {
+        //     setFlyingState(getFlyingStateCall.response.data);
+        // }
+        // else
+        // {
+        //     setFlyingState(STATE_UNAVAILABLE);
+        // }
+
+        // // > Request the current status of the crazy radio
+        // ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
+        // d_fall_pps::IntIntService getCrazyRadioCall;
+        // getCrazyRadioCall.request.data = 0;
+        // getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
+        // if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
+        // {
+        //     setCrazyRadioStatus(getCrazyRadioCall.response.data);
+        // }
+        // else
+        // {
+        //     setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
+        // }
+
+
+        // SUBSCRIBERS
+        // > For receiving message that the setpoint was changed
+        setpointChangedSubscriber = agent_base_nodeHandle.subscribe("DefaultControllerService/SetpointChanged", 1, &DefaultControllerTab::setpointChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        setpointChangedSubscriber.shutdown();
+
+        // Set information back to the default
+        ui->lineEdit_setpoint_current_x->setText("xx.xx");
+        ui->lineEdit_setpoint_current_y->setText("xx.xx");
+        ui->lineEdit_setpoint_current_z->setText("xx.xx");
+        ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
+
+    }
+#endif
+}
+
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
 //    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 28908655..135fab04 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -137,7 +137,18 @@ void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
 
 void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 {
-
+    #ifdef CATKIN_MAKE
+    // Create a local variable for the message
+    d_fall_pps::StringWithHeader yaml_filename_msg;
+    // Set for whom this applies to
+    fillStringMessageHeader(yaml_filename_msg);
+    // Specify the data
+    yaml_filename_msg.data = "DefaultController";
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+    // Inform the user that the menu item was selected
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Default Controller YAML was clicked.");
+#endif
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index cfd33ca8..58f17f9d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -95,21 +95,25 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
 
     // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
     // WITH THE LIST OF AGENT IDs TO COORDINATE
-    // Connect the "should coordinate value changed" signal to
-    // the respective slot
+    // This is passed from the "coordinator" to the elements
+    // in the main part of the GUI, namely to the:
+    // > "top banner",
+    // > "connect,start,stop bar",
+    // > "enable controller, load yaml bar", and
+    // > "controller tabs widget".
     QObject::connect(
             ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
-            ui->customWidget_connectStartStopBar , &ConnectStartStopBar::setAgentIDsToCoordinate
+            ui->customWidget_topBanner , &TopBanner::setAgentIDsToCoordinate
             );
 
     QObject::connect(
             ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
-            ui->customWidget_enableControllerLoadYamlBar , &EnableControllerLoadYamlBar::setAgentIDsToCoordinate
+            ui->customWidget_connectStartStopBar , &ConnectStartStopBar::setAgentIDsToCoordinate
             );
 
     QObject::connect(
             ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged ,
-            ui->customWidget_topBanner , &TopBanner::setAgentIDsToCoordinate
+            ui->customWidget_enableControllerLoadYamlBar , &EnableControllerLoadYamlBar::setAgentIDsToCoordinate
             );
 
     QObject::connect(
diff --git a/pps_ws/src/d_fall_pps/include/nodes/Constants.h b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
index 33898352..fd4d1d4f 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/Constants.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/Constants.h
@@ -53,6 +53,25 @@
 
 
 
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    
 //    
@@ -192,11 +211,16 @@
 
 
 
-// The types, i.e., agent or coordinator
-#define TYPE_INVALID      -1
-#define TYPE_COORDINATOR   1
-#define TYPE_AGENT         2
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
 
+// For standard buttons in the GUI
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
 
 
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
new file mode 100644
index 00000000..b88fa8e2
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
@@ -0,0 +1,237 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The fall-back controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  N   N   CCCC  L      U   U  DDDD   EEEEE   SSSS
+//     I   NN  N  C      L      U   U  D   D  E      S
+//     I   N N N  C      L      U   U  D   D  EEE     SSS
+//     I   N  NN  C      L      U   U  D   D  E          S
+//    III  N   N   CCCC  LLLLL   UUU   DDDD   EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These various headers need to be included so that this controller service can be
+// connected with the D-FaLL system.
+
+//some useful libraries
+#include <math.h>
+#include <stdlib.h>
+#include "ros/ros.h"
+#include <ros/package.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/StringWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/ViconData.h"
+#include "d_fall_pps/Setpoint.h"
+#include "d_fall_pps/ControlCommand.h"
+#include "d_fall_pps/Controller.h"
+#include "d_fall_pps/DebugMsg.h"
+#include "d_fall_pps/CustomButton.h"
+
+// Include the DFALL service types
+#include "d_fall_pps/LoadYamlFromFilename.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+// Need for having a ROS "bag" to store data for post-analysis
+//#include <rosbag/bag.h>
+
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    DDDD   EEEEE  FFFFF  III  N   N  EEEEE   SSSS
+//    D   D  E      F       I   NN  N  E      S
+//    D   D  EEE    FFF     I   N N N  EEE     SSS
+//    D   D  E      F       I   N  NN  E          S
+//    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These constants are defined to make the code more readable and adaptable.
+
+// NOTE: manz constants are already defined in the "Constant.h" header file
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    V   V    A    RRRR   III    A    BBBB   L      EEEEE   SSSS
+//    V   V   A A   R   R   I    A A   B   B  L      E      S
+//    V   V  A   A  RRRR    I   A   A  BBBB   L      EEE     SSS
+//     V V   AAAAA  R  R    I   AAAAA  B   B  L      E          S
+//      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// The ID of the agent that can coordinate this node
+int m_coordID;
+
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
+
+
+
+// The mass of the crazyflie, in [grams]
+float yaml_cf_mass_in_grams = 25.0;
+
+// Coefficients of the 16-bit command to thrust conversion
+//std::vector<float> yaml_motorPoly(3);
+std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
+
+// Frequency at which the controller is running
+float yaml_control_frequency = 200.0;
+
+// The min and max for saturating 16 bit thrust commands
+float yaml_command_sixteenbit_min = 1000;
+float yaml_command_sixteenbit_max = 65000;
+
+// The default setpoint, the ordering is (x,y,z,yaw),
+// with unit [meters,meters,meters,radians]
+std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
+
+
+
+// The weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = 0.0;
+
+// The location error of the Crazyflie at the "previous" time step
+float m_previous_stateErrorInertial[9];
+
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
+
+
+// The LQR Controller parameters for "LQR_RATE_MODE"
+std::vector<float> m_gainMatrixRollRate    =  { 0.00,-1.71, 0.00, 0.00,-1.33, 0.00, 5.12, 0.00, 0.00};
+std::vector<float> m_gainMatrixPitchRate   =  { 1.71, 0.00, 0.00, 1.33, 0.00, 0.00, 0.00, 5.12, 0.00};
+std::vector<float> m_gainMatrixYawRate     =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.84};
+std::vector<float> m_gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.08, 0.00, 0.00, 0.00};
+
+
+// ROS Publisher for debugging variables
+ros::Publisher m_debugPublisher;
+
+// ROS Publisher for inform the network about
+// changes to the setpoin
+ros::Publisher m_setpointChangedPublisher;
+
+
+
+// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
+// The "CrazyflieData" type used for the "request" variable is a
+// structure as defined in the file "CrazyflieData.msg" which has the following
+// properties:
+//     string crazyflieName              The name given to the Crazyflie in the Vicon software
+//     float64 x                         The x position of the Crazyflie [metres]
+//     float64 y                         The y position of the Crazyflie [metres]
+//     float64 z                         The z position of the Crazyflie [metres]
+//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
+//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
+//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
+//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
+//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    PPPP   RRRR    OOO   TTTTT   OOO   TTTTT  Y   Y  PPPP   EEEEE   SSSS
+//    P   P  R   R  O   O    T    O   O    T     Y Y   P   P  E      S
+//    PPPP   RRRR   O   O    T    O   O    T      Y    PPPP   EEE     SSS
+//    P      R  R   O   O    T    O   O    T      Y    P      E          S
+//    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These function prototypes are not strictly required for this code to
+// complile, but adding the function prototypes here means the the functions
+// can be written below in any order. If the function prototypes are not
+// included then the function need to written below in an order that ensure
+// each function is implemented before it is called from another function,
+// hence why the "main" function is at the bottom.
+
+// CONTROLLER COMPUTATIONS
+bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
+
+// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR INTO AN (x,y) BODY FRAME ERROR
+void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured);
+
+// CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
+float computeMotorPolyBackward(float thrust);
+
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
+
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw);
+
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButton& commandReceived);
+
+
+// > For the LOADING of YAML PARAMETERS
+void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg);
+void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
index 011ff0c7..75d51729 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
@@ -58,6 +58,9 @@
 //#include "d_fall_pps/FloatWithHeader.h"
 #include "d_fall_pps/StringWithHeader.h"
 
+// Include the DFALL service types
+#include "d_fall_pps/LoadYamlFromFilename.h"
+
 // Include the shared definitions
 #include "nodes/Constants.h"
 
@@ -101,6 +104,10 @@ int m_ID = 0;
 // The namespace into which this parameter service loads yaml parameters
 std::string m_base_namespace;
 
+// Publisher for passing a service request onto the
+// loadinging function
+ros::Publisher requestLoadYamlFilenamePublisher;
+
 
 
 
@@ -119,7 +126,7 @@ std::string m_base_namespace;
 //    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-void requestLoadControllerYamlCallback(const std_msgs::Int32& msg);
+bool requestLoadYamlFilenameCallbackServiceCallback(LoadYamlFromFilename::Request &request, LoadYamlFromFilename::Response &response);
 
 void requestLoadYamlFilenameCallback(const StringWithHeader& yamlFilenameToLoad);
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 8eea640a..7d440b25 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -55,7 +55,7 @@
 #include "std_msgs/Float32.h"
 #include <std_msgs/String.h>
 
-//the generated structs from the msg-files have to be included
+// Include the DFALL message types
 #include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/StringWithHeader.h"
 #include "d_fall_pps/ViconData.h"
@@ -65,6 +65,9 @@
 #include "d_fall_pps/DebugMsg.h"
 #include "d_fall_pps/CustomButton.h"
 
+// Include the DFALL service types
+#include "d_fall_pps/LoadYamlFromFilename.h"
+
 // Include the shared definitions
 #include "nodes/Constants.h"
 
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/pps_ws/src/d_fall_pps/launch/Agent.launch
index bb994eb3..2c978143 100755
--- a/pps_ws/src/d_fall_pps/launch/Agent.launch
+++ b/pps_ws/src/d_fall_pps/launch/Agent.launch
@@ -47,6 +47,15 @@
 			>
 		</node>
 
+		<!-- DEFAULT CONTROLLER -->
+		<node
+			pkg    = "d_fall_pps"
+			name   = "DefaultControllerService"
+			output = "screen"
+			type   = "DefaultControllerService"
+			>
+		</node>
+
 		<!-- SAFE CONTROLLER -->
 		<node
 			pkg    = "d_fall_pps"
diff --git a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
index 9198063b..ff412908 100644
--- a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
+++ b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
@@ -5,4 +5,4 @@ float64 yaw
 bool isChecked
 uint32 buttonID
 bool shouldCheckForAgentID
-uint8[] agentIDs
\ No newline at end of file
+uint32[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/param/DefaultController.yaml b/pps_ws/src/d_fall_pps/param/DefaultController.yaml
new file mode 100644
index 00000000..3c208ca7
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/param/DefaultController.yaml
@@ -0,0 +1,16 @@
+# The mass of the crazyflie, in [grams]
+mass : 28
+
+# Frequency of the controller, in [hertz]
+control_frequency : 200
+
+# Quadratic motor regression equation (a0, a1, a2)
+motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
+
+# The min and max for saturating 16 bit thrust commands
+command_sixteenbit_min : 1000
+command_sixteenbit_max : 65000
+
+# The default setpoint, the ordering is (x,y,z,yaw),
+# with unit [meters,meters,meters,radians]
+default_setpoint : [0.0, 0.0, 0.4, 0.0]
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
new file mode 100644
index 00000000..fe37b42c
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
@@ -0,0 +1,962 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The fall-back controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// INCLUDE THE HEADER
+#include "nodes/DefaultControllerService.h"
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    III M   M PPPP  L     EEEEE M   M EEEEE N   N TTTTT   A   TTTTT III  OOO  N   N
+//     I  MM MM P   P L     E     MM MM E     NN  N   T    A A    T    I  O   O NN  N
+//     I  M M M PPPP  L     EEE   M M M EEE   N N N   T   A   A   T    I  O   O N N N
+//     I  M   M P     L     E     M   M E     N  NN   T   AAAAA   T    I  O   O N  NN
+//    III M   M P     LLLLL EEEEE M   M EEEEE N   N   T   A   A   T   III  OOO  N   N
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ------------------------------------------------------------------------------
+//     OOO   U   U  TTTTT  EEEEE  RRRR 
+//    O   O  U   U    T    E      R   R
+//    O   O  U   U    T    EEE    RRRR
+//    O   O  U   U    T    E      R  R
+//     OOO    UUU     T    EEEEE  R   R
+//
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L           L       OOO    OOO   PPPP
+//    C      O   O  NN  N    T    R   R  O   O  L           L      O   O  O   O  P   P
+//    C      O   O  N N N    T    RRRR   O   O  L           L      O   O  O   O  PPPP
+//    C      O   O  N  NN    T    R  R   O   O  L           L      O   O  O   O  P
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL       LLLLL   OOO    OOO   P
+//    ----------------------------------------------------------------------------------
+
+// This function is the callback that is linked to the "DefaultController" service that
+// is advertised in the main function. This must have arguments that match the
+// "input-output" behaviour defined in the "Controller.srv" file (located in the "srv"
+// folder)
+//
+// The arument "request" is a structure provided to this service with the following two
+// properties:
+// request.ownCrazyflie
+// This property is itself a structure of type "CrazyflieData",  which is defined in the
+// file "CrazyflieData.msg", and has the following properties
+// string crazyflieName
+//     float64 x                         The x position of the Crazyflie [metres]
+//     float64 y                         The y position of the Crazyflie [metres]
+//     float64 z                         The z position of the Crazyflie [metres]
+//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
+//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
+//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
+//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
+//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+// The values in these properties are directly the measurement taken by the Vicon
+// motion capture system of the Crazyflie that is to be controlled by this service
+//
+// request.otherCrazyflies
+// This property is an array of "CrazyflieData" structures, what allows access to the
+// Vicon measurements of other Crazyflies.
+//
+// The argument "response" is a structure that is expected to be filled in by this
+// service by this function, it has only the following property
+// response.ControlCommand
+// This property is iteself a structure of type "ControlCommand", which is defined in
+// the file "ControlCommand.msg", and has the following properties:
+//     float32 roll                      The command sent to the Crazyflie for the body frame x-axis
+//     float32 pitch                     The command sent to the Crazyflie for the body frame y-axis
+//     float32 yaw                       The command sent to the Crazyflie for the body frame z-axis
+//     uint16 motorCmd1                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd2                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd3                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd4                  The command sent to the Crazyflie for motor 1
+//     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
+// 
+// IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
+// > The allowed values for "onboardControllerType" are in the "Defines"
+//   section in the header file, they are:
+//   - CF_COMMAND_TYPE_MOTORS
+//   - CF_COMMAND_TYPE_RATE
+//   - CF_COMMAND_TYPE_ANGLE
+//
+// > For completeing the class exercises it is only required to use
+//   the CF_COMMAND_TYPE_RATE option.
+//
+// > For the CF_COMMAND_TYPE_RATE optoin:
+//   1) 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.
+//   2) the ".motorCmd1" to ".motorCmd4" properties of
+//      "response.ControlCommand" are the baseline motor commands
+//      requested from the Crazyflie, with the adjustment for body rates
+//      being added on top of this in the firmware (i.e., as per the
+//      code of the "distribute_power" found in the firmware).
+//   3) the axis convention for the roll, pitch, and yaw body rates
+//      returned in "response.ControlCommand" should use right-hand
+//      coordinate axes with x-forward and z-upwards (i.e., the positive
+//      z-axis is aligned with the direction of positive thrust). To
+//      assist, the following is an ASCII art of this convention.
+//
+// ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
+//
+//  > This is a top view,
+//  > M1 to M4 stand for Motor 1 to Motor 4,
+//  > "CW"  indicates that the motor rotates Clockwise,
+//  > "CCW" indicates that the motor rotates Counter-Clockwise,
+//  > By right-hand axis convention, the positive z-direction points our of the screen,
+//  > This being a "top view" means tha the direction of positive thrust produced
+//    by the propellers is also out of the screen.
+//
+//        ____                         ____
+//       /    \                       /    \
+//  (CW) | M4 |           x           | M1 | (CCW)
+//       \____/\          ^          /\____/
+//            \ \         |         / /
+//             \ \        |        / /
+//              \ \______ | ______/ /
+//               \        |        /
+//                |       |       |
+//        y <-------------o       |
+//                |               |
+//               / _______________ \
+//              / /               \ \
+//             / /                 \ \
+//        ____/ /                   \ \____
+//       /    \/                     \/    \
+// (CCW) | M3 |                       | M2 | (CW)
+//       \____/                       \____/
+//
+//
+//
+// This function WILL NEED TO BE edited for successful completion of the PPS exercise
+bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
+{
+
+	// This is the "start" of the outer loop controller, add all your control
+	// computation here, or you may find it convienient to create functions
+	// to keep you code cleaner
+
+
+	// Define a local array to fill in with the state error
+	float stateErrorInertial[9];
+
+	// Fill in the (x,y,z) position error
+	stateErrorInertial[0] = request.ownCrazyflie.x - m_setpoint[0];
+	stateErrorInertial[1] = request.ownCrazyflie.y - m_setpoint[1];
+	stateErrorInertial[2] = request.ownCrazyflie.z - m_setpoint[2];
+
+	// Compute an estimate of the velocity
+	// > As simply the derivative between the current and previous position
+	stateErrorInertial[3] = (stateErrorInertial[0] - m_previous_stateErrorInertial[0]) * yaml_control_frequency;
+	stateErrorInertial[4] = (stateErrorInertial[1] - m_previous_stateErrorInertial[1]) * yaml_control_frequency;
+	stateErrorInertial[5] = (stateErrorInertial[2] - m_previous_stateErrorInertial[2]) * yaml_control_frequency;
+
+	// Fill in the roll and pitch angle measurements directly
+	stateErrorInertial[6] = request.ownCrazyflie.roll;
+	stateErrorInertial[7] = request.ownCrazyflie.pitch;
+
+	// Fill in the yaw angle error
+	// > This error should be "unwrapped" to be in the range
+	//   ( -pi , pi )
+	// > First, get the yaw error into a local variable
+	float yawError = request.ownCrazyflie.yaw - m_setpoint[3];
+	// > Second, "unwrap" the yaw error to the interval ( -pi , pi )
+	while(yawError > PI) {yawError -= 2 * PI;}
+	while(yawError < -PI) {yawError += 2 * PI;}
+	// > Third, put the "yawError" into the "stateError" variable
+	stateErrorInertial[8] = yawError;
+
+
+	// CONVERSION INTO BODY FRAME
+	// Conver the state erorr from the Inertial frame into the Body frame
+	// > 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
+	float stateErrorBody[9];
+	convertIntoBodyFrame(stateErrorInertial, stateErrorBody, request.ownCrazyflie.yaw);
+
+
+	// SAVE THE STATE ERROR TO BE USED NEXT TIME THIS FUNCTION IS CALLED
+	// > as we have already used previous error we can now update it update it
+	for(int i = 0; i < 9; ++i)
+	{
+		m_previous_stateErrorInertial[i] = stateErrorInertial[i];
+	}
+
+
+
+	
+	// YAW CONTROLLER
+
+	// Perform the "-Kx" LQR computation for the yaw rate
+	// to respond with
+	float yawRate_forResponse = 0;
+	for(int i = 0; i < 9; ++i)
+	{
+		yawRate_forResponse -= m_gainMatrixYawRate[i] * stateErrorBody[i];
+	}
+	// Put the computed yaw rate into the "response" variable
+	response.controlOutput.yaw = yawRate_forResponse;
+
+
+
+
+	// ALITUDE CONTROLLER (i.e., z-controller)
+	
+	// Perform the "-Kx" LQR computation for the thrust adjustment
+	// to use for computing the response with
+	float thrustAdjustment = 0;
+	for(int i = 0; i < 9; ++i)
+	{
+		thrustAdjustment -= m_gainMatrixThrust[i] * stateErrorBody[i];
+	}
+
+	// Add the feed-forward thrust before putting in the response
+	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
+	float thrust_per_motor = thrustAdjustment + feed_forward_thrust_per_motor;
+
+	// > NOTE: the function "computeMotorPolyBackward" converts the
+	//         input argument from Newtons to the 16-bit command
+	//         expected by the Crazyflie.
+	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrust_per_motor);
+	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrust_per_motor);
+	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrust_per_motor);
+	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrust_per_motor);
+
+	
+	// BODY FRAME X CONTROLLER
+
+	// Perform the "-Kx" LQR computation for the pitch rate
+	// to respoond with
+	float pitchRate_forResponse = 0;
+	for(int i = 0; i < 9; ++i)
+	{
+		pitchRate_forResponse -= m_gainMatrixPitchRate[i] * stateErrorBody[i];
+	}
+	// Put the computed pitch rate into the "response" variable
+	response.controlOutput.pitch = pitchRate_forResponse;
+
+
+
+
+	// BODY FRAME Y CONTROLLER
+
+	// Instantiate the local variable for the roll rate that will be requested
+	// from the Crazyflie's on-baord "inner-loop" controller
+	
+
+	// Perform the "-Kx" LQR computation for the roll rate
+	// to respoond with
+	float rollRate_forResponse = 0;
+	for(int i = 0; i < 9; ++i)
+	{
+		rollRate_forResponse -= m_gainMatrixRollRate[i] * stateErrorBody[i];
+	}
+	// Put the computed roll rate into the "response" variable
+	response.controlOutput.roll = rollRate_forResponse;
+
+	
+	
+	// PREPARE AND RETURN THE VARIABLE "response"
+
+	/*choosing the Crazyflie onBoard controller type.
+	it can either be Motor, Rate or Angle based */
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
+
+
+
+
+
+	//  ***********************************************************
+	//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
+	//  D   D  E      B   B  U   U  G           MM MM  S      G
+	//  D   D  EEE    BBBB   U   U  G           M M M   SSS   G
+	//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
+	//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
+
+	// DEBUGGING CODE:
+	// As part of the D-FaLL-System we have defined a message type names"DebugMsg".
+	// By fill this message with data and publishing it you can display the data in
+	// real time using rpt plots. Instructions for using rqt plots can be found on
+	// the wiki of the D-FaLL-System repository
+
+	// Instantiate a local variable of type "DebugMsg", see the file "DebugMsg.msg"
+	// (located in the "msg" folder) to see the full structure of this message.
+	DebugMsg debugMsg;
+
+	// Fill the debugging message with the data provided by Vicon
+	debugMsg.vicon_x = request.ownCrazyflie.x;
+	debugMsg.vicon_y = request.ownCrazyflie.y;
+	debugMsg.vicon_z = request.ownCrazyflie.z;
+	debugMsg.vicon_roll = request.ownCrazyflie.roll;
+	debugMsg.vicon_pitch = request.ownCrazyflie.pitch;
+	debugMsg.vicon_yaw = request.ownCrazyflie.yaw;
+
+	// Fill in the debugging message with any other data you would like to display
+	// in real time. For example, it might be useful to display the thrust
+	// adjustment computed by the z-altitude controller.
+	// The "DebugMsg" type has 10 properties from "value_1" to "value_10", all of
+	// type "float64" that you can fill in with data you would like to plot in
+	// real-time.
+	// debugMsg.value_1 = thrustAdjustment;
+	// ......................
+	// debugMsg.value_10 = your_variable_name;
+
+	// Publish the "debugMsg"
+	m_debugPublisher.publish(debugMsg);
+
+	// An alternate debugging technique is to print out data directly to the
+	// command line from which this node was launched.
+
+	// An example of "printing out" the data from the "request" argument to the
+	// command line. This might be useful for debugging.
+	// ROS_INFO_STREAM("x-coordinates: " << request.ownCrazyflie.x);
+	// ROS_INFO_STREAM("y-coordinates: " << request.ownCrazyflie.y);
+	// ROS_INFO_STREAM("z-coordinates: " << request.ownCrazyflie.z);
+	// ROS_INFO_STREAM("roll: " << request.ownCrazyflie.roll);
+	// ROS_INFO_STREAM("pitch: " << request.ownCrazyflie.pitch);
+	// ROS_INFO_STREAM("yaw: " << request.ownCrazyflie.yaw);
+	// ROS_INFO_STREAM("Delta t: " << request.ownCrazyflie.acquiringTime);
+
+	// An example of "printing out" the control actions computed.
+	// ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
+	// ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
+	// ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
+	// ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
+
+	// An example of "printing out" the "thrust-to-command" conversion parameters.
+	// ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
+	// ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
+	// ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
+
+	// An example of "printing out" the per motor 16-bit command computed.
+	// ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
+	// ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
+	// ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
+	// ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
+
+	// Return "true" to indicate that the control computation was performed successfully
+	return true;
+	}
+
+
+
+
+//    ------------------------------------------------------------------------------
+//    RRRR    OOO   TTTTT    A    TTTTT  EEEEE       III  N   N  TTTTT   OOO
+//    R   R  O   O    T     A A     T    E            I   NN  N    T    O   O
+//    RRRR   O   O    T    A   A    T    EEE          I   N N N    T    O   O
+//    R  R   O   O    T    AAAAA    T    E            I   N  NN    T    O   O
+//    R   R   OOO     T    A   A    T    EEEEE       III  N   N    T     OOO
+//
+//    BBBB    OOO   DDDD   Y   Y       FFFFF  RRRR     A    M   M  EEEEE
+//    B   B  O   O  D   D   Y Y        F      R   R   A A   MM MM  E
+//    BBBB   O   O  D   D    Y         FFF    RRRR   A   A  M M M  EEE
+//    B   B  O   O  D   D    Y         F      R  R   AAAAA  M   M  E
+//    BBBB    OOO   DDDD     Y         F      R   R  A   A  M   M  EEEEE
+//    ----------------------------------------------------------------------------------
+
+// The arguments for this function are as follows:
+// stateInertial
+// This is an array of length 9 with the estimates the error of of the following values
+// relative to the sepcifed setpoint:
+//     stateInertial[0]    x position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[1]    y position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[2]    z position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[3]    x-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[4]    y-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[5]    z-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[6]    The roll  component of the intrinsic Euler angles [radians]
+//     stateInertial[7]    The pitch component of the intrinsic Euler angles [radians]
+//     stateInertial[8]    The yaw   component of the intrinsic Euler angles [radians]
+// 
+// stateBody
+// This is an empty array of length 9, this function should fill in all elements of this
+// array with the same ordering as for the "stateInertial" argument, expect that the (x,y)
+// position and (x,y) velocities are rotated into the body frame.
+//
+// yaw_measured
+// 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
+void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
+{
+
+	float sinYaw = sin(yaw_measured);
+	float cosYaw = cos(yaw_measured);
+
+	// Fill in the (x,y,z) position estimates to be returned
+	stateBody[0] = stateInertial[0] * cosYaw  +  stateInertial[1] * sinYaw;
+	stateBody[1] = stateInertial[1] * cosYaw  -  stateInertial[0] * sinYaw;
+	stateBody[2] = stateInertial[2];
+
+	// Fill in the (x,y,z) velocity estimates to be returned
+	stateBody[3] = stateInertial[3] * cosYaw  +  stateInertial[4] * sinYaw;
+	stateBody[4] = stateInertial[4] * cosYaw  -  stateInertial[3] * sinYaw;
+	stateBody[5] = stateInertial[5];
+
+	// Fill in the (roll,pitch,yaw) estimates to be returned
+	stateBody[6] = stateInertial[6];
+	stateBody[7] = stateInertial[7];
+	stateBody[8] = stateInertial[8];
+}
+
+
+
+
+
+//    ------------------------------------------------------------------------------
+//    N   N  EEEEE  W     W   TTTTT   OOO   N   N        CCCC  M   M  DDDD
+//    NN  N  E      W     W     T    O   O  NN  N       C      MM MM  D   D
+//    N N N  EEE    W     W     T    O   O  N N N  -->  C      M M M  D   D
+//    N  NN  E       W W W      T    O   O  N  NN       C      M   M  D   D
+//    N   N  EEEEE    W W       T     OOO   N   N        CCCC  M   M  DDDD
+//
+//     CCCC   OOO   N   N  V   V  EEEEE  RRRR    SSSS  III   OOO   N   N
+//    C      O   O  NN  N  V   V  E      R   R  S       I   O   O  NN  N
+//    C      O   O  N N N  V   V  EEE    RRRR    SSS    I   O   O  N N N
+//    C      O   O  N  NN   V V   E      R  R       S   I   O   O  N  NN
+//     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
+//    ----------------------------------------------------------------------------------
+
+// This function DOES NEED TO BE edited for successful completion of
+// the exercise
+float computeMotorPolyBackward(float thrust)
+{
+	// Compute the 16-but command that would produce the requested
+	// "thrust" based on the quadratic mapping that is described
+	// by the coefficients in the "yaml_motorPoly" variable.
+	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
+
+	// Saturate the signal to be 0 or in the range [1000,65000]
+	if (cmd_16bit < yaml_command_sixteenbit_min)
+	{
+		cmd_16bit = 0;
+	}
+	else if (cmd_16bit > yaml_command_sixteenbit_max)
+	{
+		cmd_16bit = yaml_command_sixteenbit_max;
+	}
+
+	// Return the result
+	return cmd_16bit;
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    N   N  EEEEE  W     W        SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    NN  N  E      W     W       S      E        T    P   P  O   O   I   NN  N    T
+//    N N N  EEE    W     W        SSS   EEE      T    PPPP   O   O   I   N N N    T
+//    N  NN  E       W W W            S  E        T    P      O   O   I   N  NN    T
+//    N   N  EEEEE    W W         SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     GGG   U   U  III        CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    G   G  U   U   I        C       A A   L      L      B   B   A A   C      K  K
+//    G      U   U   I        C      A   A  L      L      BBBB   A   A  C      KKK
+//    G   G  U   U   I        C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newSetpoint.shouldCheckForAgentID , newSetpoint.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Check if the request if for the default setpoint
+		if (newSetpoint.buttonID == REQUEST_DEFAULT_SETPOINT_BUTTON_ID)
+		{
+			setNewSetpoint(
+					yaml_default_setpoint[0],
+					yaml_default_setpoint[1],
+					yaml_default_setpoint[2],
+					yaml_default_setpoint[3]
+				);
+		}
+		else
+		{
+			// Call the function for actually setting the setpoint
+			setNewSetpoint(
+					newSetpoint.x,
+					newSetpoint.y,
+					newSetpoint.z,
+					newSetpoint.yaw
+				);
+		}
+	}
+}
+
+
+
+void setNewSetpoint(float x, float y, float z, float yaw)
+{
+	// Put the new setpoint into the class variable
+	m_setpoint[0] = x;
+	m_setpoint[1] = y;
+	m_setpoint[2] = z;
+	m_setpoint[3] = yaw;
+
+	// Publish the change so that the netwrok is updated
+	// (mainly the "flying agent GUI" is interested in
+	// displaying this change to the user)
+
+	// Instantiate a local variable of type "SetpointWithHeader"
+	SetpointWithHeader msg;
+	// Fill in the setpoint
+	msg.x   = x;
+	msg.y   = y;
+	msg.z   = z;
+	msg.yaw = yaw;
+	// Publish the message
+	m_setpointChangedPublisher.publish(msg);
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC  U   U   SSSS  TTTTT   OOO   M   M
+//    C      U   U  S        T    O   O  MM MM
+//    C      U   U   SSS     T    O   O  M M M
+//    C      U   U      S    T    O   O  M   M
+//     CCCC   UUU   SSSS     T     OOO   M   M
+//
+//     CCCC   OOO   M   M  M   M    A    N   N  DDDD
+//    C      O   O  MM MM  MM MM   A A   NN  N  D   D
+//    C      O   O  M M M  M M M  A   A  N N N  D   D
+//    C      O   O  M   M  M   M  AAAAA  N  NN  D   D
+//     CCCC   OOO   M   M  M   M  A   A  N   N  DDDD
+//    ----------------------------------------------------------------------------------
+
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButton& commandReceived)
+{
+	// Extract the data from the message
+	int custom_button_index   = commandReceived.button_index;
+	float custom_command_code = commandReceived.command_code;
+
+	// Switch between the button pressed
+	switch(custom_button_index)
+	{
+
+		// > FOR CUSTOM BUTTON 1
+		case 1:
+		{
+			// Let the user know that this part of the code was triggered
+			ROS_INFO("[DEFAULT CONTROLLER] Button 1 received in controller.");
+			// Code here to respond to custom button 1
+			
+			break;
+		}
+
+		// > FOR CUSTOM BUTTON 2
+		case 2:
+		{
+			// Let the user know that this part of the code was triggered
+			ROS_INFO("[DEFAULT CONTROLLER] Button 2 received in controller.");
+			// Code here to respond to custom button 2
+
+			break;
+		}
+
+		// > FOR CUSTOM BUTTON 3
+		case 3:
+		{
+			// Let the user know that this part of the code was triggered
+			ROS_INFO_STREAM("[DEFAULT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
+			// Code here to respond to custom button 3
+
+			break;
+		}
+
+		default:
+		{
+			// Let the user know that the command was not recognised
+			ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
+			break;
+		}
+	}
+}
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
+//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
+//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
+//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
+//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+// This function DOES NOT NEED TO BE edited for successful completion
+// ofthe exercise
+void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
+		{
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[DEFAULT CONTROLLER] Now fetching the DefaultController 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("[DEFAULT CONTROLLER] Now fetching the DefaultController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
+
+			default:
+			{
+				ROS_ERROR("[DEFAULT CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
+		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchDefaultControllerYamlParameters(nodeHandle_to_use);
+	}
+}
+
+
+// This function CAN BE edited for successful completion of the
+// exercise, and the use of parameters fetched from the YAML file
+// is highly recommended to make tuning of your controller easier
+// and quicker.
+void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
+{
+	// Here we load the parameters that are specified in the file:
+	// DefaultController.yaml
+
+	// Add the "DefaultController" namespace to the "nodeHandle"
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "DefaultController");
+
+
+
+	// GET THE PARAMETERS:
+
+	// The mass of the crazyflie, in [grams]
+	yaml_cf_mass_in_grams = getParameterFloat(nodeHandle_for_paramaters , "mass");
+
+	// > The frequency at which the "computeControlOutput" function
+	//   is being called, as determined by the frequency at which
+	//   the Motion Caption (Vicon) system provides pose data, i.e.,
+	//   measurement of (x,y,z) position and (roll,pitch,yaw) attitude.
+	yaml_control_frequency = getParameterFloat(nodeHandle_for_paramaters, "control_frequency");
+
+	// > The co-efficients of the quadratic conversation from 16-bit
+	//   motor command to thrust force in Newtons
+	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", yaml_motorPoly, 3);
+
+	// The min and max for saturating 16 bit thrust commands
+	yaml_command_sixteenbit_min = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_min");
+	yaml_command_sixteenbit_max = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_max");
+
+	// The default setpoint, the ordering is (x,y,z,yaw),
+	// with unit [meters,meters,meters,radians]
+	getParameterFloatVector(nodeHandle_for_paramaters, "default_setpoint", yaml_default_setpoint, 4);
+
+
+
+	// > DEBUGGING: Print out one of the parameters that was loaded to
+	//   debug if the fetching of parameters worked correctly
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] DEBUGGING: the fetched DefaultController/mass = " << yaml_cf_mass_in_grams);
+
+
+
+	// PROCESS THE PARAMTERS
+
+	// > Compute the feed-forward force that we need to counteract
+	//   gravity (i.e., mg) in units of [Newtons]
+	m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81/1000.0;
+
+	// DEBUGGING: Print out one of the computed quantities
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << m_cf_weight_in_newtons);
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M    A    III  N   N
+//    MM MM   A A    I   NN  N
+//    M M M  A   A   I   N N N
+//    M   M  AAAAA   I   N  NN
+//    M   M  A   A  III  N   N
+//    ----------------------------------------------------------------------------------
+
+// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+int main(int argc, char* argv[]) {
+
+	// Starting the ROS-node
+	ros::init(argc, argv, "DefaultControllerService");
+
+	// 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 "DefaultControllerService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
+
+
+
+	// 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
+	//   "PPSClient" node.
+	// > Thus, to get access to this "agentID" paremeter, we first
+	//   need to get a handle to the "PPSClient" 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);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[DEFAULT CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+	}
+
+
+
+	// 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";
+
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+
+
+
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber safeContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "DefaultController", 1, isReadyDefaultControllerYamlCallback);
+	ros::Subscriber safeContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("DefaultController", 1, isReadyDefaultControllerYamlCallback);
+
+
+
+	// GIVE YAML VARIABLES AN INITIAL VALUE
+
+	// This can be done either here or as part of declaring the
+	// variables in the header file
+
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// The yaml files for the controllers are not added to
+	// "Parameter Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// service call containing the filename of the *.yaml file,
+	// and then a message will be received on the above subscribers
+	// when the paramters are ready.
+	// > NOTE IMPORTANTLY that by using a serice client
+	//   we stall the availability of this node until the
+	//   paramter service is ready
+
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyDefaultControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+	// Inform the user
+		ROS_ERROR("[DEFAULT CONTROLLER] The request load yaml file service call failed.");
+	}
+
+
+
+	// PUBLISHERS AND SUBSCRIBERS
+
+	// Instantiate the class variable "m_debugPublisher" to be a
+	// "ros::Publisher". This variable advertises under the name
+	// "DebugTopic" and is a message with the structure defined
+	//  in the file "DebugMsg.msg" (located in the "msg" folder).
+	m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
+
+	// Instantiate the local variable "newSetpointRequestSubscriber" to
+	// be a "ros::Subscriber" type variable that subscribes to the
+	// "NewSetpointRequest" topic and calls the class function
+	// "newSetpointRequestCallback" each time a messaged is received on
+	// this topic and the message is passed as an input argument to the
+	// callback function. This subscriber will mainly receive messages
+	// from the "flying agent GUI" when the setpoint is changed by
+	// the user.
+	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
+
+	// Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+    std::string namespace_to_coordinator;
+    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+    // And now we can instantiate the subscriber:
+	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("DefaultControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
+
+	// Instantiate the class variable "m_setpointChangedPublisher" to
+	// be a "ros::Publisher". This variable advertises under the name
+	// "SetpointChanged" and is a message with the structure defined
+	// in the file "SetpointWithHeader.msg" (located in the "msg" folder).
+	// This publisher is used by the "flying agent GUI" to update the
+	// field that displays the current setpoint for this controller.
+	m_setpointChangedPublisher = nodeHandle.advertise<SetpointWithHeader>("SetpointChanged", 1);
+
+	// Instantiate the local variable "service" to be a "ros::ServiceServer" type
+	// variable that advertises the service called "DefaultController". This service has
+	// the input-output behaviour defined in the "Controller.srv" file (located in the
+	// "srv" folder). This service, when called, is provided with the most recent
+	// measurement of the Crazyflie and is expected to respond with the control action
+	// that should be sent via the Crazyradio and requested from the Crazyflie, i.e.,
+	// this is where the "outer loop" controller function starts. When a request is made
+	// of this service the "calculateControlOutput" function is called.
+	ros::ServiceServer service = nodeHandle.advertiseService("DefaultController", calculateControlOutput);
+
+	// Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
+	// type variable that subscribes to the "GUIButton" topic and calls the class
+	// function "customCommandReceivedCallback" each time a messaged is received on this topic
+	// and the message received is passed as an input argument to the callback function.
+	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
+
+	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
+	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
+	//     "using namespace d_fall_pps;"
+	// in the "DEFINES" section at the top of this file.
+	ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
+	// Print out some information to the user.
+	ROS_INFO("[DEFAULT CONTROLLER] Service ready :-)");
+
+	// Enter an endless while loop to keep the node alive.
+	ros::spin();
+
+	// Return zero if the "ross::spin" is cancelled.
+	return 0;
+}
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 825f8108..917e7fa0 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -74,170 +74,17 @@
 
 
 
-/*
-void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
+bool requestLoadYamlFilenameCallbackServiceCallback(LoadYamlFromFilename::Request &request, LoadYamlFromFilename::Response &response)
 {
-    // Extract from the "msg" for which controller the YAML
-    // parameters should be loaded
-    int controller_to_load_yaml = msg.data;
+    // Put the flying state into the response variable
+    requestLoadYamlFilenamePublisher.publish(request.stringWithHeader);
 
-    ROS_INFO_STREAM("[PARAMETER SERVICE] Received the message to load YAML parameters from file into cache");
+    // Put success into the response
+    response.data = 1;
 
-
-    // Instantiate a local varaible to confirm that something can actually be loaded
-    // from a YAML file
-    bool isValidToAttemptLoad = true;
-
-    // Instantiate a local variable for the string that will be passed to the "system"
-    std::string cmd;
-
-    // Get the abolute path to "d_fall_pps"
-    std::string d_fall_pps_path = ros::package::getPath("d_fall_pps");
-
-    // Switch between loading for the different controllers
-    //    ----------------------------------------
-    // FOR THE SAFE CONTROLLER
-    if (
-        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_SAFE_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the safe controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/SafeController.yaml " + m_base_namespace + "/SafeController";
-    }
-    //    ----------------------------------------
-    // FOR THE DEMO CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_DEMO_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/DemoController.yaml " + m_base_namespace + "/DemoController";
-    }
-    //    ----------------------------------------
-    // FOR THE STUDENT CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_STUDENT_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/StudentController.yaml " + m_base_namespace + "/StudentController";
-    }
-    //    ----------------------------------------
-    // FOR THE MPC CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_MPC_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/MpcController.yaml " + m_base_namespace + "/MpcController";
-    }
-    //    ----------------------------------------
-    // FOR THE REMOTE CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_REMOTE_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/RemoteController.yaml " + m_base_namespace + "/RemoteController";
-    }
-    //    ----------------------------------------
-    // FOR THE TUNING CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_TUNING_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/TuningController.yaml " + m_base_namespace + "/TuningController";
-    }
-    //    ----------------------------------------
-    // FOR THE PICKER CONTROLLER
-    else if (
-        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_COORDINATOR) && (m_type==TYPE_COORDINATOR))
-        ||
-        ((controller_to_load_yaml==LOAD_YAML_PICKER_CONTROLLER_AGENT)       && (m_type==TYPE_AGENT))
-    )
-    {
-        // Re-load the parameters of the demo controller:
-        cmd = "rosparam load " + d_fall_pps_path + "/param/PickerController.yaml " + m_base_namespace + "/PickerController";
-    }
-    else
-    {
-        // Let the user know that the command was not recognised
-        ROS_INFO_STREAM("[PARAMETER SERVICE] > Nothing to load for this parameter service with.");
-        ROS_INFO_STREAM("[PARAMETER SERVICE] > The message received has 'controller_to_load_yaml'   =  " << controller_to_load_yaml);
-        ROS_INFO_STREAM("[PARAMETER SERVICE] > And the type of this Parameter Service is 'm_type'  =  " << m_type);
-        // Set the boolean that prevents the fetch message from being sent
-        isValidToAttemptLoad = false;
-    }
-
-
-    // Only bother with ttempting to loaded the .yaml file, and subseuently send the "ready for fetch"
-    // message if something can actually be loaded from a YAML file
-    if (isValidToAttemptLoad)
-    {
-        // Let the user know what is about to happen
-        ROS_INFO_STREAM("[PARAMETER SERVICE] > The following path will be used for locating the .yaml file: " << d_fall_pps_path  << " The comand line string sent to the 'system' is: " << cmd );
-
-        // Re-load the parameters by pass the command line string via a "system" call
-        // > i.e., this replicates pasting this string in a new terminal window and pressing enter
-        system(cmd.c_str());
-
-        // Pause breifly to ensure that the yaml file is fully loaded
-        ros::Duration(0.5).sleep();
-
-        // Instantiate a local varaible to confirm that something was actually loaded from
-        // a YAML file
-        bool isReadyForFetch = true;
-    
-        // Instantiate a local variable for the fetch message
-        std_msgs::Int32 fetch_msg;
-        // Fill in the data of the fetch message
-        fetch_msg.data = controller_to_load_yaml;
-        // Fill in the data of the fetch message
-        // switch(controller_to_load_yaml)
-        // {
-        //     case (LOAD_YAML_SAFE_CONTROLLER_COORDINATOR):
-        //         fetch_msg.data = FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR;
-        //         break;
-        //     case (LOAD_YAML_DEMO_CONTROLLER_COORDINATOR):
-        //         fetch_msg.data = FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR;
-        //         break;
-        //     case (LOAD_YAML_SAFE_CONTROLLER_AGENT):
-        //         fetch_msg.data = FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT;
-        //         break;
-        //     case (LOAD_YAML_DEMO_CONTROLLER_AGENT):
-        //         fetch_msg.data = FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT;
-        //         break;
-        //     default:
-        //         // Let the user know that the command was not recognised
-        //         ROS_INFO("Unknown 'controller to load yaml' command, thus a 'ready to fetch' message will NOT be published.");
-        //         // Set the boolean that prevents the fetch message from being sent
-        //         isReadyForFetch = false;
-        //         break;
-        // }
-        // Send a message that the YAML parameter have been loaded and hence are
-        // ready to be fetched (i.e., using getparam())
-        if (isReadyForFetch)
-        {
-            controllerYamlReadyForFetchPublisher.publish(fetch_msg);
-        }
-    }
+    // Return
+    return true;
 }
-*/
-
-
 
 void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_load_with_header)
 {
@@ -487,6 +334,12 @@ int main(int argc, char* argv[])
     // Subscribe to the messages that request loading a yaml file
     ros::Subscriber requestLoadYamlFilenameSubscriber = nodeHandle.subscribe("requestLoadYamlFilename", 1, requestLoadYamlFilenameCallback);
 
+    // Publisher for publishing "internally" to the subscriber above
+    requestLoadYamlFilenamePublisher = nodeHandle.advertise <StringWithHeader>("requestLoadYamlFilename", 1);
+
+    // Advertise the service for requests to load a yaml file
+    ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("requestLoadYamlFilename", requestLoadYamlFilenameCallbackServiceCallback);
+
     // Inform the user the this node is ready
     ROS_INFO("[PARAMETER SERVICE] Service ready :-)");
     // Spin as a single-thread node
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index d738c688..12ba738b 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -846,30 +846,38 @@ int main(int argc, char* argv[]) {
 
 	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
-	// The yaml files for the controllers are not added to "Parameter
-	// Service" as part of launching.
+	// The yaml files for the controllers are not added to
+	// "Parameter Service" as part of launching.
 	// The process for loading the yaml parameters is to send a
-	// message containing the filename of the *.yaml file, and
-	// then a message will be received on the above subscribers
+	// service call containing the filename of the *.yaml file,
+	// and then a message will be received on the above subscribers
 	// when the paramters are ready.
-
-	// Create a publisher for request the yaml load
-	// > created as a local variable
-	// > note importantly that the final argument is "true", this
-	//   enables "latching" on the connection. When a connection is 
-	//   latched, the last message published is saved and
-	//   automatically sent to any future subscribers that connect. 
-    ros::Publisher requestLoadYamlFilenamePublisher = nodeHandle_to_own_agent_parameter_service.advertise<StringWithHeader>("requestLoadYamlFilename", 1, true);
-	// Create a local variable for the message
-    StringWithHeader yaml_filename_msg;
-    // Specify the data
-    yaml_filename_msg.data = "StudentController";
-    // Set for whom this applies to
-    yaml_filename_msg.shouldCheckForID = false;
-    // Sleep to make the publisher known to ROS (in seconds)
-    //ros::Duration(1.0).sleep();
-    // Send the message
-    requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+	// > NOTE IMPORTANTLY that by using a serice client
+	//   we stall the availability of this node until the
+	//   paramter service is ready
+
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyStudentControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+	// Inform the user
+		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
+	}
 
 
 
diff --git a/pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv b/pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
new file mode 100644
index 00000000..c3f841a9
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
@@ -0,0 +1,3 @@
+StringWithHeader stringWithHeader
+---
+uint32 data
-- 
GitLab


From 9cb58509a9ab75eb097ef407a76c8966ff764cbd Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 18 Dec 2018 16:32:03 +0100
Subject: [PATCH 26/87] Added menu items to hide show controller tabs and
 buttons. The functions should be genrealised a bit to make adding more
 controllers easier

---
 .../flyingAgentGUI/forms/controllertabs.ui    |  5 +-
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui | 57 ++++++++++++
 .../flyingAgentGUI/include/controllertabs.h   |  6 ++
 .../include/enablecontrollerloadyamlbar.h     |  6 ++
 .../flyingAgentGUI/include/mainwindow.h       |  9 ++
 .../flyingAgentGUI/src/controllertabs.cpp     | 88 ++++++++++++++++++-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  4 +
 .../src/enablecontrollerloadyamlbar.cpp       | 29 ++++++
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  | 32 +++++++
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |  2 +
 10 files changed, 235 insertions(+), 3 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index b847e036..b4718911 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -28,7 +28,10 @@
    <item row="0" column="0">
     <widget class="QTabWidget" name="controller_tabs_widget">
      <property name="currentIndex">
-      <number>2</number>
+      <number>0</number>
+     </property>
+     <property name="movable">
+      <bool>true</bool>
      </property>
      <widget class="QWidget" name="default_tab">
       <attribute name="title">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index 832f4f81..90eb9f73 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -206,8 +206,18 @@
     <addaction name="action_LoadYAML_BatteryMonitor"/>
     <addaction name="action_LoadYAML_ClientConfig"/>
    </widget>
+   <widget class="QMenu" name="menuControllers">
+    <property name="title">
+     <string>Controllers</string>
+    </property>
+    <addaction name="action_showHideController_default"/>
+    <addaction name="action_showHideController_student"/>
+    <addaction name="action_showHideController_picker"/>
+    <addaction name="action_showHideController_safe"/>
+   </widget>
    <addaction name="menuFile"/>
    <addaction name="menuLoad_YAML"/>
+   <addaction name="menuControllers"/>
   </widget>
   <widget class="QToolBar" name="mainToolBar">
    <attribute name="toolBarArea">
@@ -233,6 +243,53 @@
     <string>ClientConfig</string>
    </property>
   </action>
+  <action name="action_showHideController_default">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="enabled">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Default</string>
+   </property>
+  </action>
+  <action name="action_showHideController_student">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Student</string>
+   </property>
+  </action>
+  <action name="action_showHideController_picker">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Picker</string>
+   </property>
+  </action>
+  <action name="action_showHideController_safe">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Safe</string>
+   </property>
+  </action>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <customwidgets>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index a4d11624..9dcd6bbd 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -45,6 +45,12 @@ public:
     explicit ControllerTabs(QWidget *parent = 0);
     ~ControllerTabs();
 
+    // PUBLIC METHODS FOR TOGGLING THE VISISBLE CONTROLLERS
+    void showHideController_default_changed();
+    void showHideController_student_changed();
+    void showHideController_picker_changed();
+    void showHideController_safe_changed();
+
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index d04e939b..a5776823 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -60,6 +60,12 @@ public:
     explicit EnableControllerLoadYamlBar(QWidget *parent = 0);
     ~EnableControllerLoadYamlBar();
 
+    // PUBLIC METHODS FOR TOGGLING THE VISISBLE CONTROLLERS
+    void showHideController_default_changed();
+    void showHideController_student_changed();
+    void showHideController_picker_changed();
+    void showHideController_safe_changed();
+
 
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 5721fffd..d456f45d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -35,6 +35,9 @@
 
 #include <QMainWindow>
 #include <QShortcut>
+#include <QMutex>
+
+#include <QTextStream>
 
 #ifdef CATKIN_MAKE
 #include <ros/ros.h>
@@ -120,6 +123,12 @@ private slots:
     void on_action_LoadYAML_BatteryMonitor_triggered();
     void on_action_LoadYAML_ClientConfig_triggered();
 
+    // FOR THE CONTROLLERS MENU
+    void on_action_showHideController_default_changed();
+    void on_action_showHideController_student_changed();
+    void on_action_showHideController_picker_changed();
+    void on_action_showHideController_safe_changed();
+
 };
 
 #endif // MAINWINDOW_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index d7140128..1c974631 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -89,6 +89,88 @@ ControllerTabs::~ControllerTabs()
 
 
 
+
+void ControllerTabs::showHideController_default_changed()
+{
+    // Get the current index of the tab
+    // > Note the this returns -1 if the tab is not found
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->default_tab);
+
+    // Switch depending on whether the tab was found
+    if (current_index_of_tab < 0)
+    {
+        // Insert the tab
+        ui->controller_tabs_widget->addTab(ui->default_tab,"Default");
+    }
+    else
+    {
+        // Remove the tab
+        ui->controller_tabs_widget->removeTab(current_index_of_tab);
+    }
+}
+
+void ControllerTabs::showHideController_student_changed()
+{
+    // Get the current index of the tab
+    // > Note the this returns -1 if the tab is not found
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->student_tab);
+
+    // Switch depending on whether the tab was found
+    if (current_index_of_tab < 0)
+    {
+        // Insert the tab
+        ui->controller_tabs_widget->addTab(ui->student_tab,"Student");
+    }
+    else
+    {
+        // Remove the tab
+        ui->controller_tabs_widget->removeTab(current_index_of_tab);
+    }
+}
+
+void ControllerTabs::showHideController_picker_changed()
+{
+    // Get the current index of the tab
+    // > Note the this returns -1 if the tab is not found
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->picker_tab);
+
+    // Switch depending on whether the tab was found
+    if (current_index_of_tab < 0)
+    {
+        // Insert the tab
+        ui->controller_tabs_widget->addTab(ui->picker_tab,"Picker");
+    }
+    else
+    {
+        // Remove the tab
+        ui->controller_tabs_widget->removeTab(current_index_of_tab);
+    }
+}
+
+void ControllerTabs::showHideController_safe_changed()
+{
+    // Get the current index of the tab
+    // > Note the this returns -1 if the tab is not found
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->safe_tab);
+
+    // Switch depending on whether the tab was found
+    if (current_index_of_tab < 0)
+    {
+        // Insert the tab
+        ui->controller_tabs_widget->addTab(ui->safe_tab,"Safe");
+    }
+    else
+    {
+        // Remove the tab
+        ui->controller_tabs_widget->removeTab(current_index_of_tab);
+    }
+}
+
+
+
+
+
+
 void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
 {
     if (object_name.isEmpty())
@@ -100,7 +182,9 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
         // Emit a signal to let the tabs know
         emit poseDataUnavailableSignal();
         // Inform the user
-        ROS_INFO("[CONTROLLER TABS GUI] No longer emitting pose data for any object.");
+        #ifdef CATKIN_MAKE
+            ROS_INFO("[CONTROLLER TABS GUI] No longer emitting pose data for any object.");
+        #endif
     }
     else
     {
@@ -264,4 +348,4 @@ bool ControllerTabs::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 702388f2..3f9eb75c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
@@ -644,6 +644,7 @@ void CoordinatorRow::loadCrazyflieContext()
 
 void CoordinatorRow::getCurrentFlyingState()
 {
+#ifdef CATKIN_MAKE
     d_fall_pps::IntIntService getFlyingStateCall;
     getFlyingStateCall.request.data = 0;
     getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
@@ -655,6 +656,7 @@ void CoordinatorRow::getCurrentFlyingState()
     {
         setFlyingState(STATE_UNAVAILABLE);
     }
+#endif
 }
 
 
@@ -662,6 +664,7 @@ void CoordinatorRow::getCurrentFlyingState()
 
 void CoordinatorRow::getCurrentCrazyRadioState()
 {
+#ifdef CATKIN_MAKE
     d_fall_pps::IntIntService getCrazyRadioCall;
     getCrazyRadioCall.request.data = 0;
     getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
@@ -673,6 +676,7 @@ void CoordinatorRow::getCurrentCrazyRadioState()
     {
         setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
     }
+#endif
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 135fab04..5458bcce 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -47,6 +47,35 @@ EnableControllerLoadYamlBar::~EnableControllerLoadYamlBar()
 
 
 
+void EnableControllerLoadYamlBar::showHideController_default_changed()
+{
+    ui->enable_default_button   ->setHidden( !(ui->enable_default_button->isHidden()) );
+    ui->load_yaml_default_button->setHidden( !(ui->load_yaml_default_button->isHidden()) );
+}
+
+void EnableControllerLoadYamlBar::showHideController_student_changed()
+{
+    ui->enable_student_button   ->setHidden( !(ui->enable_student_button->isHidden()) );
+    ui->load_yaml_student_button->setHidden( !(ui->load_yaml_student_button->isHidden()) );
+}
+
+void EnableControllerLoadYamlBar::showHideController_picker_changed()
+{
+    ui->enable_demo_button   ->setHidden(    !(ui->enable_demo_button->isHidden()) );
+    ui->load_yaml_demo_button->setHidden( !(ui->load_yaml_demo_button->isHidden()) );
+}
+
+void EnableControllerLoadYamlBar::showHideController_safe_changed()
+{
+    ui->enable_safe_button   ->setHidden( !(ui->enable_safe_button->isHidden()) );
+    ui->load_yaml_safe_button->setHidden( !(ui->load_yaml_safe_button->isHidden()) );
+}
+
+
+
+
+
+
 // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
 
 void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 58f17f9d..5479a6d6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -199,6 +199,38 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
 
 
 
+void MainWindow::on_action_showHideController_default_changed()
+{
+    // Notify the UI elements of this change
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_default_changed();
+    ui->customWidget_controller_tabs->showHideController_default_changed();
+}
+
+
+void MainWindow::on_action_showHideController_student_changed()
+{
+    // Notify the UI elements of this change
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_student_changed();
+    ui->customWidget_controller_tabs->showHideController_student_changed();
+}
+
+
+void MainWindow::on_action_showHideController_picker_changed()
+{
+    // Notify the UI elements of this change
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_picker_changed();
+    ui->customWidget_controller_tabs->showHideController_picker_changed();
+}
+
+void MainWindow::on_action_showHideController_safe_changed()
+{
+    // Notify the UI elements of this change
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_safe_changed();
+    ui->customWidget_controller_tabs->showHideController_safe_changed();
+}
+
+
+
 //    ----------------------------------------------------------------------------------
 //    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
 //     I   D   D     &           T     Y Y   P   P  E
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index b0e31846..9a77f018 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -154,7 +154,9 @@ void TopBanner::databaseChangedCallback(const std_msgs::Int32& msg)
 void TopBanner::emitObjectNameForDisplayingPoseDataValueChanged()
 {
     emit objectNameForDisplayingPoseDataValueChanged( m_object_name_for_emitting_pose_data );
+#ifdef CATKIN_MAKE
     ROS_INFO_STREAM("[TOP BANNER GUI] Object name \"" << m_object_name_for_emitting_pose_data.toStdString() << "\" emitted for the controller tabs.");
+#endif
 }
 
 
-- 
GitLab


From 31032427be7c93feb7b7ac1c34586bff9609bbcb Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 19 Dec 2018 16:29:43 +0100
Subject: [PATCH 27/87] Added the custom button support to the new GUI, and
 added a get setpoint service. The Default and Student controller tabs are now
 fully integrated for the agent and coordinator mode. Needs testing.

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |    1 +
 .../forms/studentcontrollertab.ui             | 1992 +++++++++--------
 .../flyingAgentGUI/include/controllertabs.h   |    1 +
 .../include/defaultcontrollertab.h            |   10 +
 .../include/studentcontrollertab.h            |   94 +-
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h |    3 +
 .../flyingAgentGUI/src/controllertabs.cpp     |   63 +-
 .../src/defaultcontrollertab.cpp              |  100 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |   12 +
 .../src/studentcontrollertab.cpp              |  877 +++++++-
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |   11 +-
 .../include/nodes/DefaultControllerService.h  |   61 +-
 .../include/nodes/StudentControllerService.h  |   86 +-
 .../d_fall_pps/msg/CustomButtonWithHeader.msg |    7 +
 pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg |    2 +-
 .../src/d_fall_pps/msg/StringWithHeader.msg   |    2 +-
 .../d_fall_pps/param/StudentController.yaml   |    6 +-
 .../src/nodes/DefaultControllerService.cpp    |  144 +-
 .../src/nodes/StudentControllerService.cpp    |  226 +-
 .../src/d_fall_pps/srv/GetSetpointService.srv |    3 +
 20 files changed, 2508 insertions(+), 1193 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
 create mode 100644 pps_ws/src/d_fall_pps/srv/GetSetpointService.srv

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 81579ef9..b2f1ecd6 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -231,6 +231,7 @@ add_service_files(
   CMUpdate.srv
   CMCommand.srv
   LoadYamlFromFilename.srv
+  GetSetpointService.srv
 )
 
 ## Generate actions in the 'action' folder
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index c21c48a5..86fa1a9e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1631</width>
-    <height>760</height>
+    <width>1692</width>
+    <height>931</height>
    </rect>
   </property>
   <property name="font">
@@ -19,1062 +19,1308 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
-   <item row="5" column="3">
-    <widget class="QLineEdit" name="lineEdit_error_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
+   <item row="12" column="0" rowspan="2">
+    <layout class="QGridLayout" name="gridLayout_3">
+     <property name="leftMargin">
+      <number>0</number>
      </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
+     <property name="topMargin">
+      <number>0</number>
      </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
+     <property name="rightMargin">
+      <number>0</number>
      </property>
-     <property name="text">
-      <string>xx.xx</string>
+     <property name="bottomMargin">
+      <number>0</number>
      </property>
-     <property name="readOnly">
-      <bool>true</bool>
+     <property name="horizontalSpacing">
+      <number>20</number>
      </property>
-    </widget>
-   </item>
-   <item row="2" column="7">
-    <layout class="QHBoxLayout" name="horizontalLayout">
-     <item>
-      <widget class="QPushButton" name="x_increment_minus_button">
+     <item row="0" column="1">
+      <widget class="QPushButton" name="custom_button_2">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>-</string>
+        <string>Button 2</string>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+     <item row="0" column="3">
+      <widget class="QPushButton" name="custom_button_4">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
+       <property name="text">
+        <string>Button 4</string>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="x_increment_plus_button">
+     <item row="1" column="0">
+      <widget class="QLineEdit" name="lineEdit_custom_1">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
-       <property name="text">
-        <string>+</string>
-       </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="2" column="6">
-    <spacer name="horizontalSpacer_2">
-     <property name="orientation">
-      <enum>Qt::Horizontal</enum>
-     </property>
-     <property name="sizeType">
-      <enum>QSizePolicy::Fixed</enum>
-     </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>20</width>
-       <height>20</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="5" column="2">
-    <widget class="QLabel" name="label_row_yaw">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>yaw [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="4">
-    <widget class="QLabel" name="label_current_title">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Current</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="1">
-    <widget class="QLabel" name="label_measured_title">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Measured</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="4">
-    <widget class="QPushButton" name="default_setpoint_button">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Default</string>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="2">
-    <widget class="QLabel" name="label_row_y">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>y [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-    </widget>
-   </item>
-   <item row="8" column="2">
-    <widget class="QLabel" name="label_row_roll">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>roll [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="1" column="5">
-    <widget class="QLabel" name="label_new_title_line2">
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="5">
-    <widget class="QLabel" name="label_new_title">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>New</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="7">
-    <layout class="QHBoxLayout" name="horizontalLayout_3">
-     <item>
-      <widget class="QPushButton" name="z_increment_minus_button">
+     <item row="0" column="2">
+      <widget class="QPushButton" name="custom_button_3">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>-</string>
+        <string>Button 3</string>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
+     <item row="0" column="0">
+      <widget class="QPushButton" name="custom_button_1">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
+       <property name="text">
+        <string>Button 1</string>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="z_increment_plus_button">
+     <item row="0" column="5">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="0" column="4">
+      <widget class="QPushButton" name="custom_button_5">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>+</string>
+        <string>Button 5</string>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="2" column="3">
-    <widget class="QLineEdit" name="lineEdit_error_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="3">
-    <widget class="QLineEdit" name="lineEdit_error_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="7">
-    <layout class="QHBoxLayout" name="horizontalLayout_4">
-     <item>
-      <widget class="QPushButton" name="yaw_increment_minus_button">
+     <item row="1" column="1">
+      <widget class="QLineEdit" name="lineEdit_custom_2">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
-       <property name="text">
-        <string>-</string>
-       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+     <item row="1" column="2">
+      <widget class="QLineEdit" name="lineEdit_custom_3">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="yaw_increment_plus_button">
+     <item row="1" column="3">
+      <widget class="QLineEdit" name="lineEdit_custom_4">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>240</width>
          <height>60</height>
         </size>
        </property>
-       <property name="text">
-        <string>+</string>
+      </widget>
+     </item>
+     <item row="1" column="4">
+      <widget class="QLineEdit" name="lineEdit_custom_5">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>240</width>
+         <height>60</height>
+        </size>
        </property>
       </widget>
      </item>
     </layout>
    </item>
-   <item row="3" column="7">
-    <layout class="QHBoxLayout" name="horizontalLayout_2">
-     <item>
-      <widget class="QPushButton" name="y_increment_minus_button">
+   <item row="9" column="0">
+    <layout class="QGridLayout" name="gridLayout_2">
+     <property name="leftMargin">
+      <number>0</number>
+     </property>
+     <property name="topMargin">
+      <number>0</number>
+     </property>
+     <property name="rightMargin">
+      <number>0</number>
+     </property>
+     <property name="bottomMargin">
+      <number>0</number>
+     </property>
+     <item row="0" column="0">
+      <widget class="QLabel" name="label_measured_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Measured</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_x">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_5">
+       <property name="spacing">
+        <number>0</number>
+       </property>
+       <property name="leftMargin">
+        <number>0</number>
+       </property>
+       <property name="topMargin">
+        <number>0</number>
+       </property>
+       <property name="rightMargin">
+        <number>0</number>
+       </property>
+       <property name="bottomMargin">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QFrame" name="red_frame_position_left">
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLabel" name="label_measured_title_line2">
+         <property name="text">
+          <string>Position</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QFrame" name="red_frame_position_right">
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="1">
+      <widget class="QLabel" name="label_row_x">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>x [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="1">
+      <widget class="QLabel" name="label_row_z">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>z [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="1">
+      <widget class="QLabel" name="label_row_yaw">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>-</string>
+        <string>yaw [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
+     <item row="3" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout">
+       <item>
+        <widget class="QPushButton" name="x_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="x_increment_plus_button">
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="5">
+      <spacer name="horizontalSpacer_2">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeType">
+        <enum>QSizePolicy::Fixed</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="3" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_x">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="y_increment_plus_button">
+     <item row="4" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_y">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>+</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="0" column="3">
-    <widget class="QLabel" name="label_error_title">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Error</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="5">
-    <widget class="QPushButton" name="set_setpoint_button">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Set New</string>
-     </property>
-    </widget>
-   </item>
-   <item row="1" column="3">
-    <widget class="QLabel" name="label_error_title_line2">
-     <property name="text">
-      <string>meas-ref</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="8">
-    <spacer name="horizontalSpacer">
-     <property name="orientation">
-      <enum>Qt::Horizontal</enum>
-     </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>40</width>
-       <height>20</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="1" column="7">
-    <widget class="QLabel" name="label">
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="8" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_roll">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_pitch">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="2">
-    <widget class="QLabel" name="label_row_pitch">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>pitch [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="2">
-    <widget class="QLabel" name="label_row_x">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>x [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="1" column="4">
-    <widget class="QLabel" name="label_current_title_2">
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="9" column="1">
-    <spacer name="verticalSpacer">
-     <property name="orientation">
-      <enum>Qt::Vertical</enum>
-     </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>20</width>
-       <height>40</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="5" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="2">
-    <widget class="QLabel" name="label_row_z">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>z [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="4">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="7">
-    <widget class="QLabel" name="label_2">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Increment</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="3">
-    <widget class="QLineEdit" name="lineEdit_error_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="1" column="1">
-    <layout class="QHBoxLayout" name="horizontalLayout_5">
-     <property name="spacing">
-      <number>0</number>
-     </property>
-     <property name="leftMargin">
-      <number>0</number>
-     </property>
-     <property name="topMargin">
-      <number>0</number>
-     </property>
-     <property name="rightMargin">
-      <number>0</number>
-     </property>
-     <property name="bottomMargin">
-      <number>0</number>
-     </property>
-     <item>
-      <widget class="QFrame" name="red_frame_position_left">
+     <item row="4" column="1">
+      <widget class="QLabel" name="label_row_y">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>y [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_pitch">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="8" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_roll">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="0">
+      <widget class="QLineEdit" name="lineEdit_measured_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="1">
+      <widget class="QLabel" name="label_row_pitch">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>pitch [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="8" column="1">
+      <widget class="QLabel" name="label_row_roll">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>roll [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="2">
+      <widget class="QLabel" name="label_error_title_line2">
+       <property name="text">
+        <string>meas-ref</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="3">
+      <widget class="QLabel" name="label_current_title_2">
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="2">
+      <widget class="QLabel" name="label_error_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Error</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="3">
+      <widget class="QPushButton" name="default_setpoint_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Default</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="4">
+      <widget class="QLabel" name="label_new_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>New</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="4">
+      <widget class="QLabel" name="label_new_title_line2">
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="3">
+      <widget class="QLabel" name="label_current_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Current</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
        <property name="maximumSize">
         <size>
-         <width>10</width>
-         <height>16777215</height>
+         <width>180</width>
+         <height>60</height>
         </size>
        </property>
-       <property name="styleSheet">
-        <string notr="true">background-color:red;</string>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
        </property>
-       <property name="frameShape">
-        <enum>QFrame::StyledPanel</enum>
+       <property name="text">
+        <string>xx.xx</string>
        </property>
-       <property name="frameShadow">
-        <enum>QFrame::Raised</enum>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLabel" name="label_measured_title_line2">
+     <item row="0" column="6">
+      <widget class="QLabel" name="label_2">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
        <property name="text">
-        <string>Position</string>
+        <string>Increment</string>
        </property>
        <property name="alignment">
         <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QFrame" name="red_frame_position_right">
+     <item row="6" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="4">
+      <widget class="QPushButton" name="set_setpoint_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Set New</string>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
        <property name="maximumSize">
         <size>
-         <width>10</width>
-         <height>16777215</height>
+         <width>180</width>
+         <height>60</height>
         </size>
        </property>
-       <property name="styleSheet">
-        <string notr="true">background-color:red;</string>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
        </property>
-       <property name="frameShape">
-        <enum>QFrame::StyledPanel</enum>
+      </widget>
+     </item>
+     <item row="1" column="6">
+      <widget class="QLabel" name="label">
+       <property name="text">
+        <string>Setpoint</string>
        </property>
-       <property name="frameShadow">
-        <enum>QFrame::Raised</enum>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
+     <item row="4" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_2">
+       <item>
+        <widget class="QPushButton" name="y_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="y_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="6" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_4">
+       <item>
+        <widget class="QPushButton" name="yaw_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="yaw_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="5" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_3">
+       <item>
+        <widget class="QPushButton" name="z_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="z_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="7">
+      <spacer name="horizontalSpacer_3">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
     </layout>
    </item>
+   <item row="14" column="0">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>40</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="11" column="0">
+    <spacer name="verticalSpacer_2">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeType">
+      <enum>QSizePolicy::Fixed</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>20</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="10" column="0">
+    <widget class="Line" name="line">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+    </widget>
+   </item>
   </layout>
  </widget>
  <resources/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 9dcd6bbd..8cf774a9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -46,6 +46,7 @@ public:
     ~ControllerTabs();
 
     // PUBLIC METHODS FOR TOGGLING THE VISISBLE CONTROLLERS
+    void showHideController_toggle(QString qstr_label, QWidget * tab_widget_to_toggle);
     void showHideController_default_changed();
     void showHideController_student_changed();
     void showHideController_picker_changed();
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 68edb4ea..68763c1d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -20,6 +20,9 @@
 //#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/SetpointWithHeader.h"
 
+// Include the DFALL service types
+#include "d_fall_pps/GetSetpointService.h"
+
 // Include the shared definitions
 #include "nodes/Constants.h"
 
@@ -32,6 +35,8 @@
 
 #endif
 
+
+
 namespace Ui {
 class DefaultControllerTab;
 }
@@ -45,12 +50,14 @@ public:
     ~DefaultControllerTab();
 
 
+
 public slots:
     void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
     void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
     void poseDataUnavailableSlot();
 
 
+
 private slots:
     void on_lineEdit_setpoint_new_x_returnPressed();
     void on_lineEdit_setpoint_new_y_returnPressed();
@@ -70,6 +77,8 @@ private slots:
     void on_yaw_increment_plus_button_clicked();
     void on_yaw_increment_minus_button_clicked();
 
+
+
 private:
     Ui::DefaultControllerTab *ui;
 
@@ -101,6 +110,7 @@ private:
 #endif
 
 
+
     // --------------------------------------------------- //
     // PRIVATE FUNCTIONS
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index c3c57fc1..7baf4930 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -2,6 +2,7 @@
 #define STUDENTCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QMutex>
 #include <QVector>
 #include <QTextStream>
 
@@ -18,6 +19,10 @@
 // Include the DFALL message types
 //#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/CustomButtonWithHeader"
+
+// Include the DFALL service types
+#include "d_fall_pps/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -27,11 +32,12 @@
 
 #else
 // Include the shared definitions
-//#include "include/Constants_for_Qt_compile.h"
+#include "include/Constants_for_Qt_compile.h"
 
 #endif
 
 
+
 namespace Ui {
 class StudentControllerTab;
 }
@@ -45,12 +51,98 @@ public:
     ~StudentControllerTab();
 
 
+
 public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
     void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSlot();
+
+
+
+private slots:
+    void on_lineEdit_setpoint_new_x_returnPressed();
+    void on_lineEdit_setpoint_new_y_returnPressed();
+    void on_lineEdit_setpoint_new_z_returnPressed();
+    void on_lineEdit_setpoint_new_yaw_returnPressed();
+
+    void on_set_setpoint_button_clicked();
+
+    void on_default_setpoint_button_clicked();
+
+    void on_x_increment_plus_button_clicked();
+    void on_x_increment_minus_button_clicked();
+    void on_y_increment_plus_button_clicked();
+    void on_y_increment_minus_button_clicked();
+    void on_z_increment_plus_button_clicked();
+    void on_z_increment_minus_button_clicked();
+    void on_yaw_increment_plus_button_clicked();
+    void on_yaw_increment_minus_button_clicked();
+
+    void on_custom_button_1_clicked();
+    void on_custom_button_2_clicked();
+    void on_custom_button_3_clicked();
+    void on_custom_button_4_clicked();
+    void on_custom_button_5_clicked();
+
 
 
 private:
     Ui::StudentControllerTab *ui;
+
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES
+
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+
+
+#ifdef CATKIN_MAKE
+    // PUBLISHER
+    // > For requesting the setpoint to be changed
+    ros::Publisher requestSetpointChangePublisher;
+
+    // SUBSCRIBER
+    // > For being notified when the setpoint is changed
+    ros::Subscriber setpointChangedSubscriber;
+
+    // PUBLISHER
+    // > For notifying that a custom button is pressed
+    ros::Publisher customButtonPublisher;
+#endif
+
+
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+
+#ifdef CATKIN_MAKE
+    // For receiving message that the setpoint was changed
+    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+
+    // Publish a message when a custom button is pressed
+    void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer);
+
+    // Fill the header for a message
+    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+    void fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg );
+
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
+#endif
+
+    void publishSetpoint(float x, float y, float z, float yaw);
+
 };
 
 #endif // STUDENTCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index e5e76eea..a3cd555c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -131,6 +131,9 @@ private:
 
     // PUBLISHERS AND SUBSRIBERS
 
+    // > For the emergency stop button
+    ros::Publisher emergencyStopPublisher;
+
     // > For changes in the database that defines {agentID,cfID,flying zone} links
     ros::Subscriber databaseChangedSubscriber;
     ros::ServiceClient centralManagerDatabaseService;
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 1c974631..45dfcd9d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -88,19 +88,17 @@ ControllerTabs::~ControllerTabs()
 
 
 
-
-
-void ControllerTabs::showHideController_default_changed()
+void ControllerTabs::showHideController_toggle(QString qstr_label, QWidget * tab_widget_to_toggle)
 {
     // Get the current index of the tab
     // > Note the this returns -1 if the tab is not found
-    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->default_tab);
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(tab_widget_to_toggle);
 
     // Switch depending on whether the tab was found
     if (current_index_of_tab < 0)
     {
         // Insert the tab
-        ui->controller_tabs_widget->addTab(ui->default_tab,"Default");
+        ui->controller_tabs_widget->addTab(tab_widget_to_toggle,qstr_label);
     }
     else
     {
@@ -109,61 +107,26 @@ void ControllerTabs::showHideController_default_changed()
     }
 }
 
-void ControllerTabs::showHideController_student_changed()
+
+
+void ControllerTabs::showHideController_default_changed()
 {
-    // Get the current index of the tab
-    // > Note the this returns -1 if the tab is not found
-    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->student_tab);
+    showHideController_toggle("Default",ui->default_tab);
+}
 
-    // Switch depending on whether the tab was found
-    if (current_index_of_tab < 0)
-    {
-        // Insert the tab
-        ui->controller_tabs_widget->addTab(ui->student_tab,"Student");
-    }
-    else
-    {
-        // Remove the tab
-        ui->controller_tabs_widget->removeTab(current_index_of_tab);
-    }
+void ControllerTabs::showHideController_student_changed()
+{
+    showHideController_toggle("Student",ui->student_tab);
 }
 
 void ControllerTabs::showHideController_picker_changed()
 {
-    // Get the current index of the tab
-    // > Note the this returns -1 if the tab is not found
-    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->picker_tab);
-
-    // Switch depending on whether the tab was found
-    if (current_index_of_tab < 0)
-    {
-        // Insert the tab
-        ui->controller_tabs_widget->addTab(ui->picker_tab,"Picker");
-    }
-    else
-    {
-        // Remove the tab
-        ui->controller_tabs_widget->removeTab(current_index_of_tab);
-    }
+    showHideController_toggle("Picker",ui->picker_tab);
 }
 
 void ControllerTabs::showHideController_safe_changed()
 {
-    // Get the current index of the tab
-    // > Note the this returns -1 if the tab is not found
-    int current_index_of_tab = ui->controller_tabs_widget->indexOf(ui->safe_tab);
-
-    // Switch depending on whether the tab was found
-    if (current_index_of_tab < 0)
-    {
-        // Insert the tab
-        ui->controller_tabs_widget->addTab(ui->safe_tab,"Safe");
-    }
-    else
-    {
-        // Remove the tab
-        ui->controller_tabs_widget->removeTab(current_index_of_tab);
-    }
+    showHideController_toggle("Safe",ui->safe_tab);
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 147a43ba..7f503464 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -56,6 +56,18 @@ DefaultControllerTab::~DefaultControllerTab()
 }
 
 
+
+
+
+//    ----------------------------------------------------------------------------------
+//    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
+//    P   P  O   O  S      E         D   D   A A     T     A A
+//    PPPP   O   O   SSS   EEE       D   D  A   A    T    A   A
+//    P      O   O      S  E         D   D  AAAAA    T    AAAAA
+//    P       OOO   SSSS   EEEEE     DDDD   A   A    T    A   A
+//    ----------------------------------------------------------------------------------
+
+
 void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
 {
     if (!occluded)
@@ -264,7 +276,7 @@ void DefaultControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed()
 
 void DefaultControllerTab::on_set_setpoint_button_clicked()
 {
-#ifdef CATKIN_MAKE
+
     // Initialise local variable for each of (x,y,z,yaw)
     float x = 0.0f, y = 0.0f, z = 0.0f, yaw = 0.0f;
 
@@ -290,9 +302,9 @@ void DefaultControllerTab::on_set_setpoint_button_clicked()
     else
         yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
+#ifdef CATKIN_MAKE
     // Call the function to publish the setpoint
     publishSetpoint(x,y,z,yaw);
-
 #else
     // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
     QTextStream(stdout) << "[DEFAULT CONTROLLER TAB] set setpoint button clicked";
@@ -324,7 +336,6 @@ void DefaultControllerTab::on_default_setpoint_button_clicked()
 
 void DefaultControllerTab::on_x_increment_plus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
     {
@@ -338,16 +349,17 @@ void DefaultControllerTab::on_x_increment_plus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
 
     }
-#endif
 }
 
 void DefaultControllerTab::on_x_increment_minus_button_clicked()
 {
-#ifdef CATKIN_MAKE
+
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
     {
@@ -361,16 +373,15 @@ void DefaultControllerTab::on_x_increment_minus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 void DefaultControllerTab::on_y_increment_plus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
     {
@@ -384,16 +395,15 @@ void DefaultControllerTab::on_y_increment_plus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 void DefaultControllerTab::on_y_increment_minus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
     {
@@ -407,16 +417,15 @@ void DefaultControllerTab::on_y_increment_minus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 void DefaultControllerTab::on_z_increment_plus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
     {
@@ -430,16 +439,15 @@ void DefaultControllerTab::on_z_increment_plus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 void DefaultControllerTab::on_z_increment_minus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
     {
@@ -453,16 +461,15 @@ void DefaultControllerTab::on_z_increment_minus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 void DefaultControllerTab::on_yaw_increment_plus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
     {
@@ -476,15 +483,14 @@ void DefaultControllerTab::on_yaw_increment_plus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 void DefaultControllerTab::on_yaw_increment_minus_button_clicked()
 {
-#ifdef CATKIN_MAKE
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
     {
@@ -498,11 +504,11 @@ void DefaultControllerTab::on_yaw_increment_minus_button_clicked()
     }
     else
     {
+        #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
         ROS_INFO_STREAM("[DEFAULT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
-
+        #endif
     }
-#endif
 }
 
 
@@ -549,34 +555,20 @@ void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
-        // // > Request the current flying state
-        // ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
-        // d_fall_pps::IntIntService getFlyingStateCall;
-        // getFlyingStateCall.request.data = 0;
-        // getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
-        // if(getCurrentFlyingStateService.call(getFlyingStateCall))
-        // {
-        //     setFlyingState(getFlyingStateCall.response.data);
-        // }
-        // else
-        // {
-        //     setFlyingState(STATE_UNAVAILABLE);
-        // }
-
-        // // > Request the current status of the crazy radio
-        // ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
-        // d_fall_pps::IntIntService getCrazyRadioCall;
-        // getCrazyRadioCall.request.data = 0;
-        // getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
-        // if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
-        // {
-        //     setCrazyRadioStatus(getCrazyRadioCall.response.data);
-        // }
-        // else
-        // {
-        //     setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
-        // }
-
+        // // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("DefaultControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[DEFAULT CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
 
         // SUBSCRIBERS
         // > For receiving message that the setpoint was changed
@@ -753,4 +745,4 @@ bool DefaultControllerTab::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
+#endif
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 5479a6d6..f9173ae6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -132,6 +132,18 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
             ui->customWidget_controller_tabs , &ControllerTabs::setObjectNameForDisplayingPoseData
             );
 
+
+    // TOGGLE THE CONTROLLERS THAT ARE VISIBLE
+    // By default all controller buttons and tabs are visible
+    // and the menu item is checked. Hence, to hide a controller
+    // the menu item simply needs to be "triggered"
+
+    // > For the picker controller
+    ui->action_showHideController_picker->trigger();
+    // > For the safe controller
+    ui->action_showHideController_safe->trigger();
+
+
 }
 
 MainWindow::~MainWindow()
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index 9cb9fe7b..77a93f53 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -6,6 +6,51 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
     ui(new Ui::StudentControllerTab)
 {
     ui->setupUi(this);
+
+    // Hide the two red frames that are used to indcated
+    // when pose data is occluded
+    ui->red_frame_position_left->setVisible(false);
+    ui->red_frame_position_right->setVisible(false);
+
+
+
+#ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[STUDENT CONTROLLER TAB GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[STUDENT CONTROLLER TAB GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("StudentControllerService/RequestSetpointChange", 1);
+
+    // SUBSCRIBE TO SETPOINT CHANGES
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("StudentControllerService/SetpointChanged", 1, &StudentControllerTab::setpointChangedCallback, this);
+    }
+
+    // CREATE THE CUSTOM BUTTON PRESSED PUBLISHED
+    customButtonPublisher = nodeHandle_for_this_gui.advertise<CustomButton>("StudentControllerService/CustomButtonPressed", 1);
+
+#endif
+
 }
 
 StudentControllerTab::~StudentControllerTab()
@@ -13,28 +58,832 @@ StudentControllerTab::~StudentControllerTab()
     delete ui;
 }
 
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC  U   U   SSSS  TTTTT   OOO   M   M
+//    C      U   U  S        T    O   O  MM MM
+//    C      U   U   SSS     T    O   O  M M M
+//    C      U   U      S    T    O   O  M   M
+//     CCCC   UUU   SSSS     T     OOO   M   M
+//
+//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
+//    B   B  U   U    T      T    O   O  NN  N  S
+//    BBBB   U   U    T      T    O   O  N N N   SSS
+//    B   B  U   U    T      T    O   O  N  NN      S
+//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void StudentControllerTab::publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer)
+{
+    // Initialise the message as a local variable
+    d_fall_pps::CustomButtonWithHeader msg;
+    // Fill the header of the message
+    fillCustomButtonMessageHeader( msg );
+    // Fill in the button index
+    msg.button_index = button_index;
+    // Get the line edit data, as a float if possible
+    bool isFloat = false;
+    float lineEdit_as_float = (lineEdit_pointer->text()).toFloat(isFloat);
+    // Fill in the data
+    if (isFloat)
+        msg.float_data = lineEdit_as_float;
+    else
+        msg.string_data = (lineEdit_pointer->text()).toStdString();
+    // Publish the setpoint
+    this->customButtonPublisher.publish(msg);
+    // Inform the user about the change
+    ROS_INFO_STREAM("[STUDENT CONTROLLER TAB GUI] button " << button_index << " clicked.");
+}
+#endif
+
+
+void StudentControllerTab::on_custom_button_1_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    d_fall_pps::CustomButtonWithHeader msg;
+    // Fill the header of the message
+    fillCustomButtonMessageHeader( msg );
+    // Fill in the button index
+    msg.button_index = 1;
+    // Get the line edit data, as a float if possible
+    bool isFloat = false;
+    float lineEdit_as_float = (ui->lineEdit_custom_1->text()).toFloat(isFloat);
+    // Fill in the data
+    if (isFloat)
+        msg.float_data = lineEdit_as_float;
+    else
+        msg.string_data = (ui->lineEdit_custom_1->text()).toStdString();
+    // Publish the setpoint
+    this->customButtonPublisher.publish(msg);
+    // Inform the user about the change
+    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 1 clicked.");
+#endif
+}
+
+void StudentControllerTab::on_custom_button_2_clicked()
+{
+#ifdef CATKIN_MAKE
+    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 2 clicked.");
+#endif
+}
+
+void StudentControllerTab::on_custom_button_3_clicked()
+{
+#ifdef CATKIN_MAKE
+    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 3 clicked.");
+#endif
+}
+
+void StudentControllerTab::on_custom_button_4_clicked()
+{
+#ifdef CATKIN_MAKE
+    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 4 clicked.");
+#endif
+}
+
+void StudentControllerTab::on_custom_button_5_clicked()
+{
+#ifdef CATKIN_MAKE
+    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 5 clicked.");
+#endif
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
+//    P   P  O   O  S      E         D   D   A A     T     A A
+//    PPPP   O   O   SSS   EEE       D   D  A   A    T    A   A
+//    P      O   O      S  E         D   D  AAAAA    T    AAAAA
+//    P       OOO   SSSS   EEEEE     DDDD   A   A    T    A   A
+//    ----------------------------------------------------------------------------------
+
+
 void StudentControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
 {
     if (!occluded)
     {
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+        QString qstr = "";
         // UPDATE THE MEASUREMENT COLUMN
-        ui->lineEdit_measured_x    ->setText(QString::number( x     ));
-        ui->lineEdit_measured_y    ->setText(QString::number( y     ));
-        ui->lineEdit_measured_z    ->setText(QString::number( z     ));
-        ui->lineEdit_measured_roll ->setText(QString::number( roll  ));
-        ui->lineEdit_measured_pitch->setText(QString::number( pitch ));
-        ui->lineEdit_measured_yaw  ->setText(QString::number( yaw   ));
+        if (x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', 3));
+        if (y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', 3));
+        if (z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
+
+        if (roll < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        if (pitch < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
+        if (yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
 
         // GET THE CURRENT SETPOINT
-        float curr_x_setpoint   = (ui->lineEdit_setpoint_current_x->text()  ).toFloat();;
-        float curr_y_setpoint   = (ui->lineEdit_setpoint_current_y->text()  ).toFloat();;
-        float curr_z_setpoint   = (ui->lineEdit_setpoint_current_z->text()  ).toFloat();;
-        float curr_yaw_setpoint = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();;
+        float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
+        float error_y   = y   - (ui->lineEdit_setpoint_current_y->text()  ).toFloat();
+        float error_z   = z   - (ui->lineEdit_setpoint_current_z->text()  ).toFloat();
+        float error_yaw = yaw - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
         // UPDATE THE ERROR COLUMN
-        ui->lineEdit_error_x  ->setText(QString::number( x   - curr_x_setpoint   ));
-        ui->lineEdit_error_y  ->setText(QString::number( y   - curr_y_setpoint   ));
-        ui->lineEdit_error_z  ->setText(QString::number( z   - curr_z_setpoint   ));
-        ui->lineEdit_error_yaw->setText(QString::number( yaw - curr_yaw_setpoint ));
+        if (error_x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_x->setText(qstr + QString::number( error_x, 'f', 3));
+        if (error_y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_y->setText(qstr + QString::number( error_y, 'f', 3));
+        if (error_z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', 3));
+
+        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+
+        // Ensure the red frames are not visible
+        if ( ui->red_frame_position_left->isVisible() )
+            ui->red_frame_position_left->setVisible(false);
+        if ( ui->red_frame_position_right->isVisible() )
+            ui->red_frame_position_right->setVisible(false);
+    }
+    else
+    {
+        // Make visible the red frames to indicate occluded
+        if ( !(ui->red_frame_position_left->isVisible()) )
+            ui->red_frame_position_left->setVisible(true);
+        if ( !(ui->red_frame_position_right->isVisible()) )
+            ui->red_frame_position_right->setVisible(true);
     }
 }
+
+
+void StudentControllerTab::poseDataUnavailableSlot()
+{
+    ui->lineEdit_measured_x->setText("xx.xx");
+    ui->lineEdit_measured_y->setText("xx.xx");
+    ui->lineEdit_measured_z->setText("xx.xx");
+
+    ui->lineEdit_measured_roll->setText("xx.xx");
+    ui->lineEdit_measured_pitch->setText("xx.xx");
+    ui->lineEdit_measured_yaw->setText("xx.xx");
+
+    ui->lineEdit_error_x->setText("xx.xx");
+    ui->lineEdit_error_y->setText("xx.xx");
+    ui->lineEdit_error_z->setText("xx.xx");
+    ui->lineEdit_error_yaw->setText("xx.xx");
+
+
+}
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC  H   H    A    N   N   GGGG  EEEEE  DDDD
+//    C      H   H   A A   NN  N  G      E      D   D
+//    C      HHHHH  A   A  N N N  G      EEE    D   D
+//    C      H   H  AAAAA  N  NN  G   G  E      D   D
+//     CCCC  H   H  A   A  N   N   GGGG  EEEEE  DDDD
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void StudentControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+{
+    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+    QString qstr = "";
+
+    // EXTRACT THE SETPOINT
+    float x = newSetpoint.x;
+    float y = newSetpoint.y;
+    float z = newSetpoint.z;
+    float yaw = newSetpoint.yaw;
+
+    // UPDATE THE SETPOINT COLUMN
+    if (x < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_x->setText(qstr + QString::number( x, 'f', 3));
+    if (y < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_y->setText(qstr + QString::number( y, 'f', 3));
+    if (z < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3));
+
+    if (yaw < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 3));
+}
+#endif
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    RRRR   EEEEE   QQQ   U   U  EEEEE   SSSS  TTTTT     N   N  EEEEE  W     W
+//    R   R  E      Q   Q  U   U  E      S        T       NN  N  E      W     W
+//    RRRR   EEE    Q   Q  U   U  EEE     SSS     T       N N N  EEE    W     W 
+//    R   R  E      Q  Q   U   U  E          S    T       N  NN  E       W W W
+//    R   R  EEEEE   QQ Q   UUU   EEEEE  SSSS     T       N   N  EEEEE    W W
+//
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//    ----------------------------------------------------------------------------------
+
+
+void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw)
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    d_fall_pps::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.x   = x;
+    msg.y   = y;
+    msg.z   = z;
+    msg.yaw = yaw * DEG2RAD;
+
+    // Publish the setpoint
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[STUDENT CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]";
+#endif
+}
+
+
+
+void StudentControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+
+#ifdef CATKIN_MAKE
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[STUDENT CONTROLLER TAB] return pressed for x setpoint";
+#endif
+}
+
+void StudentControllerTab::on_lineEdit_setpoint_new_y_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void StudentControllerTab::on_lineEdit_setpoint_new_z_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void StudentControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void StudentControllerTab::on_set_setpoint_button_clicked()
+{
+
+    // Initialise local variable for each of (x,y,z,yaw)
+    float x = 0.0f, y = 0.0f, z = 0.0f, yaw = 0.0f;
+
+    // Take the new value if available, otherwise use the old value
+    // > For x
+    if(!ui->lineEdit_setpoint_new_x->text().isEmpty())
+        x = (ui->lineEdit_setpoint_new_x->text()).toFloat();
+    else
+        x = (ui->lineEdit_setpoint_current_x->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
+        y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
+    else
+        y = (ui->lineEdit_setpoint_current_y->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
+        z = (ui->lineEdit_setpoint_new_z->text()).toFloat();
+    else
+        z = (ui->lineEdit_setpoint_current_z->text()).toFloat();
+    // > For x
+    if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty())
+        yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat();
+    else
+        yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+#ifdef CATKIN_MAKE
+    // Call the function to publish the setpoint
+    publishSetpoint(x,y,z,yaw);
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[STUDENT CONTROLLER TAB] set setpoint button clicked";
+#endif
+}
+
+void StudentControllerTab::on_default_setpoint_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Publish this as a blank setpoint with the 
+    // "buttonID" field set appropriately
+
+    // Initialise the message as a local variable
+    d_fall_pps::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.buttonID = REQUEST_DEFAULT_SETPOINT_BUTTON_ID;
+
+    // Publish the default setpoint button press
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Published request for setpoint change to the default");
+#endif
+}
+
+void StudentControllerTab::on_x_increment_plus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[Student CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+
+    }
+}
+
+void StudentControllerTab::on_x_increment_minus_button_clicked()
+{
+
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+void StudentControllerTab::on_y_increment_plus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+void StudentControllerTab::on_y_increment_minus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+void StudentControllerTab::on_z_increment_plus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+void StudentControllerTab::on_z_increment_minus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+void StudentControllerTab::on_yaw_increment_plus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+void StudentControllerTab::on_yaw_increment_minus_button_clicked()
+{
+    // Only need to do something if the field is not empty
+    if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
+    {
+        // Call the function to publish the setpoint
+        publishSetpoint(
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() - (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
+            );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void StudentControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("StudentControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[STUDENT CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+
+        // SUBSCRIBERS
+        // > For receiving message that the setpoint was changed
+        setpointChangedSubscriber = agent_base_nodeHandle.subscribe("StudentControllerService/SetpointChanged", 1, &StudentControllerTab::setpointChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        setpointChangedSubscriber.shutdown();
+
+        // Set information back to the default
+        ui->lineEdit_setpoint_current_x->setText("xx.xx");
+        ui->lineEdit_setpoint_current_y->setText("xx.xx");
+        ui->lineEdit_setpoint_current_z->setText("xx.xx");
+        ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
+
+    }
+#endif
+}
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void StudentControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[STUDENT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[STUDENT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    } 
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool StudentControllerTab::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[STUDENT CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[STUDENT CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[STUDENT CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[STUDENT CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[STUDENT CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[STUDENT CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[STUDENT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 9a77f018..4f63bbd0 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -92,6 +92,9 @@ TopBanner::TopBanner(QWidget *parent) :
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
+    // > Publisher for the emergency stop button
+    emergencyStopPublisher = dfall_root_nodeHandle.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
+
 	// > For changes in the database that defines {agentID,cfID,flying zone} links
 	databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
 	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
@@ -245,10 +248,10 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
 void TopBanner::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    // d_fall_pps::IntWithHeader msg;
-    // fillIntMessageHeader(msg);
-    // msg.data = CMD_RECONNECT;
-    // this->crazyRadioCommandPublisher.publish(msg);
+    d_fall_pps::IntWithHeader msg;
+    msg.shouldCheckIDs = false;
+    msg.data = CMD_CRAZYFLY_MOTORS_OFF;
+    this->emergencyStopPublisher.publish(msg);
     ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
 #endif
 }
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
index b88fa8e2..612f266d 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
@@ -57,17 +57,18 @@
 
 // Include the DFALL message types
 #include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/StringWithHeader.h"
+//#include "d_fall_pps/StringWithHeader.h"
 #include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/CustomButtonWithHeader.h"
 #include "d_fall_pps/ViconData.h"
 #include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
 
 // Include the DFALL service types
 #include "d_fall_pps/LoadYamlFromFilename.h"
+#include "d_fall_pps/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -129,22 +130,23 @@ std::string m_namespace_to_coordinator_parameter_service;
 
 
 
-// The mass of the crazyflie, in [grams]
+// VARAIBLES FOR VALUES LOADED FROM THE YAML FILE
+// > the mass of the crazyflie, in [grams]
 float yaml_cf_mass_in_grams = 25.0;
 
-// Coefficients of the 16-bit command to thrust conversion
+// > the coefficients of the 16-bit command to thrust conversion
 //std::vector<float> yaml_motorPoly(3);
 std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
 
-// Frequency at which the controller is running
+// > the frequency at which the controller is running
 float yaml_control_frequency = 200.0;
 
-// The min and max for saturating 16 bit thrust commands
+// > the min and max for saturating 16 bit thrust commands
 float yaml_command_sixteenbit_min = 1000;
 float yaml_command_sixteenbit_max = 65000;
 
-// The default setpoint, the ordering is (x,y,z,yaw),
-// with unit [meters,meters,meters,radians]
+// > the default setpoint, the ordering is (x,y,z,yaw),
+//   with units [meters,meters,meters,radians]
 std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
 
 
@@ -155,7 +157,9 @@ float m_cf_weight_in_newtons = 0.0;
 // The location error of the Crazyflie at the "previous" time step
 float m_previous_stateErrorInertial[9];
 
-std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
+// The setpoint to be tracked, the ordering is (x,y,z,yaw),
+// with units [meters,meters,meters,radians]
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
 
 
 // The LQR Controller parameters for "LQR_RATE_MODE"
@@ -174,22 +178,6 @@ ros::Publisher m_setpointChangedPublisher;
 
 
 
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
-
-
 
 
 //    ----------------------------------------------------------------------------------
@@ -206,17 +194,18 @@ ros::Publisher m_setpointChangedPublisher;
 //    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
-// These function prototypes are not strictly required for this code to
-// complile, but adding the function prototypes here means the the functions
-// can be written below in any order. If the function prototypes are not
-// included then the function need to written below in an order that ensure
-// each function is implemented before it is called from another function,
-// hence why the "main" function is at the bottom.
+// These function prototypes are not strictly required for this code
+// to complile, but adding the function prototypes here means the
+// functions can be written in any order in the ".cpp" file.
+// (If the function prototypes are not included then the functions
+// need to written below in an order that ensure each function is
+// implemented before it is called from another function)
 
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
-// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR INTO AN (x,y) BODY FRAME ERROR
+// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR
+// INTO AN (x,y) BODY FRAME ERROR
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured);
 
 // CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
@@ -228,10 +217,12 @@ void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
 // CHANGE SETPOINT FUNCTION
 void setNewSetpoint(float x, float y, float z, float yaw);
 
-// CUSTOM COMMAND RECEIVED CALLBACK
-void customCommandReceivedCallback(const CustomButton& commandReceived);
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
 
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
-// > For the LOADING of YAML PARAMETERS
+// LOADING OF YAML PARAMETERS
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg);
 void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 7d440b25..42276a73 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -57,16 +57,18 @@
 
 // Include the DFALL message types
 #include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/StringWithHeader.h"
+//#include "d_fall_pps/StringWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/CustomButtonWithHeader.h"
 #include "d_fall_pps/ViconData.h"
 #include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
 
 // Include the DFALL service types
 #include "d_fall_pps/LoadYamlFromFilename.h"
+#include "d_fall_pps/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -158,16 +160,32 @@ std::string m_namespace_to_coordinator_parameter_service;
 
 
 
+// VARAIBLES FOR VALUES LOADED FROM THE YAML FILE
+// > the mass of the crazyflie, in [grams]
+float yaml_cf_mass_in_grams = 25.0;
 
-// Variables for controller
-float yaml_cf_mass_in_grams = 25.0;         // Crazyflie mass in grams
-std::vector<float> yaml_motorPoly(3);       // Coefficients of the 16-bit command to thrust conversion
-float yaml_control_frequency = 200.0;       // Frequency at which the controller is running
-float m_cf_weight_in_newtons = 0.0;      // The weight of the Crazyflie in Newtons, i.e., mg
+// > the coefficients of the 16-bit command to thrust conversion
+//std::vector<float> yaml_motorPoly(3);
+std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
 
-float m_previous_stateErrorInertial[9];  // The location error of the Crazyflie at the "previous" time step
+// > the frequency at which the controller is running
+float yaml_control_frequency = 200.0;
 
-std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};     // The setpoints for (x,y,z) position and yaw angle, in that order
+// > the default setpoint, the ordering is (x,y,z,yaw),
+//   with units [meters,meters,meters,radians]
+std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
+
+
+
+// The weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = 0.0;
+
+// The location error of the Crazyflie at the "previous" time step
+float m_previous_stateErrorInertial[9];
+
+// The setpoint to be tracked, the ordering is (x,y,z,yaw),
+// with units [meters,meters,meters,radians]
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
 
 
 // The LQR Controller parameters for "LQR_RATE_MODE"
@@ -180,21 +198,9 @@ std::vector<float> m_gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.
 // ROS Publisher for debugging variables
 ros::Publisher m_debugPublisher;
 
-
-
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+// ROS Publisher for inform the network about
+// changes to the setpoin
+ros::Publisher m_setpointChangedPublisher;
 
 
 
@@ -224,33 +230,25 @@ ros::Publisher m_debugPublisher;
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
-// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR INTO AN (x,y) BODY FRAME ERROR
+// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR
+// INTO AN (x,y) BODY FRAME ERROR
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured);
 
 // CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
 float computeMotorPolyBackward(float thrust);
 
-// SETPOINT CHANGE CALLBACK
-void setpointCallback(const Setpoint& newSetpoint);
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
 
-// CUSTOM COMMAND RECEIVED CALLBACK
-void customCommandReceivedCallback(const CustomButton& commandReceived);
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw);
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
 
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
 // > For the LOADING of YAML PARAMETERS
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg);
-void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle);
-
-
-// LOAD PARAMETERS
-//float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-//void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-//int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-//void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-//int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-//bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-
-//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-//void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-//void processFetchedParameters();
-//void customYAMLasMessageCallback(const CustomControllerYAML& newCustomControllerParameters);
\ No newline at end of file
+void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg b/pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
new file mode 100644
index 00000000..87fbf0fc
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
@@ -0,0 +1,7 @@
+uint32 button_index
+bool bool_data
+int32 int_data
+float64 float_data
+string string_data
+bool shouldCheckForAgentID
+uint32[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg b/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
index a5802e7e..cc51997e 100755
--- a/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
+++ b/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
@@ -1,3 +1,3 @@
 float32 data
 bool shouldCheckForID
-uint8[] agentIDs
\ No newline at end of file
+uint32[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg b/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
index 97b64956..8a93139a 100755
--- a/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
+++ b/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
@@ -1,3 +1,3 @@
 string data
 bool shouldCheckForID
-uint8[] agentIDs
\ No newline at end of file
+uint32[] agentIDs
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/param/StudentController.yaml b/pps_ws/src/d_fall_pps/param/StudentController.yaml
index 7dbb3ec7..737fea73 100644
--- a/pps_ws/src/d_fall_pps/param/StudentController.yaml
+++ b/pps_ws/src/d_fall_pps/param/StudentController.yaml
@@ -5,4 +5,8 @@ mass : 28
 control_frequency : 200
 
 # Quadratic motor regression equation (a0, a1, a2)
-motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
\ No newline at end of file
+motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
+
+# The default setpoint, the ordering is (x,y,z,yaw),
+# with unit [meters,meters,meters,radians]
+default_setpoint : [0.0, 0.0, 0.4, 0.0]
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
index fe37b42c..81807850 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
@@ -499,14 +499,15 @@ float computeMotorPolyBackward(float thrust)
 //    N  NN  E       W W W            S  E        T    P      O   O   I   N  NN    T
 //    N   N  EEEEE    W W         SSSS   EEEEE    T    P       OOO   III  N   N    T
 //
-//     GGG   U   U  III        CCCC    A    L      L      BBBB     A     CCCC  K   K
-//    G   G  U   U   I        C       A A   L      L      B   B   A A   C      K  K
-//    G      U   U   I        C      A   A  L      L      BBBB   A   A  C      KKK
-//    G   G  U   U   I        C      AAAAA  L      L      B   B  AAAAA  C      K  K
-//     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
 //    ----------------------------------------------------------------------------------
 
 
+// REQUEST SETPOINT CHANGE CALLBACK
 void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
 {
 	// Check whether the message is relevant
@@ -540,6 +541,7 @@ void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
 
 
 
+// CHANGE SETPOINT FUNCTION
 void setNewSetpoint(float x, float y, float z, float yaw)
 {
 	// Put the new setpoint into the class variable
@@ -548,7 +550,7 @@ void setNewSetpoint(float x, float y, float z, float yaw)
 	m_setpoint[2] = z;
 	m_setpoint[3] = yaw;
 
-	// Publish the change so that the netwrok is updated
+	// Publish the change so that the network is updated
 	// (mainly the "flying agent GUI" is interested in
 	// displaying this change to the user)
 
@@ -564,6 +566,19 @@ void setNewSetpoint(float x, float y, float z, float yaw)
 }
 
 
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response)
+{
+	// Directly put the current setpoint into the response
+	response.setpointWithHeader.x   = m_setpoint[0];
+	response.setpointWithHeader.y   = m_setpoint[1];
+	response.setpointWithHeader.z   = m_setpoint[2];
+	response.setpointWithHeader.yaw = m_setpoint[3];
+	// Return
+	return true;
+}
+
+
 
 
 
@@ -582,51 +597,57 @@ void setNewSetpoint(float x, float y, float z, float yaw)
 //    ----------------------------------------------------------------------------------
 
 // CUSTOM COMMAND RECEIVED CALLBACK
-void customCommandReceivedCallback(const CustomButton& commandReceived)
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived)
 {
-	// Extract the data from the message
-	int custom_button_index   = commandReceived.button_index;
-	float custom_command_code = commandReceived.command_code;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , commandReceived.shouldCheckForAgentID , commandReceived.agentIDs );
 
-	// Switch between the button pressed
-	switch(custom_button_index)
+	if (isRevelant)
 	{
+		// Extract the data from the message
+		int custom_button_index   = commandReceived.button_index;
+		float custom_command_code = commandReceived.float_data;
 
-		// > FOR CUSTOM BUTTON 1
-		case 1:
+		// Switch between the button pressed
+		switch(custom_button_index)
 		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO("[DEFAULT CONTROLLER] Button 1 received in controller.");
-			// Code here to respond to custom button 1
-			
-			break;
-		}
 
-		// > FOR CUSTOM BUTTON 2
-		case 2:
-		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO("[DEFAULT CONTROLLER] Button 2 received in controller.");
-			// Code here to respond to custom button 2
+			// > FOR CUSTOM BUTTON 1
+			case 1:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO("[DEFAULT CONTROLLER] Button 1 received in controller.");
+				// Code here to respond to custom button 1
+				
+				break;
+			}
 
-			break;
-		}
+			// > FOR CUSTOM BUTTON 2
+			case 2:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO("[DEFAULT CONTROLLER] Button 2 received in controller.");
+				// Code here to respond to custom button 2
 
-		// > FOR CUSTOM BUTTON 3
-		case 3:
-		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO_STREAM("[DEFAULT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
-			// Code here to respond to custom button 3
+				break;
+			}
 
-			break;
-		}
+			// > FOR CUSTOM BUTTON 3
+			case 3:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO_STREAM("[DEFAULT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
+				// Code here to respond to custom button 3
 
-		default:
-		{
-			// Let the user know that the command was not recognised
-			ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
-			break;
+				break;
+			}
+
+			default:
+			{
+				// Let the user know that the command was not recognised
+				ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
+				break;
+			}
 		}
 	}
 }
@@ -634,6 +655,7 @@ void customCommandReceivedCallback(const CustomButton& commandReceived)
 
 
 
+
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
 //    L      O   O   A A   D   D
@@ -649,8 +671,7 @@ void customCommandReceivedCallback(const CustomButton& commandReceived)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion
-// ofthe exercise
+// LOADING OF YAML PARAMETERS
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
@@ -696,10 +717,7 @@ void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg)
 }
 
 
-// This function CAN BE edited for successful completion of the
-// exercise, and the use of parameters fetched from the YAML file
-// is highly recommended to make tuning of your controller easier
-// and quicker.
+// LOADING OF YAML PARAMETERS
 void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
 	// Here we load the parameters that are specified in the file:
@@ -763,7 +781,7 @@ void fetchDefaultControllerYamlParameters(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
+
 int main(int argc, char* argv[]) {
 
 	// Starting the ROS-node
@@ -903,14 +921,14 @@ int main(int argc, char* argv[]) {
 	//  in the file "DebugMsg.msg" (located in the "msg" folder).
 	m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-	// Instantiate the local variable "newSetpointRequestSubscriber" to
-	// be a "ros::Subscriber" type variable that subscribes to the
-	// "NewSetpointRequest" topic and calls the class function
-	// "newSetpointRequestCallback" each time a messaged is received on
-	// this topic and the message is passed as an input argument to the
-	// callback function. This subscriber will mainly receive messages
-	// from the "flying agent GUI" when the setpoint is changed by
-	// the user.
+	// Instantiate the local variable "requestSetpointChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestSetpointChange" topic and calls the class function
+	// "requestSetpointChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the setpoint is changed
+	// by the user.
 	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
 
 	// Same again but instead for changes requested by the coordinator.
@@ -929,6 +947,18 @@ int main(int argc, char* argv[]) {
 	// field that displays the current setpoint for this controller.
 	m_setpointChangedPublisher = nodeHandle.advertise<SetpointWithHeader>("SetpointChanged", 1);
 
+	// Instantiate the local variable "getCurrentSetpointService" to be
+	// a "ros::ServiceServer" type variable that advertises the service
+	// called "GetCurrentSetpoint". This service has the input-output
+	// behaviour defined in the "GetSetpointService.srv" file (located
+	// in the "srv" folder). This service, when called, is provided with
+	// an integer (that is essentially ignored), and is expected to respond
+	// with the current setpoint of the controller. When a request is made
+	// of this service the "getCurrentSetpointCallback" function is called.
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);	
+
+
+
 	// Instantiate the local variable "service" to be a "ros::ServiceServer" type
 	// variable that advertises the service called "DefaultController". This service has
 	// the input-output behaviour defined in the "Controller.srv" file (located in the
@@ -943,7 +973,7 @@ int main(int argc, char* argv[]) {
 	// type variable that subscribes to the "GUIButton" topic and calls the class
 	// function "customCommandReceivedCallback" each time a messaged is received on this topic
 	// and the message received is passed as an input argument to the callback function.
-	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
+	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
 
 	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
 	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 12ba738b..cd13c090 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -534,23 +534,87 @@ float computeMotorPolyBackward(float thrust)
 //    N  NN  E       W W W            S  E        T    P      O   O   I   N  NN    T
 //    N   N  EEEEE    W W         SSSS   EEEEE    T    P       OOO   III  N   N    T
 //
-//     GGG   U   U  III        CCCC    A    L      L      BBBB     A     CCCC  K   K
-//    G   G  U   U   I        C       A A   L      L      B   B   A A   C      K  K
-//    G      U   U   I        C      A   A  L      L      BBBB   A   A  C      KKK
-//    G   G  U   U   I        C      AAAAA  L      L      B   B  AAAAA  C      K  K
-//     GGGG   UUU   III        CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     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
-void setpointCallback(const Setpoint& newSetpoint)
+
+// REQUEST SETPOINT CHANGE CALLBACK
+// This function does NOT need to be edited 
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newSetpoint.shouldCheckForAgentID , newSetpoint.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Check if the request if for the default setpoint
+		if (newSetpoint.buttonID == REQUEST_DEFAULT_SETPOINT_BUTTON_ID)
+		{
+			setNewSetpoint(
+					yaml_default_setpoint[0],
+					yaml_default_setpoint[1],
+					yaml_default_setpoint[2],
+					yaml_default_setpoint[3]
+				);
+		}
+		else
+		{
+			// Call the function for actually setting the setpoint
+			setNewSetpoint(
+					newSetpoint.x,
+					newSetpoint.y,
+					newSetpoint.z,
+					newSetpoint.yaw
+				);
+		}
+	}
+}
+
+
+// CHANGE SETPOINT FUNCTION
+// This function does NOT need to be edited 
+void setNewSetpoint(float x, float y, float z, float yaw)
 {
-	m_setpoint[0] = newSetpoint.x;
-	m_setpoint[1] = newSetpoint.y;
-	m_setpoint[2] = newSetpoint.z;
-	m_setpoint[3] = newSetpoint.yaw;
+	// Put the new setpoint into the class variable
+	m_setpoint[0] = x;
+	m_setpoint[1] = y;
+	m_setpoint[2] = z;
+	m_setpoint[3] = yaw;
+
+	// Publish the change so that the network is updated
+	// (mainly the "flying agent GUI" is interested in
+	// displaying this change to the user)
+
+	// Instantiate a local variable of type "SetpointWithHeader"
+	SetpointWithHeader msg;
+	// Fill in the setpoint
+	msg.x   = x;
+	msg.y   = y;
+	msg.z   = z;
+	msg.yaw = yaw;
+	// Publish the message
+	m_setpointChangedPublisher.publish(msg);
 }
 
 
+// GET CURRENT SETPOINT SERVICE CALLBACK
+// This function does NOT need to be edited 
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response)
+{
+	// Directly put the current setpoint into the response
+	response.setpointWithHeader.x   = m_setpoint[0];
+	response.setpointWithHeader.y   = m_setpoint[1];
+	response.setpointWithHeader.z   = m_setpoint[2];
+	response.setpointWithHeader.yaw = m_setpoint[3];
+	// Return
+	return true;
+}
+
 
 
 
@@ -570,51 +634,59 @@ void setpointCallback(const Setpoint& newSetpoint)
 //    ----------------------------------------------------------------------------------
 
 // CUSTOM COMMAND RECEIVED CALLBACK
-void customCommandReceivedCallback(const CustomButton& commandReceived)
+// This function CAN be edited to respond when the buttons
+// in the GUI are pressed
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived)
 {
-	// Extract the data from the message
-	int custom_button_index   = commandReceived.button_index;
-	float custom_command_code = commandReceived.command_code;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , commandReceived.shouldCheckForAgentID , commandReceived.agentIDs );
 
-	// Switch between the button pressed
-	switch(custom_button_index)
+	if (isRevelant)
 	{
+		// Extract the data from the message
+		int custom_button_index   = commandReceived.button_index;
+		float custom_command_code = commandReceived.command_code;
 
-		// > FOR CUSTOM BUTTON 1
-		case 1:
+		// Switch between the button pressed
+		switch(custom_button_index)
 		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO("[STUDENT CONTROLLER] Button 1 received in controller.");
-			// Code here to respond to custom button 1
-			
-			break;
-		}
 
-		// > FOR CUSTOM BUTTON 2
-		case 2:
-		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO("[STUDENT CONTROLLER] Button 2 received in controller.");
-			// Code here to respond to custom button 2
+			// > FOR CUSTOM BUTTON 1
+			case 1:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO("[STUDENT CONTROLLER] Button 1 received in controller.");
+				// Code here to respond to custom button 1
+				
+				break;
+			}
 
-			break;
-		}
+			// > FOR CUSTOM BUTTON 2
+			case 2:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO("[STUDENT CONTROLLER] Button 2 received in controller.");
+				// Code here to respond to custom button 2
 
-		// > FOR CUSTOM BUTTON 3
-		case 3:
-		{
-			// Let the user know that this part of the code was triggered
-			ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
-			// Code here to respond to custom button 3
+				break;
+			}
 
-			break;
-		}
+			// > FOR CUSTOM BUTTON 3
+			case 3:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
+				// Code here to respond to custom button 3
 
-		default:
-		{
-			// Let the user know that the command was not recognised
-			ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
-			break;
+				break;
+			}
+
+			default:
+			{
+				// Let the user know that the command was not recognised
+				ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
+				break;
+			}
 		}
 	}
 }
@@ -622,6 +694,7 @@ void customCommandReceivedCallback(const CustomButton& commandReceived)
 
 
 
+
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
 //    L      O   O   A A   D   D
@@ -637,8 +710,8 @@ void customCommandReceivedCallback(const CustomButton& commandReceived)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion
-// ofthe exercise
+// LOADING OF YAML PARAMETERS
+// This function does NOT need to be edited 
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
@@ -714,6 +787,10 @@ void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	//   thrust force in Newtons
 	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", yaml_motorPoly, 3);
 
+	// The default setpoint, the ordering is (x,y,z,yaw),
+	// with unit [meters,meters,meters,radians]
+	getParameterFloatVector(nodeHandle_for_paramaters, "default_setpoint", yaml_default_setpoint, 4);
+
 
 
 	// > DEBUGGING: Print out one of the parameters that was loaded to
@@ -744,7 +821,8 @@ void fetchStudentControllerYamlParameters(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 
 int main(int argc, char* argv[]) {
 
 	// Starting the ROS-node
@@ -833,15 +911,23 @@ int main(int argc, char* argv[]) {
 
 
 	// GIVE YAML VARIABLES AN INITIAL VALUE
+	// This can be done either here or as part of declaring the
+	// variables in the header file
 
-	// This can be done either here or as part of declaring the variable
-	// in the header file
+	// > the mass of the crazyflie, in [grams]
 	yaml_cf_mass_in_grams = 25.0;
+	// > the coefficients of the 16-bit command to thrust conversion
 	yaml_motorPoly[0] = 5.484560e-4;
 	yaml_motorPoly[1] = 1.032633e-6;
 	yaml_motorPoly[2] = 2.130295e-11;
+	// > the frequency at which the controller is running
 	yaml_control_frequency = 200.0;
-
+	// > the default setpoint, the ordering is (x,y,z,yaw),
+	//   with units [meters,meters,meters,radians]
+	yaml_default_setpoint[0] = 0.0;
+	yaml_default_setpoint[1] = 0.0;
+	yaml_default_setpoint[2] = 0.4;
+	yaml_default_setpoint[3] = 0.0;
 
 
 	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
@@ -890,11 +976,35 @@ int main(int argc, char* argv[]) {
     //  in the file "DebugMsg.msg" (located in the "msg" folder).
     m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-    // Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "Setpoint" topic and calls the class function
-    // "setpointCallback" each time a messaged is received on this topic and the message
-    // is passed as an input argument to the "setpointCallback" class function.
-    ros::Subscriber setpointSubscriber = nodeHandle.subscribe("Setpoint", 1, setpointCallback);
+	// Instantiate the local variable "requestSetpointChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestSetpointChange" topic and calls the class function
+	// "requestSetpointChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the setpoint is changed
+	// by the user.
+	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
+
+	// Instantiate the class variable "m_setpointChangedPublisher" to
+	// be a "ros::Publisher". This variable advertises under the name
+	// "SetpointChanged" and is a message with the structure defined
+	// in the file "SetpointWithHeader.msg" (located in the "msg" folder).
+	// This publisher is used by the "flying agent GUI" to update the
+	// field that displays the current setpoint for this controller.
+	m_setpointChangedPublisher = nodeHandle.advertise<SetpointWithHeader>("SetpointChanged", 1);
+
+	// Instantiate the local variable "getCurrentSetpointService" to be
+	// a "ros::ServiceServer" type variable that advertises the service
+	// called "GetCurrentSetpoint". This service has the input-output
+	// behaviour defined in the "GetSetpointService.srv" file (located
+	// in the "srv" folder). This service, when called, is provided with
+	// an integer (that is essentially ignored), and is expected to respond
+	// with the current setpoint of the controller. When a request is made
+	// of this service the "getCurrentSetpointCallback" function is called.
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);	
+
+
 
     // Instantiate the local variable "service" to be a "ros::ServiceServer" type
     // variable that advertises the service called "StudentController". This service has
@@ -910,7 +1020,7 @@ int main(int argc, char* argv[]) {
     // type variable that subscribes to the "GUIButton" topic and calls the class
     // function "customCommandReceivedCallback" each time a messaged is received on this topic
     // and the message received is passed as an input argument to the callback function.
-    ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
+    ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
     // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
diff --git a/pps_ws/src/d_fall_pps/srv/GetSetpointService.srv b/pps_ws/src/d_fall_pps/srv/GetSetpointService.srv
new file mode 100644
index 00000000..aea949a6
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/srv/GetSetpointService.srv
@@ -0,0 +1,3 @@
+uint32 data
+---
+SetpointWithHeader setpointWithHeader
-- 
GitLab


From fe61c0fdc855f19effe8b1287b249631afda4168 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 19 Dec 2018 17:36:11 +0100
Subject: [PATCH 28/87] Now compiles, needs testing

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |  1 +
 .../include/studentcontrollertab.h            |  3 +-
 .../src/defaultcontrollertab.cpp              |  2 +-
 .../src/studentcontrollertab.cpp              | 49 ++++++++++---------
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |  2 +-
 .../src/nodes/StudentControllerService.cpp    |  9 ++--
 6 files changed, 35 insertions(+), 31 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index b2f1ecd6..961c45c4 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -210,6 +210,7 @@ add_message_files(
   FloatWithHeader.msg
   StringWithHeader.msg
   SetpointWithHeader.msg
+  CustomButtonWithHeader.msg
   #------------------------
   DebugMsg.msg
   CustomButton.msg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 7baf4930..4bcaa3af 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -4,6 +4,7 @@
 #include <QWidget>
 #include <QMutex>
 #include <QVector>
+#include <QLineEdit>
 #include <QTextStream>
 
 #ifdef CATKIN_MAKE
@@ -19,7 +20,7 @@
 // Include the DFALL message types
 //#include "d_fall_pps/IntWithHeader.h"
 #include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CustomButtonWithHeader"
+#include "d_fall_pps/CustomButtonWithHeader.h"
 
 // Include the DFALL service types
 #include "d_fall_pps/GetSetpointService.h"
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 7f503464..2f198ff9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -556,7 +556,7 @@ void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("DefaultControllerService/GetCurrentSetpoint", false);
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
         d_fall_pps::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index 77a93f53..993482f2 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -47,7 +47,7 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
     }
 
     // CREATE THE CUSTOM BUTTON PRESSED PUBLISHED
-    customButtonPublisher = nodeHandle_for_this_gui.advertise<CustomButton>("StudentControllerService/CustomButtonPressed", 1);
+    customButtonPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::CustomButtonWithHeader>("StudentControllerService/CustomButtonPressed", 1);
 
 #endif
 
@@ -87,10 +87,10 @@ void StudentControllerTab::publish_custom_button_command(int button_index , QLin
     // Fill in the button index
     msg.button_index = button_index;
     // Get the line edit data, as a float if possible
-    bool isFloat = false;
-    float lineEdit_as_float = (lineEdit_pointer->text()).toFloat(isFloat);
+    bool isValidFloat = false;
+    float lineEdit_as_float = (lineEdit_pointer->text()).toFloat(&isValidFloat);
     // Fill in the data
-    if (isFloat)
+    if (isValidFloat)
         msg.float_data = lineEdit_as_float;
     else
         msg.string_data = (lineEdit_pointer->text()).toStdString();
@@ -105,24 +105,25 @@ void StudentControllerTab::publish_custom_button_command(int button_index , QLin
 void StudentControllerTab::on_custom_button_1_clicked()
 {
 #ifdef CATKIN_MAKE
-    // Initialise the message as a local variable
-    d_fall_pps::CustomButtonWithHeader msg;
-    // Fill the header of the message
-    fillCustomButtonMessageHeader( msg );
-    // Fill in the button index
-    msg.button_index = 1;
-    // Get the line edit data, as a float if possible
-    bool isFloat = false;
-    float lineEdit_as_float = (ui->lineEdit_custom_1->text()).toFloat(isFloat);
-    // Fill in the data
-    if (isFloat)
-        msg.float_data = lineEdit_as_float;
-    else
-        msg.string_data = (ui->lineEdit_custom_1->text()).toStdString();
-    // Publish the setpoint
-    this->customButtonPublisher.publish(msg);
-    // Inform the user about the change
-    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 1 clicked.");
+    publish_custom_button_command(1,ui->lineEdit_custom_1);
+    // // Initialise the message as a local variable
+    // d_fall_pps::CustomButtonWithHeader msg;
+    // // Fill the header of the message
+    // fillCustomButtonMessageHeader( msg );
+    // // Fill in the button index
+    // msg.button_index = 1;
+    // // Get the line edit data, as a float if possible
+    // bool isFloat = false;
+    // float lineEdit_as_float = (ui->lineEdit_custom_1->text()).toFloat(isFloat);
+    // // Fill in the data
+    // if (isFloat)
+    //     msg.float_data = lineEdit_as_float;
+    // else
+    //     msg.string_data = (ui->lineEdit_custom_1->text()).toStdString();
+    // // Publish the setpoint
+    // this->customButtonPublisher.publish(msg);
+    // // Inform the user about the change
+    // ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 1 clicked.");
 #endif
 }
 
@@ -655,7 +656,7 @@ void StudentControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("StudentControllerService/GetCurrentSetpoint", false);
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
         d_fall_pps::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
@@ -747,7 +748,7 @@ void StudentControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHe
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg )
+void StudentControllerTab::fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 4f63bbd0..60be1432 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -249,7 +249,7 @@ void TopBanner::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
     d_fall_pps::IntWithHeader msg;
-    msg.shouldCheckIDs = false;
+    msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->emergencyStopPublisher.publish(msg);
     ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index cd13c090..ddca6073 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -644,8 +644,9 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 	if (isRevelant)
 	{
 		// Extract the data from the message
-		int custom_button_index   = commandReceived.button_index;
-		float custom_command_code = commandReceived.command_code;
+		int custom_button_index = commandReceived.button_index;
+		float float_data        = commandReceived.float_data;
+		//std::string string_data = commandReceived.string_data;
 
 		// Switch between the button pressed
 		switch(custom_button_index)
@@ -675,7 +676,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			case 3:
 			{
 				// Let the user know that this part of the code was triggered
-				ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 3 received in controller, with command code:" << custom_command_code );
+				ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 3 received in controller, with message.float_data = " << float_data );
 				// Code here to respond to custom button 3
 
 				break;
@@ -684,7 +685,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			default:
 			{
 				// Let the user know that the command was not recognised
-				ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.command_code = " << custom_command_code );
+				ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.float_data = " << float_data );
 				break;
 			}
 		}
-- 
GitLab


From 8fe7e732cafca95ed2ff8adf8de2810ee6a68247 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 19 Dec 2018 19:05:14 +0100
Subject: [PATCH 29/87] Tested to be working and added highlighting the tab
 label for the controller that is operating. Next step is to add tabs for the
 remote and picker controllers, add service for getting the currently
 operating controller, and switch and PPSClient from the safe controller to
 the default controller.

---
 .../flyingAgentGUI/include/controllertabs.h   |  17 +-
 .../flyingAgentGUI/src/controllertabs.cpp     | 171 +++++++++++++++++-
 .../src/defaultcontrollertab.cpp              |  22 ++-
 .../src/studentcontrollertab.cpp              |  48 ++---
 .../src/nodes/DefaultControllerService.cpp    |  10 +-
 .../src/nodes/StudentControllerService.cpp    |  22 ++-
 6 files changed, 256 insertions(+), 34 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 8cf774a9..6ada530a 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -11,7 +11,7 @@
 #include <ros/package.h>
 
 // Include the standard message types
-//#include "std_msgs/Int32.h"
+#include "std_msgs/Int32.h"
 //#include "std_msgs/Float32.h"
 //#include <std_msgs/String.h>
 
@@ -90,6 +90,11 @@ private:
     // Flag for whether pose data should be emitted, this is
     // to save looking through the data when it is unnecessary
     bool m_should_search_pose_data_for_object_name = false;
+    QMutex m_should_search_pose_data_for_object_name_mutex;
+
+    // The color for normal and highlighted tabs
+    QColor m_tab_text_colour_normal;
+    QColor m_tab_text_colour_highlight;
 
 
 #ifdef CATKIN_MAKE
@@ -99,6 +104,8 @@ private:
     // SUBSRIBER
     // > For the pose data from a motion capture system
     ros::Subscriber m_poseDataSubscriber;
+    // > For the controller that is currently operating
+    ros::Subscriber controllerUsedSubscriber;
 #endif
 
 
@@ -110,6 +117,14 @@ private:
     //   "controllerUsedSubscriber"
     void poseDataReceivedCallback(const d_fall_pps::ViconData& viconData);
 
+    void controllerUsedChangedCallback(const std_msgs::Int32& msg);
+
+    void setControllerEnabled(int new_controller);
+
+    void setAllTabLabelsToNormalColouring();
+
+    void setTextColourOfTabLabel(QColor color , QWidget * tab_widget);
+
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
 #endif
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 45dfcd9d..88a4973c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -8,6 +8,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     ui->setupUi(this);
 
 
+    // Specify the color for normal and highlighted tabs
+    m_tab_text_colour_normal = Qt::black;
+    m_tab_text_colour_highlight = QColor(0,200,0);
+
+
     // Initialise the object name as blank
     m_object_name_for_emitting_pose_data = "";
 
@@ -34,6 +39,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->default_controller_tab_widget , &DefaultControllerTab::poseDataUnavailableSlot
         );
 
+    QObject::connect(
+            this , &ControllerTabs::poseDataUnavailableSignal ,
+            ui->student_controller_tab_widget , &StudentControllerTab::poseDataUnavailableSlot
+        );
+
 
     // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
     // WITH THE LIST OF AGENT IDs TO COORDINATE
@@ -45,6 +55,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->default_controller_tab_widget , &DefaultControllerTab::setAgentIDsToCoordinate
         );
 
+    QObject::connect(
+            this , &ControllerTabs::agentIDsToCoordinateChanged ,
+            ui->student_controller_tab_widget , &StudentControllerTab::setAgentIDsToCoordinate
+        );
+
     
 
 
@@ -68,6 +83,7 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     }
 
 
+
     // CREATE A NODE HANDLE TO THIS GUI
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
@@ -77,6 +93,14 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     // CREATE THE SUBSCRIBER TO THE MOTION CAPTURE DATA
     m_poseDataSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, &ControllerTabs::poseDataReceivedCallback, this);
 
+    // CREATE THE SUBSCRIBER TO THE CONTROLLER THAT IS CURRENTLY OPERATING
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        controllerUsedSubscriber = nodeHandle_for_this_gui.subscribe("PPSClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
+    }
+
+
 #endif
 
 }
@@ -136,6 +160,7 @@ void ControllerTabs::showHideController_safe_changed()
 
 void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
 {
+    m_should_search_pose_data_for_object_name_mutex.lock();
     if (object_name.isEmpty())
     {
         // Set the class variable accordingly
@@ -160,6 +185,7 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
             ROS_INFO_STREAM("[CONTROLLER TABS GUI] now emitting data for object named: " << m_object_name_for_emitting_pose_data );
         #endif
     }
+    m_should_search_pose_data_for_object_name_mutex.unlock();
 }
 
 
@@ -168,6 +194,7 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
 //   "controllerUsedSubscriber"
 void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& viconData)
 {
+    m_should_search_pose_data_for_object_name_mutex.lock();
     if (m_should_search_pose_data_for_object_name)
     {
         for(std::vector<d_fall_pps::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
@@ -188,6 +215,7 @@ void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& vicon
             }
         }
     }
+    m_should_search_pose_data_for_object_name_mutex.unlock();
 }
 #endif
 
@@ -195,6 +223,102 @@ void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& vicon
 
 
 
+
+//    ----------------------------------------------------------------------------------
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
+//    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
+//    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
+//    C      O   O  N  NN    T    R   R  O   O  L      L      E      R   R
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL  LLLLL  EEEEE  R   R
+//
+//    EEEEE  N   N    A    BBBB   L      EEEEE  DDDD
+//    E      NN  N   A A   B   B  L      E      D   D
+//    EEE    N N N  A   A  BBBB   L      EEE    D   D
+//    E      N  NN  AAAAA  B   B  L      E      D   D
+//    EEEEE  N   N  A   A  BBBB   LLLLL  EEEEE  DDDD
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// > For the controller currently operating, received on "controllerUsedSubscriber"
+void ControllerTabs::controllerUsedChangedCallback(const std_msgs::Int32& msg)
+{
+    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Controller Used Changed Callback called for agentID = " << m_agentID);
+    setControllerEnabled(msg.data);
+}
+#endif
+
+
+void ControllerTabs::setControllerEnabled(int new_controller)
+{
+    // First set everything back to normal colouring
+    setAllTabLabelsToNormalColouring();
+
+    // Now switch to highlight the tab corresponding to
+    // the enable controller
+    switch(new_controller)
+    {
+        case SAFE_CONTROLLER:
+        {
+            //ui->controller_enabled_label->setText("Safe");
+            break;
+        }
+        case DEMO_CONTROLLER:
+        {
+            //ui->controller_enabled_label->setText("Demo");
+            break;
+        }
+        case STUDENT_CONTROLLER:
+        {
+            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->student_tab );
+            break;
+        }
+        case MPC_CONTROLLER:
+        {
+            //ui->controller_enabled_label->setText("MPC");
+            break;
+        }
+        case REMOTE_CONTROLLER:
+        {
+            //ui->controller_enabled_label->setText("Remote");
+            break;
+        }
+        case TUNING_CONTROLLER:
+        {
+            //ui->controller_enabled_label->setText("Tuning");
+            break;
+        }
+        default:
+        {
+            //ui->controller_enabled_label->setText("Unknown");
+            break;
+        }
+    }
+}
+
+
+void ControllerTabs::setAllTabLabelsToNormalColouring()
+{
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->default_tab );
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->student_tab );
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->picker_tab );
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->safe_tab );
+}
+
+void ControllerTabs::setTextColourOfTabLabel(QColor color , QWidget * tab_widget)
+{
+    // Get the current index of the tab
+    int current_index_of_tab = ui->controller_tabs_widget->indexOf(tab_widget);
+    // Onlz apply the colour is the tab is found
+    if (current_index_of_tab >= 0)
+    {
+        ui->controller_tabs_widget->tabBar()->setTabTextColor(current_index_of_tab, color);
+    }
+}
+
+
+
 //    ----------------------------------------------------------------------------------
 //      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
 //     A A   G      E      NN  N    T        I   D   D  S
@@ -206,8 +330,53 @@ void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& vicon
 
 void ControllerTabs::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
 {
-    // Simply pass on the signal to the tabs
+    // Pass on the signal to the tabs
     emit agentIDsToCoordinateChanged( agentIDs , shouldCoordinateAll );
+
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // SUBSCRIBERS
+        // > For receiving message that the setpoint was changed
+        controllerUsedSubscriber = agent_base_nodeHandle.subscribe("PPSClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        controllerUsedSubscriber.shutdown();
+
+        // Set all tabs to be normal colours
+        setAllTabLabelsToNormalColouring();
+
+    }
+#endif
+
 }
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 2f198ff9..697a2fc5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -46,6 +46,26 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
         setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("DefaultControllerService/SetpointChanged", 1, &DefaultControllerTab::setpointChangedCallback, this);
     }
 
+    // GET THE CURRENT SETPOINT
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[DEFAULT CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+    }
+
 #endif
 
 }
@@ -555,7 +575,7 @@ void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
-        // // > Request the current setpoint
+        // > Request the current setpoint
         ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
         d_fall_pps::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index 993482f2..758a4014 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -46,9 +46,29 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
         setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("StudentControllerService/SetpointChanged", 1, &StudentControllerTab::setpointChangedCallback, this);
     }
 
-    // CREATE THE CUSTOM BUTTON PRESSED PUBLISHED
+    // CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
     customButtonPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::CustomButtonWithHeader>("StudentControllerService/CustomButtonPressed", 1);
 
+    // GET THE CURRENT SETPOINT
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[STUDENT CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+    }
+
 #endif
 
 }
@@ -106,52 +126,34 @@ void StudentControllerTab::on_custom_button_1_clicked()
 {
 #ifdef CATKIN_MAKE
     publish_custom_button_command(1,ui->lineEdit_custom_1);
-    // // Initialise the message as a local variable
-    // d_fall_pps::CustomButtonWithHeader msg;
-    // // Fill the header of the message
-    // fillCustomButtonMessageHeader( msg );
-    // // Fill in the button index
-    // msg.button_index = 1;
-    // // Get the line edit data, as a float if possible
-    // bool isFloat = false;
-    // float lineEdit_as_float = (ui->lineEdit_custom_1->text()).toFloat(isFloat);
-    // // Fill in the data
-    // if (isFloat)
-    //     msg.float_data = lineEdit_as_float;
-    // else
-    //     msg.string_data = (ui->lineEdit_custom_1->text()).toStdString();
-    // // Publish the setpoint
-    // this->customButtonPublisher.publish(msg);
-    // // Inform the user about the change
-    // ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 1 clicked.");
 #endif
 }
 
 void StudentControllerTab::on_custom_button_2_clicked()
 {
 #ifdef CATKIN_MAKE
-    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 2 clicked.");
+    publish_custom_button_command(2,ui->lineEdit_custom_2);
 #endif
 }
 
 void StudentControllerTab::on_custom_button_3_clicked()
 {
 #ifdef CATKIN_MAKE
-    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 3 clicked.");
+    publish_custom_button_command(3,ui->lineEdit_custom_3);
 #endif
 }
 
 void StudentControllerTab::on_custom_button_4_clicked()
 {
 #ifdef CATKIN_MAKE
-    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 4 clicked.");
+    publish_custom_button_command(4,ui->lineEdit_custom_4);
 #endif
 }
 
 void StudentControllerTab::on_custom_button_5_clicked()
 {
 #ifdef CATKIN_MAKE
-    ROS_INFO("[STUDENT CONTROLLER TAB GUI] button 5 clicked.");
+    publish_custom_button_command(5,ui->lineEdit_custom_5);
 #endif
 }
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
index 81807850..db199ea1 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
@@ -933,10 +933,10 @@ int main(int argc, char* argv[]) {
 
 	// Same again but instead for changes requested by the coordinator.
 	// For this we need to first create a node handle to the coordinator:
-    std::string namespace_to_coordinator;
-    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
-    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
-    // And now we can instantiate the subscriber:
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
 	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("DefaultControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
 
 	// Instantiate the class variable "m_setpointChangedPublisher" to
@@ -979,7 +979,7 @@ int main(int argc, char* argv[]) {
 	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
 	//     "using namespace d_fall_pps;"
 	// in the "DEFINES" section at the top of this file.
-	ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+	//ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
 	// Print out some information to the user.
 	ROS_INFO("[DEFAULT CONTROLLER] Service ready :-)");
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index ddca6073..c7e22404 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -656,7 +656,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			case 1:
 			{
 				// Let the user know that this part of the code was triggered
-				ROS_INFO("[STUDENT CONTROLLER] Button 1 received in controller.");
+				ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 1 received in controller, with message.float_data = " << float_data );
 				// Code here to respond to custom button 1
 				
 				break;
@@ -666,7 +666,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			case 2:
 			{
 				// Let the user know that this part of the code was triggered
-				ROS_INFO("[STUDENT CONTROLLER] Button 2 received in controller.");
+				ROS_INFO_STREAM("[STUDENT CONTROLLER] Button 2 received in controller, with message.float_data = " << float_data );
 				// Code here to respond to custom button 2
 
 				break;
@@ -987,6 +987,14 @@ int main(int argc, char* argv[]) {
 	// by the user.
 	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
 
+	// Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("StudentControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
+
 	// Instantiate the class variable "m_setpointChangedPublisher" to
 	// be a "ros::Publisher". This variable advertises under the name
 	// "SetpointChanged" and is a message with the structure defined
@@ -1023,11 +1031,19 @@ int main(int argc, char* argv[]) {
     // and the message received is passed as an input argument to the callback function.
     ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
 
+    // Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	//std::string namespace_to_coordinator;
+	//constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	//ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber customCommandReceivedSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("StudentControllerService/CustomButtonPressed", 1, customCommandReceivedCallback);
+
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
     // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
     //     "using namespace d_fall_pps;"
     // in the "DEFINES" section at the top of this file.
-    ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
     // Print out some information to the user.
     ROS_INFO("[STUDENT CONTROLLER] Service ready :-)");
-- 
GitLab


From f0698c72ccd32927419754b989034c2ee92ef0b6 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 12 Jan 2019 14:57:43 +0100
Subject: [PATCH 30/87] Small correction to allow Qt only compilation

---
 .../GUI_Qt/flyingAgentGUI/include/controllertabs.h     | 10 +++++-----
 1 file changed, 5 insertions(+), 5 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 6ada530a..7650f45f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -119,17 +119,17 @@ private:
 
     void controllerUsedChangedCallback(const std_msgs::Int32& msg);
 
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
+#endif
+
+
     void setControllerEnabled(int new_controller);
 
     void setAllTabLabelsToNormalColouring();
 
     void setTextColourOfTabLabel(QColor color , QWidget * tab_widget);
 
-    // Get the paramters that specify the type and ID
-    bool getTypeAndIDParameters();
-#endif
-
-
 };
 
 #endif // CONTROLLERTABS_H
-- 
GitLab


From 8225f9651ec92ff57f7a1315139f4227978bb0b5 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 30 Jan 2019 09:51:30 +0100
Subject: [PATCH 31/87] Changes to comments in PPS Client (attempt to make
 style consistent with controllers), and added Emergency stop button to GUI

---
 .../GUI_Qt/flyingAgentGUI/flyingagentgui.qrc  |   1 +
 .../flyingAgentGUI/images/emergency_stop.png  | Bin 0 -> 6692 bytes
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |   2 +-
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp | 109 +++++++++++++-----
 4 files changed, 80 insertions(+), 32 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
index fd7f30a5..abfa9642 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
@@ -17,5 +17,6 @@
         <file>images/flying_state_off.png</file>
         <file>images/flying_state_unknown.png</file>
         <file>images/flying_state_unavailable.png</file>
+        <file>images/emergency_stop.png</file>
     </qresource>
 </RCC>
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
new file mode 100644
index 0000000000000000000000000000000000000000..7643f985406c7be73109dbab7cbf9fd00f6d63b4
GIT binary patch
literal 6692
zcmV+<8r$WGP)<h;3K|Lk000e1NJLTq004Rb004Ff1^@s62b+hV000CTX+uL$YePpv
zZ)|UJQ*dEpWk+RhWpZg_Qb$4n062|}Rb6NtRTMtEb7vzY&QokOg><Mt4J8eeRy3is
zx_{l>Hg1+lHrgWSWcKdPn90sKGrRqvPeo9CG3uKX#J{(IASm?@+di}}l?o-=)F3E6
zwD^Ni=!>T7nL9I?X}YoAW$t|Qo$sD|?zw001?ah|SeB6#0T!CBEf+H4bBB+JJu8re
zhoBb*p;u8ID_yBf0ya+zcePvJL&AGs+11_tpRKn>9TgyPA7ZoSs0)aX0r00)%XR^J
z`jH<$>RKN5V(7OqK*TS4xZz{h!*f1<jcI1&EaKCM1yxgOh?fwL%*FUd4Er&#)?c7a
zYU`@#<)UJnb={z`aPMLMpKZZth4XF0r_Y(6K7{XKT>C3ECFkK$#7nA@pGN!$;%jYv
zwjAKwmYb0gKL(K8-kPtb5${A?tlI~wzMrJ6wTdBr=Y%%%EaEMQ&o}4FQ^DA)s*}Z>
z!FI&AHCpoWI|RUqx?7s@$8!5^Q=anY<?1z>%X@i5{QA6kNcMelpE>R6eCYFpmMsVT
zrI(b06~u#xf1yS}_UGdMvD``!0~u-><w<`olA{h=FXLTprs&U03>P=lA4?YN`hilQ
z|3tHka)7T{2CGqwjZfMwx$5irQN_*|e4l)UHmiYuz74Yp1t^#>hrJ3-SOXDcC_o0^
z7T9R1gAN8V6s;5)ieI5-7aQlmJn}lUna#nz!j%5V$X|o`xX!dHWQRV27P1=rj;t2b
zW$~+pTw@bIek?ZvKPDL<64`^#UNTAck#RBsB6*5DP4<%<vJ+(Q`q)ZrMP58N*8RMU
zGg79TMcp~HyP#nIGb&76Q`f944z`9P%PIQ>UA_FqU$I>2EH_cM;u)Q~SI+rg`Rn{L
z_AC5qq~L$#SMj%U$6Cz0vP{G5Y*=%5RT^yu;}-DInZ=349rJPV<W~<yewN9Z=dbi#
zJXvop4o0k(1^R0FRvAu>M6C3K^oO)8y(fJr{l>k`ead~!ea?NsT>_Ci%bnxC;Vy6=
zb6>{xYV#Ue-+LB$7`JEXmTRm^AtP)R9u{)KHsMiWGV&)32xCG~*nyU<>-!d;FP=Re
z4r3qYr~6#KE>;1F`>_J_P5xC?ROxV(DIHdCO*p<m6O1H7WQ>$HRQI@7^PwV@Pvuf+
z5K}u-6REM(K@W$srgorh0{i?O)v0c>QtHxU-hBdD(>iYJ4b2sIOVX2K8m~4gmYVA5
zh^QEb$V`rCQ-|7ZS{nuL-t>?3n=-o(6I(7vocj#GzCZEo`!3>+v;dYIfPu#&ZWzzX
z2i^rZ^Mu;6+rb@?NPG+6)c5T6zxpzGe*M(x+{AON=PiJ>H#?ob-|uwRK0yDg0B4PV
z0id6JRRdfL?*IS*32;bRa{vGr5&!@f5&>tQ(oz5b6|qS~K~#7F?Oh3Y9L1G>qmeWk
z$+~6huzbk|U)Tm4f(;)a$(%NaF(FwXu)zrg=U^erx3FwT*syG32x~A9?#mDifjIFJ
zb7Kp8A(+Dkd|<GRZC%!VjIPm)G}`xC(=%P&)ji##o=fWbzW%!Is(ydJSFc`GSKEe$
zh9F*CM@Pp=Nl8iX+HAJGc<ED^{n*{z-CbE+T-*|7dDDy8;ss~~`9uWyy-@(N2-5DJ
zo}Q&eMMceGL@e(~v20vy+Yj<+;AHWU=sqtaBV$WLL&JD!WUTx#2O2?M;1}2Vu_8hQ
z+dUy(z>cZt_Jd5~ngO}z{T<M7(_H`qgGvlIIt6$5;p7u4<HhsT6ka~6fD<paZ_mks
z(hUzl>WnG!e(&w=?X4^<ENqe|L@OLKpxfKq=iBY}EeepgeGIji{~U(;+|i<esqG{e
zjfcsvKOJ{q$3%1!$jQmcN={C2km-#XXlRD&Wvjq*;E4PMnwy@UzNN9Tae_P{8sVsO
zG=e-2LEeH7S0H`Bo>2g@^mzo%-ux7#9ye7QP5ym-eSMV^CQN9QCqyzFRgP8#dHW{`
zEv|V037ozBM?B7+<8(T=G&MC9^2$XjE@~W&AfMppWM;b2Lm+?mX9+tdhXTf4SO8OK
z%vN&tSIF5F(c<i=aP(LOnO=gy#uhk=V|M>Hhvo0YY~<{%&CSh4@`Ol)BMx+1TiaY7
zC-?r}r=yyarC<@*)hNb!V5g;}MFs4L0!<*Nq@<AI#fWPHxn>lLYbnU0Ujyt}(EvMQ
zKqJU={2(*ai2%sGeIgCU%v}p?hr?0T($Z2KDPlxK8S{g@6+6v>`~h<EWvF<KL6D^Y
z+9%`-Mis~L)1=X8bQ}8G<MC7!6cij|5=;n~&e5uzY=InrYp|(RFsjJMY_t;2OifMQ
z8VSxe73kL1*4ch>&CC&dEsz5si=Gf*lNc`%^O|ut4QK+H-bU;c3-X7bS>jp+DGjiX
z_j9&sV4DIof;<a5M%uL!<dr`i^JB6K&O&qm?61FNvY{9!uubFa5i4VUkcpF-iGQ!a
z$p~`K*wd~V#B>Ji<MW0Uw3%g02~^Myc)i|={QUenCc$7}L_l|Sb<M=~s_<e#{>M(J
zS-IK**&rAiU>`)V%SQrs*rMAHvXYZ6kPX5c%s$xMHmr>+#rO<Va;s2!P7LNY<_imG
z1o?PuhCpT}_`Md$#;DK99RPd(Atn{aYyoVXzLqixIs=A9w;$vxte*w>qg_yQ=?#{+
z)=BtK*#t3;>)DQ3)0wO|W*-_D7%0!n%d2G)LIezPv??cCAcr8c@#JC7#)S|iXHUmP
zqAKL<Nk(eb4YbSUIu0u)am~!_dM%KR(A!Yn!4?{`5$vxHGUZT=8wOh!&;&A8UWKhG
zK(4j4YX$_f0|MB~f6N2B%m`<P9HSBB8Geu%jj#8k&!KkZ4dCnUHT&7D`ZyG@7vMa5
z^ONA1J%dTbG5g!W!NH2$+}vs=K^D;DXbWT+wPG05;%wYDU4^@NCTn$173j{+&gsa>
zG$vb|tVO{nrUl0AeFvCU5vOUPz~+i>0vSJ(slwWrIa}Y3FK`O=6H8n(WR8Boo}W7`
z#^;cJ9CRqgkNAAP@|>KUqruo=pMs+;kmV$bzwlsdJMKY41x?A>Q;9+GQ>Q8NUNb-=
z$Yp+Ut>k1&@siUnrePgmPnC8s0JI<EDg>IDi1&Sr;+jD2>XDYS{Bb}55p4I~Z<yX7
zh9YNA6%&Lp8ZBP=DBpKt21aueKt{8s1+qx4_`KWma$pipz0&5=5=77;riZh#vdSn%
z;Apg+PP9M{5-8DpgKZs9gJU+2v&Cl-MfZ>xL3ex;garzVlciLNZ$E*3?7G`kJ1GLq
zW<a1VkXe!>LdfUtSM8<<G{ezgv#A!a5)z660U$-76RP)CXN^<90@^su60(E<G%8=L
z=uXH-u{y0q0gI!xsFP@E8vM!y8t2rB_J~%0RVaX13Sf#rTcTTqP@^R}*^CFVWjMjP
zXda|YErrx+rNZ4_kPF`Gdhi^o1}|QHJNLjqjp<*5n$i8?I_!2x!M@X{taRQ;D&40~
z2A``(IB<r(e550#Jb0&d;Y4!+&|xcMNSvG>UIqoXuZHCD%;A3uIt&dAK<9?npmoh-
z!V93tfDzf(tc0R<zvd;4D6aW84?x=k&#2asUbzH{*4`n!q})vBpUFgb{&_Pr-FB}&
zz>|_-X4_7tyk-E$*@5~d@O)b>Fp2w<F9o`R&!<^TE%DAf?<CPZB#Lgee5&!zQy0Lr
z9UGBAzX}O5Rbop{hMcP}g|c0*!GybS;n$19i46&3_N8V3q6PfoCw>Q$|Mr+V$ef;L
ze{VUIeYy#<uU^4PRYn<l9+E7RiXr2yQz3WN<xu>{T>_oQU2vANVtI^FWlUaP9;Pq$
zC%$;UAm-$0p~AM56v+F<HIRSX4WY6|G(GJ*^P%js|Ap-DFAu97dtNpaKm1!Lef430
z6jMe()qXhe!@JU#AB6mWyIwU<s05Lt^($k@btT9JTB6#A=XjE+)^Y{^z8W$wIY%o?
z#L`HYD1B)i5LjAHk9lF-xo1G}gLi6GV_I6ltv><Bg4u@Zn=@yQpmiI56*Dh8A2KQy
zD;lG1Ev;*xhMspm09r}0Ia0wfe-=0w&V{V+UkJ{V=P_kS>o0!vF6e&qeHiNZ2x+9`
z^nJF6$tMliv&QibW&_XBIvg+CrCAyOK%?YrbQF!HFRz1S+&;^5eLMGp>*c?L8}IHf
z_k%q*8`AI@oG1ZuufGD4(w&N8*;if+?$7r@`=c)^($peIQFZT8Y#0DiVpGc|gFQb-
zQIw=%$>Vp!;U(V%qhq#VpwkzhsOSI@r22wunH4Vrj}!^II-dOtlstP6WG=5{$|hx`
zL)uAmp%1_IAlJQlt8g)yB!P^xPlrhxACbfidt2{)0y@`kRK)Wlvah^Iu{T=G*YWJD
z(D1MS4d4w*qXCpo-Sv&o{r4^4dgTpa$V#2UY>X9(lUVIo|5x1~{dd2;9U6amx7aj$
zM?EDAhm@lG?|>v{8k0u*x@k7RIaHR(CkDokA0M1Y<CpciMR(eQIbt1wd;4P>7?1-A
zeh-0uZ1t~UXi$0nw)0fwiz6>@S{S)G{}%o@*Zf}(LBox|Wk8m<+rRs3IC|C<f;KEq
zBMFgv-9O2r!waK^?ZO#K^M9`6mQOuy8aG}mQXHeT@-S(Rx$G8GN*rhk{f`h|hYM(H
zlH55LFOWw?ES!G&BCdArt!sd``_-pk(hkwE)UxJLX;i?UebvPQzZsscP4954Nu8+z
zw1(C#if-K;?X5kg_>?p2((|C_t?k@SNh516x=yK~`gAufttu>k`kAM2%eCJ36byO1
z+%#UK>(8%4!ELK?EM@jl3Ur~*UFl0mGu%L3qoCB%)KuzHQJK{1GBY!SqFZkv%IE(4
zD@ArvMoON!C!|J5#H2G#m@A4W?Wdpl9Yx>i+cCZ4d!R6i*7nCY1cFje`WgI}Nt#Em
zpXT{;kg2TqnDIY07#7{6UGiKOYU9(kzYNp&y$wY;za(WM87Kbn<Qy~EkIJcUo+Gt}
zxLJH2kL>sfF<$=Rx)>kM-FezVZZR?`8+C$AAQPzG6)V>(uS4F?t`@8}yv9;Wi_ikL
zLbxd1i}vl_4|f8c0owD{HsMzUymAqbLrpd*CsWZ3O>@F=YUOA;W`;|iSO|q{Zsk_x
zIe3H{&x^#Pq6N{-3V&WsSsaZ&bTaRhch&>VYeP9Q=aKb^E;2y4KStZ_i<_Y1Ih+oK
zX}=BCCNG`-V8eTv)d1twA&v9aHb{d3e<&l2m@#$w6v(=KnHU_tBP4cQGjPnF4q0es
zO-ggH=@_C7fT~j~4RuEyXj;Zp(c(P#1%BNX{{n?*=awH_s_2;{f(T7Ea=LPFxDx8G
z{}1T@LOJG3ikRk2%FN)_MF+Zt<LECwgZTA|T~=>WX6Ton+9RVA&+rtgFD-XHXy_wH
zoH{egn8v%nZ@L$Mk#P8w6;OB0Eoj}^20nu)_R_?kEL8M?cQo9ftBc!AauM?n7j7P2
zqzx@(a*!#XT06WtjK<M1B5e;nZ?u?@U!9}%REHej^|!Z$%a)n~&Ls;WW9brbE?x*}
zC(h=I9%;2HC53{;tma}gVnkSs`#QQ{2-~2QB&kc8th91T)7AVmB=Ou}TPH7iL~%6a
zk!7y&)-|e9HdF(Kl`*vnY3kIAf1smFaJZsFcJB1@#XyFC=PC2KMKf^9<Cr%y@**6G
z<!g5-Y{)5-`G9ddD~U{*Tp|etz4YOm8IHiEgWSo;)N;?`(2r*3a2%d<5}q=qyD_vE
z(}(kP(Po3R6X!tDgTH|^&gx4VE`CH~tak6-4;lF4Ngb_Z+0dSB^v`*uF!5afZg!!9
zmxtoI(ZJOH<V%X=p?)urQEC8Z14fKELPhv;s5y1f%~8gPC~}}k9Cp9<o?88Zc$$A#
zUvfRn*#E9Vq!ZBQ3%o$n0Z;F?PZU7YYE;gTE{Ap_V;@?oXeCSTh!%7<xgO`Osn=yq
z)Kiz9JR;EQuY#nO6g2rweEvR3%&_;+{AJ)p!$T<N!|{uz25Bg&rOxJ5P9vo0X8C)z
z?ZCgd{6bM({!Oc(<EdA4b2V84d7``ji~Zp1<STuOMxzuVif&dj3DLNkRV?$O$`B=o
zlap}X?U+@j$m`ZvgH~i7K?Kd=-M9iJcgeV8hBiXzar7&~0+pQ}?N7g=r;3>5F$6Sm
zB+tN*|H~f>i}RtLAn(S123kCqJFU$I^1LGrxBQ;J@|1tmwKxN~7iij~=4eTEDw=tD
z+)Q-o{L?12qA`od(~1~nOqb}U-qMZ``S?V;A*Q_d0<^7r4!Ur>_8dG4v@A(`sZwx}
zo>qDCZu}vThAnqwpzq&%Kpq{jFzFLCA5C9;lA?{QmFI!ugyX^W>KowRg*!}k?L#d+
zSC~Dd;jAI&2P=T4kvu1?9f#OH#VZ%BIB|^D-ConL{s*_!ED*G4X(1ae>fgLdxF~)Q
z$11W$$>*)oGPJL(9t|$Q*^nU3XSToYs+(bI)dsG;o-BRiZ~v*GCfgobkGoG^H&iAf
znKiU-L3HDsP07)ub#vSh+FEOoP=l=<oYY{HJv&nqWXjoe$6B0zeI6_nB_G-AYrpq%
z@ZuJskvigjdimqk;c--q3Di(O>5B_Go10do!g2JHG~RX(v_Bl4IWL?x<z;BNAQLXF
zE7P>dsG}i=UikV|xWW`hd86%(G`}HbOxl<*FUG&9($6*NM=5$7*~44@@B|!MungM&
z_=27y5zRx#cQoGeJ2-mIHHsaXY7Ns%(f-6saQNg)blDHo>WOx|aQqaVG>6*R5ozQ5
zb5U6_Fm{sCMFy4OJNnT?NMhc5xK>!)r+GHbp?$7yX)|%<rv(<_o2%od3afG{^z9YC
z44wn{-PJev-4)$Y(G<5Q$5rRCGeq<0d){Qa<#xL>aVKcEVP%Y|MH2Ah-fFrM*$Ml~
zX>Yks2^DY8%2Tz(KB|ju6=h5;Xx$To0=NetsEl#7?!<TwtCu<{pw7`cE3mR91_jjT
z(TUN2tCt}tFrs;Mh`O!hSW$pu_Y%9JF1q=KF|nL=PcRCIKr2k3WV^OpVo|`x*&fVj
z-Mq&se(Y}CWNd-WqfI=<CE?ma$&<fV?V7;RxC@~dr&ztxTv?Z%3nfplvA~uRB~JYW
z@}y0V3(Kj}E+VE!@ej3biW7jwQ`+0`?<yB^!G6X9TS~lm^9vy3VLP<rR_X|3`eV+F
z88iARUL2zVf1$IL3-$`+Yzu5D4dcd7TeBt+$cs*3`Xqvkm>v-m6#u=#1&(r@du_%+
zJYCF0cNcEdufG<T<P0oyNXuJ(b15KzOyXJzay0^7o}Hb2SlVKMqs2&k3#yQ_mn+0L
zaW<YqVku}MrDAv2;AAey)Kdk}6zK<h8G_CH11SrSi?YBb3dPO^K$e~IgjlJ9Ougj-
zO$iA0`+m;0z$SvkfztrF27#`Si)(3@Re`2Vez3WmJ@L7FEio>oWQ6?!$bWrQab6n&
zOd!*k{H<0OG=Zjq2=+GQYz5ev7oQCR*s_CEv>LP0!lMA~rkz9}D?e1M^>eZ&$kb{`
zpeYl9jX$Hl04rto0a;)Zbt3BokZB6V0T~&PIQfvC9_Rv^D#AaGZ%43+vsth&T555&
z9!iIi$1ISkY283mW<S_U&bGiN@|fy0#C4rtT<hXwu~Q0ziI|{u$KTAKj=M(RM579G
zU`H2zl}|@qKpcOXqV-(yk`@3Nzlf1J0=XPb)(2(rA%liETC5E@`vVl?=VPPHH=>yr
zR>H*fe*mx)G?7$>?;$|02nS^9L|7ax_8xynd>VpHoSiAg(cR)~DK+%_lg6c^c8!V`
zp4udH^?ptc`)kCoI9luko-_F&g3Raa=Pk|_>7?f#Nsy`i5plHm0La-(@Qr&*!P%Q}
z%)Z(hvqd_o-8DcyhGoi;q4XV$qSgS$kBFnida)z_K#<Qvu<@hlpreD>g`+U6F*`^U
znU6p&-H65zrMNZ?WNOkBps6AP8*d!2D~7?2@DE0)4~gbPkU4)fAdoA};AD{|rU6YA
zqDJ@;-uPgzzfXBqx7dp@c-H`#4jCnom4~g2fKH|YP5tnLeXdfB6KCTG;}&PbFvySK
z@fwQXOf+~r9@9Z4TucYr5B3hc6WGl0VVTRy$2{2dd&g4z0SxC16#?Y@{QUhyL$h5(
zfTm6&XIo&)&?1m&6^a9LBXV+Oq(G)_L=0%E9Krq=Z(PnUePQjG65|5Md`>2iD-h&}
zo@X6Vpe10RgJPUH-G=_PI99+8fQ+Xf%Uo1IrZ!D6n8-TM4Z2(|`m4y>IN#2ZX6Sz7
zeW?Ax&6@w4lIBk|zXr%nUaz+zFE5Y(lM<63G~ygB_7}zYC&<-&&i>Q=qf(5=3&?~)
z)PSbOa5u!KT(I%~%%upn+Npe0Hqo2_@?ZW4=}K`;oLm_#P8R7FHPJ0LNcYap&P6D~
z-@z+a8c%0f*Ijj!@pG!BmBfLc&J&%q5kWp}k-Rs}esR55o)GD9R5@CF8075F{G81k
zS3mB&GhkwZbG8=90|NuZ$x#QH=pGY}76C`jUWi=%E|;@WK^wwT{JD;IViGrwTblb@
zB<^41d392iym*YWrKRE!v=-7&KUv;zGl7g7HulI9q7{xQ(Daagut|(Z=XW{LqHM68
z7C*?lgHh4<#YA*V9}~s+PTaP7Hj45#Y5XYh#|6kl%a{XAoxpwLyG9|{1oBc8*D>W}
uqA$6)0Gc}D2Ycx#;cOA)FX`Fh!TmolQb-5Pk=#lE0000<MNUMnLSTXfKkMrN

literal 0
HcmV?d00001

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 60be1432..5f58fcdf 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -51,7 +51,7 @@ TopBanner::TopBanner(QWidget *parent) :
 {
     ui->setupUi(this);
     (":/images/rf_connected.png");
-    QPixmap pixmap(":/images/rf_connected.png");
+    QPixmap pixmap(":/images/emergency_stop.png");
     QIcon ButtonIcon(pixmap);
     ui->emergency_stop_button->setText("");
     ui->emergency_stop_button->setIcon(ButtonIcon);
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 79bd5ce3..90d259e0 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -913,7 +913,19 @@ void CFBatteryCallback(const std_msgs::Float32& msg)
 
 
 
-
+//    ----------------------------------------------------------------------------------
+//     GGGG  EEEEE  TTTTT      SSSS  TTTTT    A    TTTTT  U   U   SSSS
+//    G      E        T       S        T     A A     T    U   U  S
+//    G      EEE      T        SSS     T    A   A    T    U   U   SSS
+//    G   G  E        T           S    T    AAAAA    T    U   U      S
+//     GGGG  EEEEE    T       SSSS     T    A   A    T     UUU   SSSS
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K   SSSS
+//    C       A A   L      L      B   B   A A   C      K  K   S
+//    C      A   A  L      L      BBBB   A   A  C      KKK     SSS
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K       S
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K  SSSS
+//    ----------------------------------------------------------------------------------
 
 bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response)
 {
@@ -1213,15 +1225,56 @@ int main(int argc, char* argv[])
 
 
 
-    // FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+    // GIVE YAML VARIABLES AN INITIAL VALUE
+
+	// This can be done either here or as part of declaring the
+	// variables in the header file
+
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
     // Call the class function that loads the parameters for this class.
     fetchClientConfigYamlParameters(nodeHandle_to_own_agent_parameter_service);
     fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
 
-
-
+    // THIS IS THE "NEW" WAY TO DO IT
+    // BUT NEED TO CHECK ALL VARIABLES HAVE INITIAL VALUE
+ //    // FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// // The yaml files for the controllers are not added to
+	// // "Parameter Service" as part of launching.
+	// // The process for loading the yaml parameters is to send a
+	// // service call containing the filename of the *.yaml file,
+	// // and then a message will be received on the above subscribers
+	// // when the paramters are ready.
+	// // > NOTE IMPORTANTLY that by using a serice client
+	// //   we stall the availability of this node until the
+	// //   paramter service is ready
+
+	// // Create the service client as a local variable
+	// ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// // Create the service call as a local variable
+	// LoadYamlFromFilename loadYamlFromFilenameCall;
+	// // Specify the Yaml filename as a string
+	// loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
+	// // Set for whom this applies to
+	// loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// // Wait until the serivce exists
+	// requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// // Make the service call
+	// if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	// {
+	// 	// Nothing to do in this case.
+	// 	// The "isReadyDefaultControllerYamlCallback" function
+	// 	// will be called once the YAML file is loaded
+	// }
+	// else
+	// {
+	// // Inform the user
+	// 	ROS_ERROR("[DEFAULT CONTROLLER] The request load yaml file service call failed.");
+	// }
 
 
 
@@ -1234,17 +1287,23 @@ int main(int argc, char* argv[])
 
 
 
-
+    // PUBLISHERS, SUBSCRIBERS, AND SERVICE CLIENTS
 
 	
+
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle nodeHandle_dfall_root("/dfall");
 
+    // CREATE A NODE HANDLE TO THE COORDINATOR
+    std::string namespace_to_coordinator;
+    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
 
 
 
 
-    // SERVICE CLIENT FOR THE ALLOWED FLYING ZONE AND OTHER CONTEXT DETAILS
+    // SERVICE CLIENT FOR LOADING THE ALLOCATED FLYING ZONE
+    // AND OTHER CONTEXT DETAILS
 
     //ros::service::waitForService("/CentralManagerService/CentralManager");
 	centralManager = nodeHandle_dfall_root.serviceClient<CMQuery>("CentralManagerService/Query", false);
@@ -1253,25 +1312,15 @@ int main(int argc, char* argv[])
     // Subscriber for when the Flying Zone Database changed
     ros::Subscriber databaseChangedSubscriber = nodeHandle_dfall_root.subscribe("CentralManagerService/DBChanged", 1, crazyflieContextDatabaseChangedCallback);
 
-
-
-
-
     // EMERGENCY STOP OF THE WHOLE "D-FaLL-System"
     ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopCallback);
 
-
-
-
-
     // LOCALISATION DATA FROM MOTION CAPTURE SYSTEM
-
 	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
 	ros::Subscriber viconSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, viconCallback);
 
 
 
-
     // PUBLISHER FOR COMMANDING THE CRAZYFLIE
     // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
 	//ros::Publishers to advertise the control output
@@ -1282,18 +1331,8 @@ int main(int argc, char* argv[])
 
 
 
-
-
-    // CREATE A NODE HANDLE TO THE COORDINATOR
-    std::string namespace_to_coordinator;
-    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
-    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
-
-
-
-
-
-    // SUBSCRIBER FOR {TAKE-OFF,LAND,MOTORS-OFF} AND CONTROLLER SELECTION
+    // SUBSCRIBER FOR THE CHANGE STATE COMMANDS
+    // i.e., {TAKE-OFF,LAND,MOTORS-OFF,CONTROLLER SELECTION}
     // > for the agent GUI
     ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, commandCallback);
     // > for the coord GUI
@@ -1302,14 +1341,22 @@ int main(int argc, char* argv[])
 
 
 
-
-    //this topic lets us use the terminal to communicate with crazyRadio node.
+    // PUBLISHER FOR THE CRAZYRADIO COMMANDS
+    // i.e., {CONNECT,DISCONNECT}
+    // This topic lets us use the terminal to communicate with
+    // the crazyRadio node even when the GUI is not launched
     crazyRadioCommandPublisher = nodeHandle.advertise<IntWithHeader>("crazyRadioCommand", 1);
 
-    // this topic will publish flying state whenever it changes.
+
+
+    // PUBLISHER FOR THE FLYING STATE
+    // Possible states: {MOTORS-OFF,TAKE-OFF,FLYING,LAND}
+    // This topic will publish flying state whenever it changes.
     flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
 
     
+
+    // PUBLISHER FOR THE 
     controllerUsedPublisher = nodeHandle.advertise<std_msgs::Int32>("controllerUsed", 1);
 
 
-- 
GitLab


From b53e09bdfac1f702eec2653323592532f6ecccc3 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 30 Jan 2019 13:35:16 +0100
Subject: [PATCH 32/87] Adjusted flying agent GUI behaviour for coorindator
 mode to be able to use the increment setpoint buttons in a meaningful fashion

---
 .../include/studentcontrollertab.h            |   2 +
 .../src/studentcontrollertab.cpp              | 145 +++++++++++-------
 2 files changed, 88 insertions(+), 59 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 4bcaa3af..32825c7e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -144,6 +144,8 @@ private:
 
     void publishSetpoint(float x, float y, float z, float yaw);
 
+    void increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc);
+
 };
 
 #endif // STUDENTCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index 758a4014..efc5d999 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -441,13 +441,7 @@ void StudentControllerTab::on_x_increment_plus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        increment_setpoint_by( (ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,0.0,0.0);
     }
     else
     {
@@ -465,13 +459,7 @@ void StudentControllerTab::on_x_increment_minus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_x->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_x->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        increment_setpoint_by( -(ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,0.0,0.0);
     }
     else
     {
@@ -487,13 +475,7 @@ void StudentControllerTab::on_y_increment_plus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        increment_setpoint_by(0.0, (ui->lineEdit_setpoint_increment_y->text()).toFloat() ,0.0,0.0);
     }
     else
     {
@@ -509,19 +491,13 @@ void StudentControllerTab::on_y_increment_minus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_y->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_y->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        increment_setpoint_by(0.0, -(ui->lineEdit_setpoint_increment_y->text()).toFloat() ,0.0,0.0);
     }
     else
     {
         #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
-        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment y setpoint clicked but field is empty");
         #endif
     }
 }
@@ -531,19 +507,13 @@ void StudentControllerTab::on_z_increment_plus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() + (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        increment_setpoint_by(0.0,0.0, (ui->lineEdit_setpoint_increment_z->text()).toFloat() ,0.0);
     }
     else
     {
         #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
-        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment z setpoint clicked but field is empty");
         #endif
     }
 }
@@ -553,19 +523,14 @@ void StudentControllerTab::on_z_increment_minus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_z->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() - (ui->lineEdit_setpoint_increment_z->text()).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat()
-            );
+        // Call the function to increment the setpoint
+        increment_setpoint_by(0.0,0.0, -(ui->lineEdit_setpoint_increment_z->text()).toFloat() ,0.0);
     }
     else
     {
         #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
-        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment z setpoint clicked but field is empty");
         #endif
     }
 }
@@ -575,19 +540,14 @@ void StudentControllerTab::on_yaw_increment_plus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
     {
-        // Call the function to publish the setpoint
-        publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
-            );
+        // Call the function to increment the setpoint
+        increment_setpoint_by(0.0,0.0,0.0, (ui->lineEdit_setpoint_increment_yaw->text()).toFloat() );
     }
     else
     {
         #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
-        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment yaw setpoint clicked but field is empty");
         #endif
     }
 }
@@ -596,19 +556,85 @@ void StudentControllerTab::on_yaw_increment_minus_button_clicked()
     // Only need to do something if the field is not empty
     if(!ui->lineEdit_setpoint_increment_yaw->text().isEmpty())
     {
-        // Call the function to publish the setpoint
+        // Call the function to increment the setpoint
+        increment_setpoint_by(0.0,0.0,0.0, -(ui->lineEdit_setpoint_increment_yaw->text()).toFloat() );
+    }
+    else
+    {
+        #ifdef CATKIN_MAKE
+        // Inform the user that nothing can be done
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment yaw setpoint clicked but field is empty");
+        #endif
+    }
+}
+
+
+void StudentControllerTab::increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc)
+{
+	
+    if (m_type == TYPE_AGENT)
+    {
+    	// WHEN GUI IS IN AGENT TYPE MODE:
+    	// APPLY THE INCREMENT FROM THE CURRENT SETPOINT
+		// Call the function to publish the setpoint
         publishSetpoint(
-                (ui->lineEdit_setpoint_current_x->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_y->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_z->text()  ).toFloat(),
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() - (ui->lineEdit_setpoint_increment_yaw->text()).toFloat()
+                (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + x_inc,
+                (ui->lineEdit_setpoint_current_y->text()  ).toFloat() + y_inc,
+                (ui->lineEdit_setpoint_current_z->text()  ).toFloat() + z_inc,
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + yaw_inc
             );
     }
+    else if (m_type == TYPE_COORDINATOR)
+    {
+    	// WHEN GUI IS IN COORDINATOR TYPE MODE:
+    	// APPLY THE INCREMENT FROM THE CURRENT SETPOINT
+
+		// Initialise local variable for each of (x,y,z,yaw)
+    	float x = 0.0f, y = 0.0f, z = 0.4f, yaw = 0.0f;
+
+	    // Take the new value if available, otherwise use the old value
+	    // > For x
+	    if(!ui->lineEdit_setpoint_new_x->text().isEmpty())
+	        x = (ui->lineEdit_setpoint_new_x->text()).toFloat();
+	    // > For x
+	    if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
+	        y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
+	    // > For x
+	    if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
+	        z = (ui->lineEdit_setpoint_new_z->text()).toFloat();
+	    // > For x
+	    if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty())
+	        yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat();
+
+	    // Add the increment to this
+	    float x_new   = x   + x_inc;
+	    float y_new   = y   + y_inc;
+	    float z_new   = z   + z_inc;
+	    float yaw_new = yaw + yaw_inc;
+
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+    	QString qstr = "";
+
+	    // Put this back into the new fields
+	    if (x_new < 0.0f) qstr = ""; else qstr = "+";
+    		ui->lineEdit_setpoint_new_x->setText(qstr + QString::number( x_new, 'f', 3));
+		if (y_new < 0.0f) qstr = ""; else qstr = "+";
+    		ui->lineEdit_setpoint_new_y->setText(qstr + QString::number( y_new, 'f', 3));
+	    if (z_new < 0.0f) qstr = ""; else qstr = "+";
+    		ui->lineEdit_setpoint_new_z->setText(qstr + QString::number( z_new, 'f', 3));
+
+    	if (yaw_new < 0.0f) qstr = ""; else qstr = "+";
+    		ui->lineEdit_setpoint_new_yaw->setText(qstr + QString::number( yaw_new, 'f', 3));
+
+		// Call the function to publish the setpoint
+        publishSetpoint(x_new,y_new,z_new,yaw_new);
+
+    }
     else
     {
         #ifdef CATKIN_MAKE
         // Inform the user that nothing can be done
-        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment x setpoint clicked but field is empty");
+        ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Increment setpoint not possible because m_type is not recognised.");
         #endif
     }
 }
@@ -617,6 +643,7 @@ void StudentControllerTab::on_yaw_increment_minus_button_clicked()
 
 
 
+
 //    ----------------------------------------------------------------------------------
 //      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
 //     A A   G      E      NN  N    T        I   D   D  S
-- 
GitLab


From 4292664bded7a0ab809190b8065656d3491a69fc Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 30 Jan 2019 13:36:15 +0100
Subject: [PATCH 33/87] Change student GUI tab field to Courier font

---
 .../flyingAgentGUI/forms/studentcontrollertab.ui  | 15 +++++++++++++++
 1 file changed, 15 insertions(+)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index 86fa1a9e..98d17bfe 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -1131,6 +1131,11 @@
            <height>60</height>
           </size>
          </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
         </widget>
        </item>
        <item>
@@ -1189,6 +1194,11 @@
            <height>60</height>
           </size>
          </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
         </widget>
        </item>
        <item>
@@ -1247,6 +1257,11 @@
            <height>60</height>
           </size>
          </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
         </widget>
        </item>
        <item>
-- 
GitLab


From 33769a7a87bd4fbd0e51cdbb9783eadf6ff4198f Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 3 Feb 2019 09:20:06 +0100
Subject: [PATCH 34/87] Filled in the Picker GUI and connected all the buttons
 to Qt code. Next step is to integrate the Picker GUI with ROS

---
 .../forms/pickercontrollertab.ui              | 2548 ++++++++++++++++-
 .../include/pickercontrollertab.h             |  186 ++
 .../src/pickercontrollertab.cpp               | 1337 +++++++++
 3 files changed, 4065 insertions(+), 6 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
index 0b90bdd1..0527a979 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
@@ -6,20 +6,2556 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>400</width>
-    <height>300</height>
+    <width>1978</width>
+    <height>1188</height>
    </rect>
   </property>
+  <property name="font">
+   <font>
+    <pointsize>16</pointsize>
+   </font>
+  </property>
   <property name="windowTitle">
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
    <item row="0" column="0">
-    <widget class="QLabel" name="label">
-     <property name="text">
-      <string>Picker</string>
+    <layout class="QGridLayout" name="gridLayout_2">
+     <property name="leftMargin">
+      <number>6</number>
+     </property>
+     <property name="topMargin">
+      <number>6</number>
+     </property>
+     <property name="rightMargin">
+      <number>6</number>
+     </property>
+     <property name="bottomMargin">
+      <number>6</number>
      </property>
-    </widget>
+     <item row="1" column="0">
+      <widget class="Line" name="line_15">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="1">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="4" column="0">
+      <spacer name="verticalSpacer">
+       <property name="orientation">
+        <enum>Qt::Vertical</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>40</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="0" column="0">
+      <layout class="QGridLayout" name="gridLayout_3">
+       <property name="leftMargin">
+        <number>6</number>
+       </property>
+       <property name="topMargin">
+        <number>6</number>
+       </property>
+       <property name="rightMargin">
+        <number>6</number>
+       </property>
+       <property name="bottomMargin">
+        <number>6</number>
+       </property>
+       <item row="19" column="3">
+        <widget class="Line" name="line_24">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="16" column="6">
+        <widget class="QLineEdit" name="lineEdit_increment_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="8" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_22">
+         <item>
+          <widget class="QCheckBox" name="checkbox_goto_end">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="8" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_13">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_end_x">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_minus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_plus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="8" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_35">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_end_yaw">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_minus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_plus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="16" column="7">
+        <widget class="QLineEdit" name="lineEdit_increment_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="7" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_4">
+         <item>
+          <widget class="QPushButton" name="button_lift_up">
+           <property name="text">
+            <string>Lift Up</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_lift_up_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="12" column="6">
+        <widget class="Line" name="line_4">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="8">
+        <widget class="Line" name="line_13">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="9" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_6">
+         <item>
+          <widget class="QPushButton" name="button_put_down">
+           <property name="text">
+            <string>Put Down</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_put_down_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="0">
+        <widget class="QLabel" name="label_function_column">
+         <property name="text">
+          <string>Function</string>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="3">
+        <widget class="QLabel" name="label_smooth_column">
+         <property name="text">
+          <string>Smooth</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="6" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_3">
+         <item>
+          <widget class="QPushButton" name="button_attach">
+           <property name="text">
+            <string>Attach</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_attach_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="10" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_7">
+         <item>
+          <widget class="QPushButton" name="button_squat">
+           <property name="text">
+            <string>Squaut</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_squat_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="5" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_34">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_start_yaw">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_minus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_plus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="18" column="0">
+        <widget class="QLabel" name="label_current">
+         <property name="text">
+          <string>Current:</string>
+         </property>
+        </widget>
+       </item>
+       <item row="18" column="8">
+        <widget class="QLineEdit" name="lineEdit_current_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="12" column="0">
+        <widget class="Line" name="line">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="7">
+        <widget class="QLabel" name="label_z_column">
+         <property name="text">
+          <string>z[m]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="4">
+        <widget class="QLabel" name="label_x_column">
+         <property name="text">
+          <string>x[m]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="12" column="9">
+        <widget class="Line" name="line_7">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="18" column="4">
+        <widget class="QLineEdit" name="lineEdit_current_x">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="8" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_21">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_end_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_minus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_plus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="6">
+        <widget class="QLabel" name="label_y_column">
+         <property name="text">
+          <string>y[m]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="8" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_5">
+         <item>
+          <widget class="QPushButton" name="button_goto_end">
+           <property name="text">
+            <string>Goto End</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_goto_end_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_17">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="5" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_26">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_start_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="16" column="8">
+        <widget class="QLineEdit" name="lineEdit_increment_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="8">
+        <widget class="Line" name="line_35">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="16" column="9">
+        <widget class="QLineEdit" name="lineEdit_increment_mass">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="11" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_32">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_jump_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_jump_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_jump_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="18" column="7">
+        <widget class="QLineEdit" name="lineEdit_current_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="0">
+        <widget class="Line" name="line_8">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="9">
+        <widget class="QLabel" name="label_mass_column">
+         <property name="text">
+          <string>mass[g]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="12" column="8">
+        <widget class="Line" name="line_6">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="6" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_16">
+         <item>
+          <widget class="QCheckBox" name="checkbox_attach">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="5" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_2">
+         <item>
+          <widget class="QPushButton" name="button_goto_start">
+           <property name="text">
+            <string>Goto Start</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_goto_start_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="7" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_28">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_lift_up_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_lift_up_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_lift_up_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="17" column="9">
+        <widget class="Line" name="line_14">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="16" column="4">
+        <widget class="QLineEdit" name="lineEdit_increment_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="7" column="9">
+        <layout class="QHBoxLayout" name="horizontalLayout_44">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_lift_up_mass">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_lift_up_inc_minus_mass">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_lift_up_inc_plus_mass">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="18" column="6">
+        <widget class="QLineEdit" name="lineEdit_current_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="12" column="3">
+        <widget class="Line" name="line_2">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="4">
+        <widget class="Line" name="line_10">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="8">
+        <widget class="QLabel" name="label_yaw_column">
+         <property name="text">
+          <string>yaw[deg]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="6">
+        <widget class="Line" name="line_11">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="11" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_8">
+         <item>
+          <widget class="QPushButton" name="button_jump">
+           <property name="text">
+            <string>Jump</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_jump_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="10" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_31">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_squat_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_squat_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_squat_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="17" column="7">
+        <widget class="Line" name="line_12">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="6" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_27">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_attach_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_attach_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_attach_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout">
+         <item>
+          <widget class="QPushButton" name="button_standby">
+           <property name="text">
+            <string>Standby</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_standby_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="5" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_10">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_start_x">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_minus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_plus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="12" column="7">
+        <widget class="Line" name="line_5">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="16" column="0">
+        <widget class="QLabel" name="label_increment">
+         <property name="text">
+          <string>Increment:</string>
+         </property>
+        </widget>
+       </item>
+       <item row="5" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_18">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_start_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_minus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_plus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="9" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_30">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_put_down_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_put_down_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_put_down_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="12" column="4">
+        <widget class="Line" name="line_3">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="3">
+        <widget class="Line" name="line_9">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="15" column="0">
+        <widget class="Line" name="line_16">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="14" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_33">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_yaw">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_9">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_x">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_x">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="5" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_14">
+         <item>
+          <widget class="QCheckBox" name="checkbox_goto_start">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="11" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_29">
+         <item>
+          <widget class="QCheckBox" name="checkbox_jump">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="15" column="3">
+        <widget class="Line" name="line_17">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="9" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_23">
+         <item>
+          <widget class="QCheckBox" name="checkbox_put_down">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="7" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_19">
+         <item>
+          <widget class="QCheckBox" name="checkbox_lift_up">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_11">
+         <item>
+          <widget class="QCheckBox" name="checkbox_standby">
+           <property name="enabled">
+            <bool>true</bool>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+           <property name="checkable">
+            <bool>true</bool>
+           </property>
+           <property name="checked">
+            <bool>false</bool>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="10" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_24">
+         <item>
+          <widget class="QCheckBox" name="checkbox_squat">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_25">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="15" column="4">
+        <widget class="Line" name="line_18">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="14" column="9">
+        <layout class="QHBoxLayout" name="horizontalLayout_41">
+         <property name="spacing">
+          <number>0</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_mass">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_mass">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_mass">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="15" column="6">
+        <widget class="Line" name="line_19">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="15" column="7">
+        <widget class="Line" name="line_20">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="15" column="8">
+        <widget class="Line" name="line_21">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="15" column="9">
+        <widget class="Line" name="line_22">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="20" column="0">
+        <widget class="QLabel" name="label_error">
+         <property name="text">
+          <string>Error:</string>
+         </property>
+        </widget>
+       </item>
+       <item row="22" column="0">
+        <widget class="QLabel" name="label_measured">
+         <property name="text">
+          <string>Measured:</string>
+         </property>
+        </widget>
+       </item>
+       <item row="18" column="9">
+        <widget class="QLineEdit" name="lineEdit">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="0">
+        <widget class="Line" name="line_23">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="9">
+        <widget class="Line" name="line_36">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="4">
+        <widget class="Line" name="line_25">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="6">
+        <widget class="Line" name="line_26">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="7">
+        <widget class="Line" name="line_27">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="9">
+        <widget class="Line" name="line_29">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="19" column="8">
+        <widget class="Line" name="line_28">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="3">
+        <widget class="Line" name="line_31">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="0">
+        <widget class="Line" name="line_30">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="4">
+        <widget class="Line" name="line_32">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="6">
+        <widget class="Line" name="line_33">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="21" column="7">
+        <widget class="Line" name="line_34">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="18" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_15">
+         <item>
+          <widget class="QCheckBox" name="checkbox_current">
+           <property name="enabled">
+            <bool>false</bool>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="20" column="4">
+        <widget class="QLineEdit" name="lineEdit_error_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="20" column="6">
+        <widget class="QLineEdit" name="lineEdit_error_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="20" column="7">
+        <widget class="QLineEdit" name="lineEdit_error_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="20" column="8">
+        <widget class="QLineEdit" name="lineEdit_error_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="22" column="4">
+        <widget class="QLineEdit" name="lineEdit_measured_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="22" column="7">
+        <widget class="QLineEdit" name="lineEdit_measured_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="22" column="6">
+        <widget class="QLineEdit" name="lineEdit_measured_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="22" column="8">
+        <widget class="QLineEdit" name="lineEdit_measured_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="2" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_12">
+       <property name="leftMargin">
+        <number>6</number>
+       </property>
+       <property name="topMargin">
+        <number>6</number>
+       </property>
+       <item>
+        <widget class="QCheckBox" name="checkbox_should_publish_value_changed">
+         <property name="maximumSize">
+          <size>
+           <width>40</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+         </property>
+         <property name="text">
+          <string/>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLabel" name="label_should_publish_value_changed">
+         <property name="font">
+          <font>
+           <pointsize>14</pointsize>
+          </font>
+         </property>
+         <property name="text">
+          <string>Publish setpoint change everytime a {x,y,z,yaw,mass} value is changed?</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="0">
+      <widget class="Line" name="line_37">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+      </widget>
+     </item>
+    </layout>
    </item>
   </layout>
  </widget>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index c8c83a3a..1a49ebd6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -2,6 +2,34 @@
 #define PICKERCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QVector>
+
+#define DECIMAL_PLACES_POSITION         2
+#define DECIMAL_PLACES_ANGLE_DEGREES    1
+#define DECIMAL_PLACES_MASS_GRAMS       1
+
+#define DEFAULT_INCREMENT_POSITION_XY      0.01
+#define DEFAULT_INCREMENT_POSITION_Z       0.01
+#define DEFAULT_INCREMENT_ANGLE_DEGREES    5
+#define DEFAULT_INCREMENT_MASS_GRAMS       1
+
+#define PICKER_STATE_UNKNOWN      -1
+#define PICKER_STATE_STANDBY       0
+#define PICKER_STATE_GOTO_START    1
+#define PICKER_STATE_ATTACH        2
+#define PICKER_STATE_LIFT          3
+#define PICKER_STATE_GOTO_END      4
+#define PICKER_STATE_PUT_DOWN      5
+#define PICKER_STATE_SQUAT         6
+#define PICKER_STATE_JUMP          7
+
+#define PICKER_DEFAULT_X               0
+#define PICKER_DEFAULT_Y               0
+#define PICKER_DEFAULT_Z               0.4
+#define PICKER_DEFAULT_YAW_DEGREES     0
+#define PICKER_DEFAULT_MASS_GRAMS     30
+
+
 
 namespace Ui {
 class PickerControllerTab;
@@ -15,6 +43,164 @@ public:
     explicit PickerControllerTab(QWidget *parent = 0);
     ~PickerControllerTab();
 
+private:
+    int current_picker_state = PICKER_STATE_STANDBY;
+
+    void publish_setpoint_if_current_state_matches(QVector<int> state_to_match);
+
+    void publish_request_setpoint_change_for_state(int state_to_publish);
+
+private slots:
+    void on_button_goto_start_clicked();
+
+    void on_button_attach_clicked();
+
+    void on_button_lift_up_clicked();
+
+    void on_button_goto_end_clicked();
+
+    void on_button_put_down_clicked();
+
+    void on_button_squat_clicked();
+
+    void on_button_jump_clicked();
+
+    void on_button_standby_clicked();
+
+    void on_checkbox_goto_start_clicked();
+
+    void on_checkbox_attach_clicked();
+
+    void on_checkbox_lift_up_clicked();
+
+    void on_checkbox_goto_end_clicked();
+
+    void on_checkbox_put_down_clicked();
+
+    void on_checkbox_squat_clicked();
+
+    void on_checkbox_jump_clicked();
+
+    void on_checkbox_standby_clicked();
+
+    void on_button_goto_start_inc_minus_x_clicked();
+
+    void on_button_goto_start_inc_plus_x_clicked();
+
+    void on_button_goto_start_inc_minus_y_clicked();
+
+    void on_button_goto_start_inc_plus_y_clicked();
+
+    void on_button_goto_start_inc_minus_z_clicked();
+
+    void on_button_goto_start_inc_plus_z_clicked();
+
+    void on_button_goto_start_inc_minus_yaw_clicked();
+
+    void on_button_goto_start_inc_plus_yaw_clicked();
+
+    void on_button_attach_inc_minus_z_clicked();
+
+    void on_button_attach_inc_plus_z_clicked();
+
+    void on_button_lift_up_inc_minus_z_clicked();
+
+    void on_button_lift_up_inc_plus_z_clicked();
+
+    void on_button_lift_up_inc_minus_mass_clicked();
+
+    void on_button_lift_up_inc_plus_mass_clicked();
+
+    void on_button_goto_end_inc_minus_x_clicked();
+
+    void on_button_goto_end_inc_plus_x_clicked();
+
+    void on_button_goto_end_inc_minus_y_clicked();
+
+    void on_button_goto_end_inc_plus_y_clicked();
+
+    void on_button_goto_end_inc_minus_yaw_clicked();
+
+    void on_button_goto_end_inc_plus_yaw_clicked();
+
+    void on_button_put_down_inc_minus_z_clicked();
+
+    void on_button_put_down_inc_plus_z_clicked();
+
+    void on_button_squat_inc_minus_z_clicked();
+
+    void on_button_squat_inc_plus_z_clicked();
+
+    void on_button_jump_inc_minus_z_clicked();
+
+    void on_button_jump_inc_plus_z_clicked();
+
+    void on_button_stanby_inc_minus_x_clicked();
+
+    void on_button_stanby_inc_plus_x_clicked();
+
+    void on_button_stanby_inc_minus_y_clicked();
+
+    void on_button_stanby_inc_plus_y_clicked();
+
+    void on_button_stanby_inc_minus_z_clicked();
+
+    void on_button_stanby_inc_plus_z_clicked();
+
+    void on_button_stanby_inc_minus_yaw_clicked();
+
+    void on_button_stanby_inc_plus_yaw_clicked();
+
+    void on_button_stanby_inc_minus_mass_clicked();
+
+    void on_button_stanby_inc_plus_mass_clicked();
+
+    void on_lineEdit_goto_start_x_editingFinished();
+
+    void on_lineEdit_goto_start_y_editingFinished();
+
+    void on_lineEdit_goto_start_z_editingFinished();
+
+    void on_lineEdit_goto_start_yaw_editingFinished();
+
+    void on_lineEdit_attach_z_editingFinished();
+
+    void on_lineEdit_lift_up_z_editingFinished();
+
+    void on_lineEdit_lift_up_mass_editingFinished();
+
+    void on_lineEdit_goto_end_x_editingFinished();
+
+    void on_lineEdit_goto_end_y_editingFinished();
+
+    void on_lineEdit_goto_end_yaw_editingFinished();
+
+    void on_lineEdit_put_down_z_editingFinished();
+
+    void on_lineEdit_squat_z_editingFinished();
+
+    void on_lineEdit_jump_z_editingFinished();
+
+    void on_lineEdit_standby_x_editingFinished();
+
+    void on_lineEdit_standby_y_editingFinished();
+
+    void on_lineEdit_standby_z_editingFinished();
+
+    void on_lineEdit_standby_yaw_editingFinished();
+
+    void on_lineEdit_standby_mass_editingFinished();
+
+    void on_lineEdit_increment_x_editingFinished();
+
+    void on_lineEdit_increment_y_editingFinished();
+
+    void on_lineEdit_increment_z_editingFinished();
+
+    void on_lineEdit_increment_yaw_editingFinished();
+
+    void on_lineEdit_increment_mass_editingFinished();
+
 private:
     Ui::PickerControllerTab *ui;
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index f71f7205..f8cc168e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -6,9 +6,1346 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
     ui(new Ui::PickerControllerTab)
 {
     ui->setupUi(this);
+
+
+    // HIDE ALL THE "GREEN FRAMES"
+    ui->frame_goto_start_active->setVisible(false);
+    ui->frame_attach_active->setVisible(false);
+    ui->frame_lift_up_active->setVisible(false);
+    ui->frame_goto_end_active->setVisible(false);
+    ui->frame_put_down_active->setVisible(false);
+    ui->frame_squat_active->setVisible(false);
+    ui->frame_jump_active->setVisible(false);
+    ui->frame_standby_active->setVisible(false);
+
+    // SET DEFAULTS FOR THE INCREMENT
+    ui->lineEdit_increment_x   ->setText(QString::number( DEFAULT_INCREMENT_POSITION_XY,   'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_increment_y   ->setText(QString::number( DEFAULT_INCREMENT_POSITION_XY,   'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_increment_z   ->setText(QString::number( DEFAULT_INCREMENT_POSITION_Z,    'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_increment_yaw ->setText(QString::number( DEFAULT_INCREMENT_ANGLE_DEGREES, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    ui->lineEdit_increment_mass->setText(QString::number( DEFAULT_INCREMENT_MASS_GRAMS,    'f', DECIMAL_PLACES_MASS_GRAMS));
+
+    // SET THE INITIAL CHECKBOX STATE FOR SMOOTHING
+    ui->checkbox_goto_start->setChecked(true);
+    ui->checkbox_attach    ->setChecked(true);
+    ui->checkbox_lift_up   ->setChecked(true);
+    ui->checkbox_goto_end  ->setChecked(true);
+    ui->checkbox_put_down  ->setChecked(true);
+    ui->checkbox_squat     ->setChecked(true);
+    ui->checkbox_jump      ->setChecked(false);
+    ui->checkbox_standby   ->setChecked(true);
+    ui->checkbox_current   ->setChecked(false);
+
+    // SET THE INITIAL CHECKBOX STATE FOR PUBLISHING EVERY CHANGED VALUE
+    ui->checkbox_should_publish_value_changed->setChecked(true);
 }
 
 PickerControllerTab::~PickerControllerTab()
 {
     delete ui;
 }
+
+
+
+
+
+
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+// PUBLISH CHANGES IN STATE AND SETPOINT
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+
+void PickerControllerTab::publish_setpoint_if_current_state_matches(QVector<int> state_to_match)
+{
+    if ( state_to_match.contains(current_picker_state) )
+    {
+        publish_request_setpoint_change_for_state(current_picker_state);
+    }
+}
+
+void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to_publish)
+{
+    // Initiliase variables for the setpoing
+    bool req_should_smooth;
+    float req_x;
+    float req_y;
+    float req_z;
+    float req_yaw;
+    float req_mass;
+
+
+    // Switch between the possible states and get the respectively
+    // values for the setpoint
+    switch (state_to_publish)
+    {
+    case PICKER_STATE_STANDBY:
+    {
+        req_should_smooth = ui->checkbox_standby->isChecked();
+        req_x    = (ui->lineEdit_standby_x   ->text()).toFloat();
+        req_y    = (ui->lineEdit_standby_y   ->text()).toFloat();
+        req_z    = (ui->lineEdit_standby_z   ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_standby_yaw ->text()).toFloat();
+        req_mass = (ui->lineEdit_standby_mass->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_GOTO_START:
+    {
+        req_should_smooth = ui->checkbox_goto_start->isChecked();
+        req_x    = (ui->lineEdit_goto_start_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_start_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_goto_start_z  ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_standby_mass  ->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_ATTACH:
+    {
+        req_should_smooth = ui->checkbox_attach->isChecked();
+        req_x    = (ui->lineEdit_goto_start_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_start_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_attach_z      ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_standby_mass  ->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_LIFT:
+    {
+        req_should_smooth = ui->checkbox_lift_up->isChecked();
+        req_x    = (ui->lineEdit_goto_start_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_start_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_lift_up_z     ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_lift_up_mass  ->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_GOTO_END:
+    {
+        req_should_smooth = ui->checkbox_goto_end->isChecked();
+        req_x    = (ui->lineEdit_goto_end_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_end_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_lift_up_z   ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_lift_up_mass->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_PUT_DOWN:
+    {
+        req_should_smooth = ui->checkbox_put_down->isChecked();
+        req_x    = (ui->lineEdit_goto_end_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_end_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_put_down_z  ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_lift_up_mass->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_SQUAT:
+    {
+        req_should_smooth = ui->checkbox_squat->isChecked();
+        req_x    = (ui->lineEdit_goto_end_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_end_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_squat_z     ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_standby_mass->text()).toFloat();
+        break;
+    }
+    case PICKER_STATE_JUMP:
+    {
+        req_should_smooth = ui->checkbox_jump->isChecked();
+        req_x    = (ui->lineEdit_goto_end_x  ->text()).toFloat();
+        req_y    = (ui->lineEdit_goto_end_y  ->text()).toFloat();
+        req_z    = (ui->lineEdit_jump_z      ->text()).toFloat();
+        req_yaw  = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+        req_mass = (ui->lineEdit_standby_mass->text()).toFloat();
+        break;
+    }
+    default:
+    {
+        req_should_smooth = true;
+        req_x    = PICKER_DEFAULT_X;
+        req_y    = PICKER_DEFAULT_Y;
+        req_z    = PICKER_DEFAULT_Z;
+        req_yaw  = PICKER_DEFAULT_YAW_DEGREES;
+        req_mass = PICKER_DEFAULT_MASS_GRAMS;
+        break;
+    }
+    }
+
+    // Publish a ROS message with the setpoint to be requested
+
+}
+
+
+
+
+
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+// STATE BUTTONS CLICKED
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+
+void PickerControllerTab::on_button_goto_start_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_GOTO_START);
+}
+
+void PickerControllerTab::on_button_attach_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_ATTACH);
+}
+
+void PickerControllerTab::on_button_lift_up_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_LIFT);
+}
+
+void PickerControllerTab::on_button_goto_end_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_GOTO_END);
+}
+
+void PickerControllerTab::on_button_put_down_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_PUT_DOWN);
+}
+
+void PickerControllerTab::on_button_squat_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_SQUAT);
+}
+
+void PickerControllerTab::on_button_jump_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_JUMP);
+}
+
+void PickerControllerTab::on_button_standby_clicked()
+{
+    // Directly call the function that publishes state (and setpoint) changes
+    publish_request_setpoint_change_for_state(PICKER_STATE_STANDBY);
+}
+
+
+
+
+
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+// CHECK BOXES CLICKED
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+
+void PickerControllerTab::on_checkbox_goto_start_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_attach_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_lift_up_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_goto_end_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_put_down_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_squat_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_jump_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_checkbox_standby_clicked()
+{
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+
+
+
+
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+// INCREMENT BUTTONS CLICKED
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+
+// >> FOR GOTO START
+
+void PickerControllerTab::on_button_goto_start_inc_minus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_start_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_plus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_start_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_minus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_start_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_plus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_start_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_start_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_start_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_minus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_start_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_start_inc_plus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_start_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR ATTACH
+
+void PickerControllerTab::on_button_attach_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_attach_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_attach_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_attach_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_attach_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_attach_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR LIFT UP
+
+void PickerControllerTab::on_button_lift_up_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_lift_up_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_lift_up_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_lift_up_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_lift_up_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_lift_up_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_lift_up_inc_minus_mass_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_lift_up_mass->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_mass ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_lift_up_mass->setText(QString::number( new_value, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_lift_up_inc_plus_mass_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_lift_up_mass->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_mass ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_lift_up_mass->setText(QString::number( new_value, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR GOTO END
+
+void PickerControllerTab::on_button_goto_end_inc_minus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_end_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_end_inc_plus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_end_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_end_inc_minus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_end_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_end_inc_plus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_end_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_end_inc_minus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_goto_end_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_goto_end_inc_plus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_goto_end_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR PUT DOWN
+
+void PickerControllerTab::on_button_put_down_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_put_down_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_put_down_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_put_down_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_put_down_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_put_down_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR SQUAT
+
+void PickerControllerTab::on_button_squat_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_squat_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_squat_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_squat_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_squat_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_squat_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR JUMP
+
+void PickerControllerTab::on_button_jump_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_jump_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_jump_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_jump_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_jump_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_jump_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR STANDBY
+
+void PickerControllerTab::on_button_stanby_inc_minus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_standby_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_plus_x_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_x->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_x ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_standby_x->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_minus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_standby_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_plus_y_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_y->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_y ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_standby_y->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_minus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_standby_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_plus_z_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_z->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_z ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_standby_z->setText(QString::number( new_value, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_minus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_standby_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_plus_yaw_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_yaw->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_yaw ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_standby_yaw->setText(QString::number( new_value, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_minus_mass_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_mass->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_mass ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value - current_inc;
+    ui->lineEdit_standby_mass->setText(QString::number( new_value, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_button_stanby_inc_plus_mass_clicked()
+{
+    // Get the value from the respective line edit and increment
+    float current_value = (ui->lineEdit_standby_mass->text()).toFloat();
+    float current_inc   = (ui->lineEdit_increment_mass ->text()).toFloat();
+    // Compute the new value and set it back
+    float new_value = current_value + current_inc;
+    ui->lineEdit_standby_mass->setText(QString::number( new_value, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+
+
+
+
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+// LINE EDITS FINISHED EDITING
+// ---------------------------------------------------------- //
+// ---------------------------------------------------------- //
+
+// >> FOR GOTO START
+
+void PickerControllerTab::on_lineEdit_goto_start_x_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_start_x->text()).toFloat();
+    ui->lineEdit_goto_start_x->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_goto_start_y_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_start_y->text()).toFloat();
+    ui->lineEdit_goto_start_y->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_goto_start_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_start_z->text()).toFloat();
+    ui->lineEdit_goto_start_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_goto_start_yaw_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_start_yaw->text()).toFloat();
+    ui->lineEdit_goto_start_yaw->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR ATTACH
+
+void PickerControllerTab::on_lineEdit_attach_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_attach_z->text()).toFloat();
+    ui->lineEdit_attach_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR LIFT UP
+
+void PickerControllerTab::on_lineEdit_lift_up_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_lift_up_z->text()).toFloat();
+    ui->lineEdit_lift_up_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_lift_up_mass_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_lift_up_mass->text()).toFloat();
+    ui->lineEdit_lift_up_mass->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR GOTO END
+
+void PickerControllerTab::on_lineEdit_goto_end_x_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_end_x->text()).toFloat();
+    ui->lineEdit_goto_end_x->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_goto_end_y_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_end_y->text()).toFloat();
+    ui->lineEdit_goto_end_y->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_goto_end_yaw_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_goto_end_yaw->text()).toFloat();
+    ui->lineEdit_goto_end_yaw->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR PUT DOWN
+
+void PickerControllerTab::on_lineEdit_put_down_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_put_down_z->text()).toFloat();
+    ui->lineEdit_put_down_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR SQUAT
+
+void PickerControllerTab::on_lineEdit_squat_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_squat_z->text()).toFloat();
+    ui->lineEdit_squat_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR JUMP
+
+void PickerControllerTab::on_lineEdit_jump_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_jump_z->text()).toFloat();
+    ui->lineEdit_jump_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR  STANDBY
+
+void PickerControllerTab::on_lineEdit_standby_x_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_standby_x->text()).toFloat();
+    ui->lineEdit_standby_x->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_standby_y_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_standby_y->text()).toFloat();
+    ui->lineEdit_standby_y->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_standby_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_standby_z->text()).toFloat();
+    ui->lineEdit_standby_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_standby_yaw_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_standby_yaw->text()).toFloat();
+    ui->lineEdit_standby_yaw->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+void PickerControllerTab::on_lineEdit_standby_mass_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_standby_mass->text()).toFloat();
+    ui->lineEdit_standby_mass->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_MASS_GRAMS));
+    // Call the function to publish the new setpoint if appropriate
+    if (ui->checkbox_should_publish_value_changed->isChecked())
+    {
+        QVector<int> states_for_which_this_change_applies;
+        states_for_which_this_change_applies.append(PICKER_STATE_STANDBY);
+        states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
+        states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
+        states_for_which_this_change_applies.append(PICKER_STATE_SQUAT);
+        states_for_which_this_change_applies.append(PICKER_STATE_JUMP);
+        publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
+    }
+}
+
+// >> FOR INCREMENTS
+
+void PickerControllerTab::on_lineEdit_increment_x_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_increment_x->text()).toFloat();
+    ui->lineEdit_increment_x->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+}
+
+void PickerControllerTab::on_lineEdit_increment_y_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_increment_y->text()).toFloat();
+    ui->lineEdit_increment_y->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+}
+
+void PickerControllerTab::on_lineEdit_increment_z_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_increment_z->text()).toFloat();
+    ui->lineEdit_increment_z->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_POSITION));
+}
+
+void PickerControllerTab::on_lineEdit_increment_yaw_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_increment_yaw->text()).toFloat();
+    ui->lineEdit_increment_yaw->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+}
+
+void PickerControllerTab::on_lineEdit_increment_mass_editingFinished()
+{
+    // Get the value and set it back with two decimal places
+    float value_entered = (ui->lineEdit_increment_mass->text()).toFloat();
+    ui->lineEdit_increment_mass->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_MASS_GRAMS));
+}
-- 
GitLab


From 1619928d9cb6b8813b098254ae99023f4d579198 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 3 Feb 2019 10:40:39 +0100
Subject: [PATCH 35/87] Added ROS connections in the Picker GUI. Next step to
 update the PickerControlService to the new standards (by mimicking the
 StudentControllerService

---
 .../forms/pickercontrollertab.ui              | 402 ++++++++----
 .../include/pickercontrollertab.h             |  96 ++-
 .../src/pickercontrollertab.cpp               | 610 +++++++++++++++++-
 .../src/d_fall_pps/msg/SetpointWithHeader.msg |   1 +
 4 files changed, 967 insertions(+), 142 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
index 0527a979..e12164b6 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
@@ -7,7 +7,7 @@
     <x>0</x>
     <y>0</y>
     <width>1978</width>
-    <height>1188</height>
+    <height>1312</height>
    </rect>
   </property>
   <property name="font">
@@ -2389,124 +2389,304 @@
         </widget>
        </item>
        <item row="22" column="4">
-        <widget class="QLineEdit" name="lineEdit_measured_x">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+        <layout class="QHBoxLayout" name="horizontalLayout_20">
+         <property name="spacing">
+          <number>0</number>
          </property>
-         <property name="readOnly">
-          <bool>true</bool>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_measured_x">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_x_unavailable">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="horizontalSpacer_2">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
+       </item>
+       <item row="22" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_36">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_measured_yaw">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_yaw_unavailable">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="horizontalSpacer_3">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
        </item>
        <item row="22" column="7">
-        <widget class="QLineEdit" name="lineEdit_measured_z">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
+        <layout class="QHBoxLayout" name="horizontalLayout_37">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_measured_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_z_unavailable">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="horizontalSpacer_4">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
        </item>
        <item row="22" column="6">
-        <widget class="QLineEdit" name="lineEdit_measured_y">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
-         </property>
-        </widget>
-       </item>
-       <item row="22" column="8">
-        <widget class="QLineEdit" name="lineEdit_measured_yaw">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
+        <layout class="QHBoxLayout" name="horizontalLayout_38">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_measured_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_y_unavailable">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="horizontalSpacer_5">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
        </item>
       </layout>
      </item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 1a49ebd6..0e428a13 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -2,7 +2,9 @@
 #define PICKERCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QMutex>
 #include <QVector>
+#include <QTextStream>
 
 #define DECIMAL_PLACES_POSITION         2
 #define DECIMAL_PLACES_ANGLE_DEGREES    1
@@ -11,13 +13,13 @@
 #define DEFAULT_INCREMENT_POSITION_XY      0.01
 #define DEFAULT_INCREMENT_POSITION_Z       0.01
 #define DEFAULT_INCREMENT_ANGLE_DEGREES    5
-#define DEFAULT_INCREMENT_MASS_GRAMS       1
+#define DEFAULT_INCREMENT_MASS_GRAMS       0.5
 
 #define PICKER_STATE_UNKNOWN      -1
 #define PICKER_STATE_STANDBY       0
 #define PICKER_STATE_GOTO_START    1
 #define PICKER_STATE_ATTACH        2
-#define PICKER_STATE_LIFT          3
+#define PICKER_STATE_LIFT_UP       3
 #define PICKER_STATE_GOTO_END      4
 #define PICKER_STATE_PUT_DOWN      5
 #define PICKER_STATE_SQUAT         6
@@ -29,6 +31,36 @@
 #define PICKER_DEFAULT_YAW_DEGREES     0
 #define PICKER_DEFAULT_MASS_GRAMS     30
 
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+//#include "d_fall_pps/CustomButtonWithHeader.h"
+
+// Include the DFALL service types
+#include "d_fall_pps/GetSetpointService.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
+#endif
+
 
 
 namespace Ui {
@@ -43,12 +75,14 @@ public:
     explicit PickerControllerTab(QWidget *parent = 0);
     ~PickerControllerTab();
 
-private:
-    int current_picker_state = PICKER_STATE_STANDBY;
 
-    void publish_setpoint_if_current_state_matches(QVector<int> state_to_match);
 
-    void publish_request_setpoint_change_for_state(int state_to_publish);
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSlot();
+
+
 
 private slots:
     void on_button_goto_start_clicked();
@@ -201,8 +235,58 @@ private slots:
 
     void on_lineEdit_increment_mass_editingFinished();
 
+
+
 private:
     Ui::PickerControllerTab *ui;
+
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES
+
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+    // THE CURRENT STATE OF THE PICKER
+    int current_picker_state = PICKER_STATE_STANDBY;
+
+#ifdef CATKIN_MAKE
+    // PUBLISHER
+    // > For requesting the setpoint to be changed
+    ros::Publisher requestSetpointChangePublisher;
+
+    // SUBSCRIBER
+    // > For being notified when the setpoint is changed
+    ros::Subscriber setpointChangedSubscriber;
+#endif
+
+
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+#ifdef CATKIN_MAKE
+    // For receiving message that the setpoint was changed
+    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+
+    // Fill the header for a message
+    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
+#endif
+
+    void publish_setpoint_if_current_state_matches(QVector<int> state_to_match);
+
+    void publish_request_setpoint_change_for_state(int state_to_publish);
 };
 
 #endif // PICKERCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index f8cc168e..17b4ef60 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -9,14 +9,15 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
 
 
     // HIDE ALL THE "GREEN FRAMES"
+    // > These indicate which state is currently active
     ui->frame_goto_start_active->setVisible(false);
-    ui->frame_attach_active->setVisible(false);
-    ui->frame_lift_up_active->setVisible(false);
-    ui->frame_goto_end_active->setVisible(false);
-    ui->frame_put_down_active->setVisible(false);
-    ui->frame_squat_active->setVisible(false);
-    ui->frame_jump_active->setVisible(false);
-    ui->frame_standby_active->setVisible(false);
+    ui->frame_attach_active    ->setVisible(false);
+    ui->frame_lift_up_active   ->setVisible(false);
+    ui->frame_goto_end_active  ->setVisible(false);
+    ui->frame_put_down_active  ->setVisible(false);
+    ui->frame_squat_active     ->setVisible(false);
+    ui->frame_jump_active      ->setVisible(false);
+    ui->frame_standby_active   ->setVisible(false);
 
     // SET DEFAULTS FOR THE INCREMENT
     ui->lineEdit_increment_x   ->setText(QString::number( DEFAULT_INCREMENT_POSITION_XY,   'f', DECIMAL_PLACES_POSITION));
@@ -38,6 +39,99 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
 
     // SET THE INITIAL CHECKBOX STATE FOR PUBLISHING EVERY CHANGED VALUE
     ui->checkbox_should_publish_value_changed->setChecked(true);
+
+    // HIDE ALL THE "RED FRAMES"
+    // > These indicate when an occuled measurement is recieved
+    ui->frame_x_unavailable  ->setVisible(false);
+    ui->frame_y_unavailable  ->setVisible(false);
+    ui->frame_z_unavailable  ->setVisible(false);
+    ui->frame_yaw_unavailable->setVisible(false);
+
+    // SET DEFAULTS FOR ALL THE {x,y,z,yaw,mass} LineEdits
+    // > For Goto Start
+    ui->lineEdit_goto_start_x  ->setText(QString::number( PICKER_DEFAULT_X,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_goto_start_y  ->setText(QString::number( PICKER_DEFAULT_Y,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_goto_start_z  ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_goto_start_yaw->setText(QString::number( PICKER_DEFAULT_YAW_DEGREES, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // > For Attach
+    ui->lineEdit_attach_z      ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    // > For Lift Up
+    ui->lineEdit_lift_up_z     ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_lift_up_mass  ->setText(QString::number( PICKER_DEFAULT_MASS_GRAMS,  'f', DECIMAL_PLACES_MASS_GRAMS));
+    // > For Goto End
+    ui->lineEdit_goto_end_x    ->setText(QString::number( PICKER_DEFAULT_X,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_goto_end_y    ->setText(QString::number( PICKER_DEFAULT_Y,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_goto_end_yaw  ->setText(QString::number( PICKER_DEFAULT_YAW_DEGREES, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    // > For Put Down
+    ui->lineEdit_put_down_z    ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    // > For Squat
+    ui->lineEdit_squat_z       ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    // > For Jump
+    ui->lineEdit_jump_z        ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    // > For Standby
+    ui->lineEdit_standby_x     ->setText(QString::number( PICKER_DEFAULT_X,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_standby_y     ->setText(QString::number( PICKER_DEFAULT_Y,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_standby_z     ->setText(QString::number( PICKER_DEFAULT_Z,           'f', DECIMAL_PLACES_POSITION));
+    ui->lineEdit_standby_yaw   ->setText(QString::number( PICKER_DEFAULT_YAW_DEGREES, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+    ui->lineEdit_standby_mass  ->setText(QString::number( PICKER_DEFAULT_MASS_GRAMS,  'f', DECIMAL_PLACES_MASS_GRAMS));
+
+
+
+
+
+#ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[PICKER CONTROLLER TAB GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[PICKER CONTROLLER TAB GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("PickerControllerService/RequestSetpointChange", 1);
+
+    // SUBSCRIBE TO SETPOINT CHANGES
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("PickerControllerService/SetpointChanged", 1, &PickerControllerTab::setpointChangedCallback, this);
+    }
+
+    // GET THE CURRENT SETPOINT
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[PICKER CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+    }
+
+#endif
 }
 
 PickerControllerTab::~PickerControllerTab()
@@ -109,7 +203,7 @@ void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to
         req_mass = (ui->lineEdit_standby_mass  ->text()).toFloat();
         break;
     }
-    case PICKER_STATE_LIFT:
+    case PICKER_STATE_LIFT_UP:
     {
         req_should_smooth = ui->checkbox_lift_up->isChecked();
         req_x    = (ui->lineEdit_goto_start_x  ->text()).toFloat();
@@ -172,7 +266,239 @@ void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to
     }
 
     // Publish a ROS message with the setpoint to be requested
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    d_fall_pps::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw,mass) values
+    msg.x    = req_x;
+    msg.y    = req_y;
+    msg.z    = req_z;
+    msg.yaw  = req_yaw * DEG2RAD;
+    msg.mass = req_mass;
+
+    // Fill in the "should smooth" value
+    msg.isChecked = req_should_smooth;
+
+    // Fill in the "picker state" value
+    msg.buttonID = state_to_publish;
+
+    // Publish the setpoint
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[PICKER CONTROLLER GUI] Published request for setpoint change to: [" << req_x << ", "<< req_y << ", "<< req_z << ", "<< req_yaw << "], with {mass,smooth,state} = " << req_mass << ", "<< req_should_smooth << ", "<< state_to_publish );
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[PICKER CONTROLLER GUI] would publish request for: [" << req_x << ", "<< req_y << ", "<< req_z << ", "<< req_yaw << "], with {mass,smooth,state} = " << req_mass << ", "<< req_should_smooth << ", "<< state_to_publish;
+#endif
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC  H   H    A    N   N   GGGG  EEEEE  DDDD
+//    C      H   H   A A   NN  N  G      E      D   D
+//    C      HHHHH  A   A  N N N  G      EEE    D   D
+//    C      H   H  AAAAA  N  NN  G   G  E      D   D
+//     CCCC  H   H  A   A  N   N   GGGG  EEEEE  DDDD
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void PickerControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+{
+    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+    QString qstr = "";
+
+    // EXTRACT THE SETPOINT
+    float x   = newSetpoint.x;
+    float y   = newSetpoint.y;
+    float z   = newSetpoint.z;
+    float yaw = newSetpoint.yaw;
+
+    float mass    = newSetpoint.yaw;
+    bool  smooth  = newSetpoint.isChecked;
+    int   state   = newSetpoint.buttonID;
+
+    // UPDATE THE SETPOINT LineEdits
+    if (x < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_current_x->setText(qstr + QString::number( x, 'f', DECIMAL_PLACES_POSITION));
+    if (y < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_current_y->setText(qstr + QString::number( y, 'f', DECIMAL_PLACES_POSITION));
+    if (z < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_current_z->setText(qstr + QString::number( z, 'f', DECIMAL_PLACES_POSITION));
+
+    if (yaw < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+
+    ui->lineEdit_current_mass->setText(qstr + QString::number( mass, 'f', DECIMAL_PLACES_MASS_GRAMS));
+
+    ui->checkbox_current->setChecked(smooth);
+
+
+    // MAKE THE "GREEN FRAME" VISIBLE ONLY FOR THE CURRENT STATE
+
+    // First make all of them NOT visible
+    ui->frame_goto_start_active->setVisible(false);
+    ui->frame_attach_active    ->setVisible(false);
+    ui->frame_lift_up_active   ->setVisible(false);
+    ui->frame_goto_end_active  ->setVisible(false);
+    ui->frame_put_down_active  ->setVisible(false);
+    ui->frame_squat_active     ->setVisible(false);
+    ui->frame_jump_active      ->setVisible(false);
+    ui->frame_standby_active   ->setVisible(false);
+
+    // Switch between the possible states
+    switch (state)
+    {
+    case PICKER_STATE_STANDBY:
+    {
+        ui->frame_standby_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_GOTO_START:
+    {
+        ui->frame_goto_start_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_ATTACH:
+    {
+        ui->frame_attach_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_LIFT_UP:
+    {
+        ui->frame_lift_up_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_GOTO_END:
+    {
+        ui->frame_goto_end_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_PUT_DOWN:
+    {
+        ui->frame_put_down_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_SQUAT:
+    {
+        ui->frame_squat_active->setVisible(true);
+        break;
+    }
+    case PICKER_STATE_JUMP:
+    {
+        ui->frame_standby_active->setVisible(true);
+        break;
+    }
+    default:
+    {
+        break;
+    }
+    }
+
+}
+#endif
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
+//    P   P  O   O  S      E         D   D   A A     T     A A
+//    PPPP   O   O   SSS   EEE       D   D  A   A    T    A   A
+//    P      O   O      S  E         D   D  AAAAA    T    AAAAA
+//    P       OOO   SSSS   EEEEE     DDDD   A   A    T    A   A
+//    ----------------------------------------------------------------------------------
+
+
+void PickerControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+{
+    if (!occluded)
+    {
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+        QString qstr = "";
+        // UPDATE THE MEASUREMENT COLUMN
+        if (x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', DECIMAL_PLACES_POSITION));
+        if (y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', DECIMAL_PLACES_POSITION));
+        if (z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', DECIMAL_PLACES_POSITION));
+
+        if (yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+
+        // GET THE CURRENT SETPOINT
+        float error_x   = x   - (ui->lineEdit_current_x->text()  ).toFloat();
+        float error_y   = y   - (ui->lineEdit_current_y->text()  ).toFloat();
+        float error_z   = z   - (ui->lineEdit_current_z->text()  ).toFloat();
+        float error_yaw = yaw - (ui->lineEdit_current_yaw->text()).toFloat();
+
+        // UPDATE THE ERROR COLUMN
+        if (error_x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_x->setText(qstr + QString::number( error_x, 'f', DECIMAL_PLACES_POSITION));
+        if (error_y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_y->setText(qstr + QString::number( error_y, 'f', DECIMAL_PLACES_POSITION));
+        if (error_z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', DECIMAL_PLACES_POSITION));
+
+        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+
+        // Ensure the red frames are not visible
+        if ( ui->frame_x_unavailable->isVisible() )
+        {
+            ui->frame_x_unavailable  ->setVisible(false);
+            ui->frame_y_unavailable  ->setVisible(false);
+            ui->frame_z_unavailable  ->setVisible(false);
+            ui->frame_yaw_unavailable->setVisible(false);
+        }
+    }
+    else
+    {
+        // Make visible the red frames to indicate occluded
+        if ( !(ui->frame_x_unavailable->isVisible()) )
+        {
+            ui->frame_x_unavailable  ->setVisible(true);
+            ui->frame_y_unavailable  ->setVisible(true);
+            ui->frame_z_unavailable  ->setVisible(true);
+            ui->frame_yaw_unavailable->setVisible(true);
+        }
+    }
+}
 
+
+void PickerControllerTab::poseDataUnavailableSlot()
+{
+    ui->lineEdit_measured_x->setText("xx.xx");
+    ui->lineEdit_measured_y->setText("xx.xx");
+    ui->lineEdit_measured_z->setText("xx.xx");
+
+    ui->lineEdit_measured_yaw->setText("xx.xx");
+
+    ui->lineEdit_error_x->setText("xx.xx");
+    ui->lineEdit_error_y->setText("xx.xx");
+    ui->lineEdit_error_z->setText("xx.xx");
+    ui->lineEdit_error_yaw->setText("xx.xx");
 }
 
 
@@ -200,7 +526,7 @@ void PickerControllerTab::on_button_attach_clicked()
 void PickerControllerTab::on_button_lift_up_clicked()
 {
     // Directly call the function that publishes state (and setpoint) changes
-    publish_request_setpoint_change_for_state(PICKER_STATE_LIFT);
+    publish_request_setpoint_change_for_state(PICKER_STATE_LIFT_UP);
 }
 
 void PickerControllerTab::on_button_goto_end_clicked()
@@ -271,7 +597,7 @@ void PickerControllerTab::on_checkbox_lift_up_clicked()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -357,7 +683,7 @@ void PickerControllerTab::on_button_goto_start_inc_minus_x_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -376,7 +702,7 @@ void PickerControllerTab::on_button_goto_start_inc_plus_x_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -395,7 +721,7 @@ void PickerControllerTab::on_button_goto_start_inc_minus_y_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -414,7 +740,7 @@ void PickerControllerTab::on_button_goto_start_inc_plus_y_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -467,7 +793,7 @@ void PickerControllerTab::on_button_goto_start_inc_minus_yaw_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -486,7 +812,7 @@ void PickerControllerTab::on_button_goto_start_inc_plus_yaw_clicked()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -541,7 +867,7 @@ void PickerControllerTab::on_button_lift_up_inc_minus_z_clicked()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
@@ -559,7 +885,7 @@ void PickerControllerTab::on_button_lift_up_inc_plus_z_clicked()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
@@ -577,7 +903,7 @@ void PickerControllerTab::on_button_lift_up_inc_minus_mass_clicked()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
@@ -596,7 +922,7 @@ void PickerControllerTab::on_button_lift_up_inc_plus_mass_clicked()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
@@ -1036,7 +1362,7 @@ void PickerControllerTab::on_lineEdit_goto_start_x_editingFinished()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -1052,7 +1378,7 @@ void PickerControllerTab::on_lineEdit_goto_start_y_editingFinished()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -1082,7 +1408,7 @@ void PickerControllerTab::on_lineEdit_goto_start_yaw_editingFinished()
         QVector<int> states_for_which_this_change_applies;
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_START);
         states_for_which_this_change_applies.append(PICKER_STATE_ATTACH);
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
 }
@@ -1114,7 +1440,7 @@ void PickerControllerTab::on_lineEdit_lift_up_z_editingFinished()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
     }
@@ -1129,7 +1455,7 @@ void PickerControllerTab::on_lineEdit_lift_up_mass_editingFinished()
     if (ui->checkbox_should_publish_value_changed->isChecked())
     {
         QVector<int> states_for_which_this_change_applies;
-        states_for_which_this_change_applies.append(PICKER_STATE_LIFT);
+        states_for_which_this_change_applies.append(PICKER_STATE_LIFT_UP);
         states_for_which_this_change_applies.append(PICKER_STATE_GOTO_END);
         states_for_which_this_change_applies.append(PICKER_STATE_PUT_DOWN);
         publish_setpoint_if_current_state_matches(states_for_which_this_change_applies);
@@ -1349,3 +1675,237 @@ void PickerControllerTab::on_lineEdit_increment_mass_editingFinished()
     float value_entered = (ui->lineEdit_increment_mass->text()).toFloat();
     ui->lineEdit_increment_mass->setText(QString::number( value_entered, 'f', DECIMAL_PLACES_MASS_GRAMS));
 }
+
+
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void PickerControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
+        d_fall_pps::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[PICKER CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+
+        // SUBSCRIBERS
+        // > For receiving message that the setpoint was changed
+        setpointChangedSubscriber = agent_base_nodeHandle.subscribe("PickerControllerService/SetpointChanged", 1, &PickerControllerTab::setpointChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        setpointChangedSubscriber.shutdown();
+
+        // Set information back to the default
+        ui->lineEdit_current_x   ->setText("xx.xx");
+        ui->lineEdit_current_y   ->setText("xx.xx");
+        ui->lineEdit_current_z   ->setText("xx.xx");
+        ui->lineEdit_current_yaw ->setText("xx.xx");
+        ui->lineEdit_current_mass->setText("xx.xx");
+
+    }
+#endif
+}
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void PickerControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[PICKER CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool PickerControllerTab::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[PICKER CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[PICKER CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[PICKER CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[PICKER CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[PICKER CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[PICKER CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[PICKER CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
diff --git a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
index ff412908..cdf1562a 100644
--- a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
+++ b/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
@@ -2,6 +2,7 @@ float64 x
 float64 y
 float64 z
 float64 yaw
+float64 mass
 bool isChecked
 uint32 buttonID
 bool shouldCheckForAgentID
-- 
GitLab


From 41f9058f079f6c19c7bb9a05b0887e4e7c7508da Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Sun, 3 Feb 2019 11:26:35 +0100
Subject: [PATCH 36/87] Picker GUI was missing name for the current mass
 LineEdit

---
 .../GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui    | 2 +-
 .../d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp    | 8 ++++----
 2 files changed, 5 insertions(+), 5 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
index e12164b6..ad7dea1b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
@@ -2132,7 +2132,7 @@
         </widget>
        </item>
        <item row="18" column="9">
-        <widget class="QLineEdit" name="lineEdit">
+        <widget class="QLineEdit" name="lineEdit_current_mass">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 5f58fcdf..1c8f5232 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -110,14 +110,14 @@ TopBanner::TopBanner(QWidget *parent) :
     else if (m_type == TYPE_COORDINATOR)
     {
 		// Set the label appropriate for a cooridnator
-		QString qstr_title = "Flying Device GUI: for COORDINATOR ID ";
+		QString qstr_title = "Flying Agent GUI: for COORDINATOR ID ";
 		qstr_title.append( QString::number(m_ID) );
 		ui->top_banner_label->setText(qstr_title);
 	}
 	else
 	{
 		// Set the label to inform the user of the error
-		QString qstr_title = "Flying Device GUI: for UNKNOWN NODE TYPE";
+		QString qstr_title = "Flying Agent GUI: for UNKNOWN NODE TYPE";
 		ui->top_banner_label->setText(qstr_title);
     }
 
@@ -225,7 +225,7 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
 #endif
 
 	// Construct and set the string for the checkbox label
-	QString qstr_title = "Flying Device GUI: for AGENT ID ";
+	QString qstr_title = "Flying Agent GUI: for AGENT ID ";
 	qstr_title.append( QString::number(m_ID) );
 	qstr_title.append(", connected to ");
 	qstr_title.append(qstr_crazyflie_name);
@@ -298,7 +298,7 @@ void TopBanner::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoord
     else
     {
         // Set the label appropriate for a cooridnator
-        QString qstr_title = "Flying Device GUI: for COORDINATOR ID ";
+        QString qstr_title = "Flying Agent GUI: for COORDINATOR ID ";
         qstr_title.append( QString::number(m_ID) );
         ui->top_banner_label->setText(qstr_title);
 
-- 
GitLab


From 50a9eff3b14cbc4a9a42495fd724f846e642663f Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Sun, 3 Feb 2019 11:51:38 +0100
Subject: [PATCH 37/87] Fixed a few connections so that the picker GUI works
 with ROS. Still need to integrate with the PickerControllerService

---
 .../flyingAgentGUI/forms/controllertabs.ui    |  2 +-
 .../forms/enablecontrollerloadyamlbar.ui      |  8 ++--
 .../forms/pickercontrollertab.ui              | 40 +++++++++----------
 .../include/enablecontrollerloadyamlbar.h     | 16 ++++----
 .../flyingAgentGUI/src/controllertabs.cpp     | 21 ++++++++++
 .../src/enablecontrollerloadyamlbar.cpp       | 16 ++++----
 6 files changed, 62 insertions(+), 41 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index b4718911..928aa115 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -59,7 +59,7 @@
       </attribute>
       <layout class="QGridLayout" name="gridLayout_5">
        <item row="0" column="0">
-        <widget class="PickerControllerTab" name="widget_4" native="true"/>
+        <widget class="PickerControllerTab" name="picker_controller_tab_widget" native="true"/>
        </item>
       </layout>
      </widget>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index 0537109e..4201e18d 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -267,7 +267,7 @@
       </widget>
      </item>
      <item row="0" column="3">
-      <widget class="QPushButton" name="enable_demo_button">
+      <widget class="QPushButton" name="enable_picker_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -293,12 +293,12 @@
         </font>
        </property>
        <property name="text">
-        <string>Demo</string>
+        <string>Picker</string>
        </property>
       </widget>
      </item>
      <item row="1" column="3">
-      <widget class="QPushButton" name="load_yaml_demo_button">
+      <widget class="QPushButton" name="load_yaml_picker_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -318,7 +318,7 @@
         </size>
        </property>
        <property name="text">
-        <string>Demo</string>
+        <string>Picker</string>
        </property>
       </widget>
      </item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
index ad7dea1b..232408bd 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
@@ -120,12 +120,12 @@
           <widget class="QCheckBox" name="checkbox_goto_end">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1027,12 +1027,12 @@
           <widget class="QCheckBox" name="checkbox_attach">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1832,12 +1832,12 @@
           <widget class="QCheckBox" name="checkbox_goto_start">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1852,12 +1852,12 @@
           <widget class="QCheckBox" name="checkbox_jump">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1879,12 +1879,12 @@
           <widget class="QCheckBox" name="checkbox_put_down">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1899,12 +1899,12 @@
           <widget class="QCheckBox" name="checkbox_lift_up">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1922,12 +1922,12 @@
            </property>
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -1948,12 +1948,12 @@
           <widget class="QCheckBox" name="checkbox_squat">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -2254,12 +2254,12 @@
            </property>
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
             <string/>
@@ -2702,12 +2702,12 @@
         <widget class="QCheckBox" name="checkbox_should_publish_value_changed">
          <property name="maximumSize">
           <size>
-           <width>40</width>
+           <width>30</width>
            <height>16777215</height>
           </size>
          </property>
          <property name="styleSheet">
-          <string notr="true">QCheckBox::indicator{ width:40px ; height:40px }</string>
+          <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
          </property>
          <property name="text">
           <string/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index a5776823..53139bfe 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -40,12 +40,12 @@
 // operation state of this agent. These "commands"
 // are sent from this GUI node to the "PPSClient"
 // node where the command is enacted
-#define CMD_USE_SAFE_CONTROLLER      1
-#define CMD_USE_DEMO_CONTROLLER      2
-#define CMD_USE_STUDENT_CONTROLLER   3
-#define CMD_USE_MPC_CONTROLLER       4
-#define CMD_USE_REMOTE_CONTROLLER    5
-#define CMD_USE_TUNING_CONTROLLER    6
+// #define CMD_USE_SAFE_CONTROLLER      1
+// #define CMD_USE_DEMO_CONTROLLER      2
+// #define CMD_USE_STUDENT_CONTROLLER   3
+// #define CMD_USE_MPC_CONTROLLER       4
+// #define CMD_USE_REMOTE_CONTROLLER    5
+// #define CMD_USE_TUNING_CONTROLLER    6
 
 
 namespace Ui {
@@ -75,13 +75,13 @@ private slots:
 
     // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
     void on_enable_safe_button_clicked();
-    void on_enable_demo_button_clicked();
+    void on_enable_picker_button_clicked();
     void on_enable_student_button_clicked();
     void on_enable_default_button_clicked();
 
     // LOAD YAML BUTTONS ON-CLICK CALLBACK
     void on_load_yaml_safe_button_clicked();
-    void on_load_yaml_demo_button_clicked();
+    void on_load_yaml_picker_button_clicked();
     void on_load_yaml_student_button_clicked();
     void on_load_yaml_default_button_clicked();
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 88a4973c..7f58a1c9 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -31,6 +31,12 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->student_controller_tab_widget , &StudentControllerTab::setMeasuredPose
         );
 
+    QObject::connect(
+            this , &ControllerTabs::measuredPoseValueChanged ,
+            ui->picker_controller_tab_widget , &PickerControllerTab::setMeasuredPose
+        );
+
+
 
     // CONNECT THE "MEASUREMENTS UNAVAILABLE" SIGNAL TO
     // EACH OF THE TABS
@@ -44,6 +50,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->student_controller_tab_widget , &StudentControllerTab::poseDataUnavailableSlot
         );
 
+    QObject::connect(
+            this , &ControllerTabs::poseDataUnavailableSignal ,
+            ui->picker_controller_tab_widget , &PickerControllerTab::poseDataUnavailableSlot
+        );
+
 
     // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
     // WITH THE LIST OF AGENT IDs TO COORDINATE
@@ -60,6 +71,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->student_controller_tab_widget , &StudentControllerTab::setAgentIDsToCoordinate
         );
 
+    QObject::connect(
+            this , &ControllerTabs::agentIDsToCoordinateChanged ,
+            ui->picker_controller_tab_widget , &PickerControllerTab::setAgentIDsToCoordinate
+        );
+
     
 
 
@@ -289,6 +305,11 @@ void ControllerTabs::setControllerEnabled(int new_controller)
             //ui->controller_enabled_label->setText("Tuning");
             break;
         }
+        case PICKER_CONTROLLER:
+        {
+            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->picker_tab );
+            break;
+        }
         default:
         {
             //ui->controller_enabled_label->setText("Unknown");
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index 5458bcce..ca509b8f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -61,8 +61,8 @@ void EnableControllerLoadYamlBar::showHideController_student_changed()
 
 void EnableControllerLoadYamlBar::showHideController_picker_changed()
 {
-    ui->enable_demo_button   ->setHidden(    !(ui->enable_demo_button->isHidden()) );
-    ui->load_yaml_demo_button->setHidden( !(ui->load_yaml_demo_button->isHidden()) );
+    ui->enable_picker_button   ->setHidden(    !(ui->enable_picker_button->isHidden()) );
+    ui->load_yaml_picker_button->setHidden( !(ui->load_yaml_picker_button->isHidden()) );
 }
 
 void EnableControllerLoadYamlBar::showHideController_safe_changed()
@@ -89,14 +89,14 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_enable_demo_button_clicked()
+void EnableControllerLoadYamlBar::on_enable_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
     d_fall_pps::IntWithHeader msg;
     fillIntMessageHeader(msg);
-    msg.data = CMD_USE_DEMO_CONTROLLER;
+    msg.data = CMD_USE_PICKER_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Demo Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Picker Controller");
 #endif
 }
 
@@ -132,7 +132,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_safe_button_clicked()
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_load_yaml_demo_button_clicked()
+void EnableControllerLoadYamlBar::on_load_yaml_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
@@ -140,11 +140,11 @@ void EnableControllerLoadYamlBar::on_load_yaml_demo_button_clicked()
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
-    yaml_filename_msg.data = "DemoController";
+    yaml_filename_msg.data = "PickerController";
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
     // Inform the user that the menu item was selected
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Demo Controller YAML was clicked.");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Picker Controller YAML was clicked.");
 #endif
 }
 
-- 
GitLab


From e14ebf49122049d3367d927dfa59066013aba8b2 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Sun, 3 Feb 2019 16:35:41 +0100
Subject: [PATCH 38/87] Started with updating the picker controller service.
 Header fill is updated, cpp file needs updating

---
 ...PickerControllerConstants_for_Qt_compile.h |  56 +++
 .../include/pickercontrollertab.h             |  32 +-
 .../include/nodes/PickerControllerConstants.h |  56 +++
 .../include/nodes/PickerControllerService.h   | 403 +++++++++++++-----
 4 files changed, 418 insertions(+), 129 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
 create mode 100644 pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
new file mode 100644
index 00000000..3b1c36cd
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
@@ -0,0 +1,56 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    Constants that are used across the Picker Controler Service and GUI
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// TO IDENITFY THE STATE OF THE PICKER
+
+#define PICKER_STATE_UNKNOWN      -1
+#define PICKER_STATE_STANDBY       0
+#define PICKER_STATE_GOTO_START    1
+#define PICKER_STATE_ATTACH        2
+#define PICKER_STATE_LIFT_UP       3
+#define PICKER_STATE_GOTO_END      4
+#define PICKER_STATE_PUT_DOWN      5
+#define PICKER_STATE_SQUAT         6
+#define PICKER_STATE_JUMP          7
+
+
+
+// DEFAULT {x,y,z,yaw,mass}
+
+#define PICKER_DEFAULT_X               0
+#define PICKER_DEFAULT_Y               0
+#define PICKER_DEFAULT_Z               0.4
+#define PICKER_DEFAULT_YAW_DEGREES     0
+#define PICKER_DEFAULT_MASS_GRAMS     30
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 0e428a13..6247cc79 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -15,21 +15,21 @@
 #define DEFAULT_INCREMENT_ANGLE_DEGREES    5
 #define DEFAULT_INCREMENT_MASS_GRAMS       0.5
 
-#define PICKER_STATE_UNKNOWN      -1
-#define PICKER_STATE_STANDBY       0
-#define PICKER_STATE_GOTO_START    1
-#define PICKER_STATE_ATTACH        2
-#define PICKER_STATE_LIFT_UP       3
-#define PICKER_STATE_GOTO_END      4
-#define PICKER_STATE_PUT_DOWN      5
-#define PICKER_STATE_SQUAT         6
-#define PICKER_STATE_JUMP          7
-
-#define PICKER_DEFAULT_X               0
-#define PICKER_DEFAULT_Y               0
-#define PICKER_DEFAULT_Z               0.4
-#define PICKER_DEFAULT_YAW_DEGREES     0
-#define PICKER_DEFAULT_MASS_GRAMS     30
+// #define PICKER_STATE_UNKNOWN      -1
+// #define PICKER_STATE_STANDBY       0
+// #define PICKER_STATE_GOTO_START    1
+// #define PICKER_STATE_ATTACH        2
+// #define PICKER_STATE_LIFT_UP       3
+// #define PICKER_STATE_GOTO_END      4
+// #define PICKER_STATE_PUT_DOWN      5
+// #define PICKER_STATE_SQUAT         6
+// #define PICKER_STATE_JUMP          7
+
+// #define PICKER_DEFAULT_X               0
+// #define PICKER_DEFAULT_Y               0
+// #define PICKER_DEFAULT_Z               0.4
+// #define PICKER_DEFAULT_YAW_DEGREES     0
+// #define PICKER_DEFAULT_MASS_GRAMS     30
 
 #ifdef CATKIN_MAKE
 #include <ros/ros.h>
@@ -51,6 +51,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
+#include "nodes/PickerControllerConstants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
 //using namespace d_fall_pps;
@@ -58,6 +59,7 @@
 #else
 // Include the shared definitions
 #include "include/Constants_for_Qt_compile.h"
+#include "include/PickerControllerConstants_for_Qt_compile.h"
 
 #endif
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
new file mode 100644
index 00000000..3b1c36cd
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
@@ -0,0 +1,56 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    Constants that are used across the Picker Controler Service and GUI
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// TO IDENITFY THE STATE OF THE PICKER
+
+#define PICKER_STATE_UNKNOWN      -1
+#define PICKER_STATE_STANDBY       0
+#define PICKER_STATE_GOTO_START    1
+#define PICKER_STATE_ATTACH        2
+#define PICKER_STATE_LIFT_UP       3
+#define PICKER_STATE_GOTO_END      4
+#define PICKER_STATE_PUT_DOWN      5
+#define PICKER_STATE_SQUAT         6
+#define PICKER_STATE_JUMP          7
+
+
+
+// DEFAULT {x,y,z,yaw,mass}
+
+#define PICKER_DEFAULT_X               0
+#define PICKER_DEFAULT_Y               0
+#define PICKER_DEFAULT_Z               0.4
+#define PICKER_DEFAULT_YAW_DEGREES     0
+#define PICKER_DEFAULT_MASS_GRAMS     30
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index 69647983..e1cc4c15 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -50,20 +50,47 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
-//the generated structs from the msg-files have to be included
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+//#include "d_fall_pps/StringWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+//#include "d_fall_pps/CustomButtonWithHeader.h"
 #include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/SetpointV2.h"
-#include "d_fall_pps/ControlCommand.h"
+//#include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
 
-// Include the Parameter Service shared definitions
+//the generated structs from the msg-files have to be included
+// #include "d_fall_pps/Setpoint.h"
+// #include "d_fall_pps/SetpointV2.h"
+// #include "d_fall_pps/ControlCommand.h"
+// #include "d_fall_pps/CustomButton.h"
+
+// Include the DFALL service types
+#include "d_fall_pps/LoadYamlFromFilename.h"
+#include "d_fall_pps/GetSetpointService.h"
+
+// Include the shared definitions
 #include "nodes/Constants.h"
+#include "nodes/PickerContorllerConstants.h"
 
-#include <std_msgs/Int32.h>
-#include <std_msgs/Float32.h>
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+// Needed for having a ROS "bag" to store data for post-analysis
+//#include <rosbag/bag.h>
+
+
+
+
+
+// Namespacing the package
+using namespace d_fall_pps;
 
 
 
@@ -80,18 +107,18 @@
 // These constants are defined to make the code more readable and adaptable.
 
 // FOR WHICH BUTTON WAS PRESSED IN THE PICKER CONTOLLER
-#define PICKER_BUTTON_GOTOSTART     1
-#define PICKER_BUTTON_ATTACH        2
-#define PICKER_BUTTON_PICKUP        3
-#define PICKER_BUTTON_GOTOEND       4
-#define PICKER_BUTTON_PUTDOWN       5
-#define PICKER_BUTTON_SQUAT         6
-#define PICKER_BUTTON_JUMP          7
+// #define PICKER_BUTTON_GOTOSTART     1
+// #define PICKER_BUTTON_ATTACH        2
+// #define PICKER_BUTTON_PICKUP        3
+// #define PICKER_BUTTON_GOTOEND       4
+// #define PICKER_BUTTON_PUTDOWN       5
+// #define PICKER_BUTTON_SQUAT         6
+// #define PICKER_BUTTON_JUMP          7
 
-#define PICKER_BUTTON_1             11
-#define PICKER_BUTTON_2             12
-#define PICKER_BUTTON_3             13
-#define PICKER_BUTTON_4             14
+// #define PICKER_BUTTON_1             11
+// #define PICKER_BUTTON_2             12
+// #define PICKER_BUTTON_3             13
+// #define PICKER_BUTTON_4             14
 
 
 // These constants define the modes that can be used for controller the Crazyflie 2.0,
@@ -108,9 +135,9 @@
 //               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_MOTOR   6
-#define CF_COMMAND_TYPE_RATE    7
-#define CF_COMMAND_TYPE_ANGLE   8
+// #define CF_COMMAND_TYPE_MOTOR   6
+// #define CF_COMMAND_TYPE_RATE    7
+// #define CF_COMMAND_TYPE_ANGLE   8
 
 // These constants define the method used for estimating the Inertial
 // frame state.
@@ -130,13 +157,9 @@
 // ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED
 //       Uses the model of the quad-rotor and the previous inputs
 //
-#define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
-#define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
-#define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3
-
-
-// Namespacing the package
-using namespace d_fall_pps;
+// #define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
+// #define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
+// #define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3
 
 
 
@@ -150,133 +173,128 @@ using namespace d_fall_pps;
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+
+
+// ----------------------------------------
+// VARIABLES SPECIFIC TO THE PICKER SERVICE
+
 // Current time
 int m_time_ticks = 0;
 float m_time_seconds;
 
-// > Mass of the Crazyflie quad-rotor, in [grams]
-float m_mass_CF_grams;
-
-// > Mass of the letters to be lifted, in [grams]
-float m_mass_E_grams;
-float m_mass_T_grams;
-float m_mass_H_grams;
-
 // > Total mass of the Crazyflie plus whatever it is carrying, in [grams]
 float m_mass_total_grams;
 
-// Thickness of the object at pick-up and put-down, in [meters]
-// > This should also account for extra height due to 
-//   the surface where the object is
-float m_thickness_of_object_at_pickup;
-float m_thickness_of_object_at_putdown;
-
-// (x,y) coordinates of the pickup location
-std::vector<float> m_pickup_coordinates_xy(2);
-
-// (x,y) coordinates of the drop off location
-std::vector<float> m_dropoff_coordinates_xy_for_E(2);
-std::vector<float> m_dropoff_coordinates_xy_for_T(2);
-std::vector<float> m_dropoff_coordinates_xy_for_H(2);
+// The setpoint to be tracked, the ordering is (x,y,z,yaw),
+// with units [meters,meters,meters,radians]
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
 
-// Length of the string from the Crazyflie
-// to the end of the Picker, in [meters]
-float m_picker_string_length;
-
-// > The setpoints for (x,y,z) position and yaw angle, in that order
-float m_setpoint[4] = {0.0,0.0,0.4,0.0};
-float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
-
-// > Small adjustments to the x-y setpoint
-float m_xAdjustment = 0.0f;
-float m_yAdjustment = 0.0f;
+// The setpoint that is actually used by the controller, this
+// differs from the setpoint when smoothing is turned on
+std::vector<float> m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
 
 // Boolean for whether to limit rate of change of the setpoint
 bool m_shouldSmoothSetpointChanges = true;
 
 // Max setpoint change per second
-float m_max_setpoint_change_per_second_horizontal;
-float m_max_setpoint_change_per_second_vertical;
-float m_max_setpoint_change_per_second_yaw_degrees;
+float yaml_max_setpoint_change_per_second_horizontal;
+float yaml_max_setpoint_change_per_second_vertical;
+float yaml_max_setpoint_change_per_second_yaw_degrees;
 float m_max_setpoint_change_per_second_yaw_radians;
 
 
-// Frequency at which the controller is running
-float m_vicon_frequency;
 
 
 
+// ------------------------------------------------------
+// VARIABLES THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
+// The ID of the agent that this node is monitoring
+int m_agentID;
 
-// THE FOLLOWING PARAMETERS ARE USED
-// FOR THE LOW-LEVEL CONTROLLER
+// The ID of the agent that can coordinate this node
+int m_coordID;
 
-// Frequency at which the controller is running
-float control_frequency;
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
+
+
+// VARIABLES FOR THE CONTOLLER
+
+// > the mass of the crazyflie, in [grams]
+float yaml_cf_mass_in_grams = 25.0;
+
+// > the coefficients of the 16-bit command to thrust conversion
+//std::vector<float> yaml_motorPoly(3);
+std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
+
+// > the frequency at which the controller is running
+float yaml_control_frequency = 200.0;
+
+// > the default setpoint, the ordering is (x,y,z,yaw),
+//   with units [meters,meters,meters,radians]
+std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
+
+// The weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = 0.0;
 
-// > Coefficients of the 16-bit command to thrust conversion
-std::vector<float> motorPoly(3);
+// The location error of the Crazyflie at the "previous" time step
+float m_previous_stateErrorInertial[9];
 
 // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
-std::vector<float> gainMatrixThrust_NineStateVector (9,0.0);
-std::vector<float> gainMatrixRollRate               (9,0.0);
-std::vector<float> gainMatrixPitchRate              (9,0.0);
-std::vector<float> gainMatrixYawRate                (9,0.0);
+std::vector<float> yaml_gainMatrixThrust_NineStateVector (9,0.0);
+std::vector<float> yaml_gainMatrixRollRate               (9,0.0);
+std::vector<float> yaml_gainMatrixPitchRate              (9,0.0);
+std::vector<float> yaml_gainMatrixYawRate                (9,0.0);
 
 // The 16-bit command limits
-float cmd_sixteenbit_min;
-float cmd_sixteenbit_max;
+float yaml_cmd_sixteenbit_min;
+float yaml_cmd_sixteenbit_max;
+
 
 
 // VARIABLES FOR THE ESTIMATOR
 
 // Frequency at which the controller is running
-float estimator_frequency;
+float yaml_estimator_frequency;
 
 // > A flag for which estimator to use:
-int estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
+int yaml_estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
 // > The current state interial estimate,
 //   for use by the controller
-float current_stateInertialEstimate[12];
+float m_current_stateInertialEstimate[12];
 
 // > The measurement of the Crazyflie at the "current" time step,
 //   to avoid confusion
-float current_xzy_rpy_measurement[6];
+float m_current_xzy_rpy_measurement[6];
 
 // > The measurement of the Crazyflie at the "previous" time step,
 //   used for computing finite difference velocities
-float previous_xzy_rpy_measurement[6];
+float m_previous_xzy_rpy_measurement[6];
 
 // > The full 12 state estimate maintained by the finite
 //   difference state estimator
-float stateInterialEstimate_viaFiniteDifference[12];
+float m_stateInterialEstimate_viaFiniteDifference[12];
 
 // > The full 12 state estimate maintained by the point mass
 //   kalman filter state estimator
-float stateInterialEstimate_viaPointMassKalmanFilter[12];
+float m_stateInterialEstimate_viaPointMassKalmanFilter[12];
 
 // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 // > For the (x,y,z) position
-std::vector<float> PMKF_Ahat_row1_for_positions (2,0.0);
-std::vector<float> PMKF_Ahat_row2_for_positions (2,0.0);
-std::vector<float> PMKF_Kinf_for_positions      (2,0.0);
+std::vector<float> yaml_PMKF_Ahat_row1_for_positions (2,0.0);
+std::vector<float> yaml_PMKF_Ahat_row2_for_positions (2,0.0);
+std::vector<float> yaml_PMKF_Kinf_for_positions      (2,0.0);
 // > For the (roll,pitch,yaw) angles
-std::vector<float> PMKF_Ahat_row1_for_angles    (2,0.0);
-std::vector<float> PMKF_Ahat_row2_for_angles    (2,0.0);
-std::vector<float> PMKF_Kinf_for_angles         (2,0.0);
-
-
-
-// VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
-// > For the paramter service of this agent
-std::string namespace_to_own_agent_parameter_service;
-// > For the parameter service of the coordinator
-std::string namespace_to_coordinator_parameter_service;
+std::vector<float> yaml_PMKF_Ahat_row1_for_angles    (2,0.0);
+std::vector<float> yaml_PMKF_Ahat_row2_for_angles    (2,0.0);
+std::vector<float> yaml_PMKF_Kinf_for_angles         (2,0.0);
 
 
-// ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
-ros::Publisher debugPublisher;
-
 
 // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
 
@@ -292,24 +310,181 @@ bool shouldPublishDebugMessage = false;
 // Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
 bool shouldDisplayDebugInfo = false;
 
+// ROS Publisher for debugging variables
+ros::Publisher m_debugPublisher;
+
+
+// VARIABLES RELATING TO COMMUNICATING THE SETPOINT
+
+// ROS Publisher for inform the network about
+// changes to the setpoin
+ros::Publisher m_setpointChangedPublisher;
+
+
+
+
+
+
+// // Current time
+// int m_time_ticks = 0;
+// float m_time_seconds;
+
+// // > Mass of the Crazyflie quad-rotor, in [grams]
+// float m_mass_CF_grams;
+
+// // > Mass of the letters to be lifted, in [grams]
+// float m_mass_E_grams;
+// float m_mass_T_grams;
+// float m_mass_H_grams;
+
+// // > Total mass of the Crazyflie plus whatever it is carrying, in [grams]
+// float m_mass_total_grams;
+
+// // Thickness of the object at pick-up and put-down, in [meters]
+// // > This should also account for extra height due to 
+// //   the surface where the object is
+// float m_thickness_of_object_at_pickup;
+// float m_thickness_of_object_at_putdown;
+
+// // (x,y) coordinates of the pickup location
+// std::vector<float> m_pickup_coordinates_xy(2);
+
+// // (x,y) coordinates of the drop off location
+// std::vector<float> m_dropoff_coordinates_xy_for_E(2);
+// std::vector<float> m_dropoff_coordinates_xy_for_T(2);
+// std::vector<float> m_dropoff_coordinates_xy_for_H(2);
+
+// // Length of the string from the Crazyflie
+// // to the end of the Picker, in [meters]
+// float m_picker_string_length;
+
+// // > The setpoints for (x,y,z) position and yaw angle, in that order
+// float m_setpoint[4] = {0.0,0.0,0.4,0.0};
+// float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
+
+// // > Small adjustments to the x-y setpoint
+// float m_xAdjustment = 0.0f;
+// float m_yAdjustment = 0.0f;
+
+// // Boolean for whether to limit rate of change of the setpoint
+// bool m_shouldSmoothSetpointChanges = true;
+
+// // Max setpoint change per second
+// float m_max_setpoint_change_per_second_horizontal;
+// float m_max_setpoint_change_per_second_vertical;
+// float m_max_setpoint_change_per_second_yaw_degrees;
+// float m_max_setpoint_change_per_second_yaw_radians;
+
+
+// // Frequency at which the controller is running
+// float m_vicon_frequency;
+
+
+
+
+
+// THE FOLLOWING PARAMETERS ARE USED
+// FOR THE LOW-LEVEL CONTROLLER
+
+// // Frequency at which the controller is running
+// float control_frequency;
+
+// // > Coefficients of the 16-bit command to thrust conversion
+// std::vector<float> motorPoly(3);
+
+// // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
+// std::vector<float> gainMatrixThrust_NineStateVector (9,0.0);
+// std::vector<float> gainMatrixRollRate               (9,0.0);
+// std::vector<float> gainMatrixPitchRate              (9,0.0);
+// std::vector<float> gainMatrixYawRate                (9,0.0);
+
+// // The 16-bit command limits
+// float cmd_sixteenbit_min;
+// float cmd_sixteenbit_max;
+
+
+// // VARIABLES FOR THE ESTIMATOR
+
+// // Frequency at which the controller is running
+// float estimator_frequency;
+
+// // > A flag for which estimator to use:
+// int estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
+// // > The current state interial estimate,
+// //   for use by the controller
+// float current_stateInertialEstimate[12];
+
+// // > The measurement of the Crazyflie at the "current" time step,
+// //   to avoid confusion
+// float current_xzy_rpy_measurement[6];
+
+// // > The measurement of the Crazyflie at the "previous" time step,
+// //   used for computing finite difference velocities
+// float previous_xzy_rpy_measurement[6];
+
+// // > The full 12 state estimate maintained by the finite
+// //   difference state estimator
+// float stateInterialEstimate_viaFiniteDifference[12];
+
+// // > The full 12 state estimate maintained by the point mass
+// //   kalman filter state estimator
+// float stateInterialEstimate_viaPointMassKalmanFilter[12];
+
+// // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
+// // > For the (x,y,z) position
+// std::vector<float> PMKF_Ahat_row1_for_positions (2,0.0);
+// std::vector<float> PMKF_Ahat_row2_for_positions (2,0.0);
+// std::vector<float> PMKF_Kinf_for_positions      (2,0.0);
+// // > For the (roll,pitch,yaw) angles
+// std::vector<float> PMKF_Ahat_row1_for_angles    (2,0.0);
+// std::vector<float> PMKF_Ahat_row2_for_angles    (2,0.0);
+// std::vector<float> PMKF_Kinf_for_angles         (2,0.0);
+
+
+
+// // VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
+// // > For the paramter service of this agent
+// std::string namespace_to_own_agent_parameter_service;
+// // > For the parameter service of the coordinator
+// std::string namespace_to_coordinator_parameter_service;
+
+
+// // ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
+// ros::Publisher debugPublisher;
+
+
+// // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
+
+// // Boolean whether to execute the convert into body frame function
+// bool shouldPerformConvertIntoBodyFrame = false;
+
+
+// // VARIABLES RELATING TO THE PUBLISHING OF A DEBUG MESSAGE
+
+// // Boolean indiciating whether the "Debug Message" of this agent should be published or not
+// bool shouldPublishDebugMessage = false;
+
+// // Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
+// bool shouldDisplayDebugInfo = false;
+
 
-// VARIABLES RELATING TO PUBLISHING CURRENT POSITION AND FOLLOWING ANOTHER AGENT'S
-// POSITION
+// // VARIABLES RELATING TO PUBLISHING CURRENT POSITION AND FOLLOWING ANOTHER AGENT'S
+// // POSITION
 
-// The ID of this agent, i.e., the ID of this compute
-int my_agentID = 0;
+// // The ID of this agent, i.e., the ID of this compute
+// int my_agentID = 0;
 
-// Boolean indicating whether the (x,y,z,yaw) of this agent should be published or not
-// > The default behaviour is: do not publish,
-// > This varaible is changed based on parameters loaded from the YAML file
-bool shouldPublishCurrent_xyz_yaw = false;
+// // Boolean indicating whether the (x,y,z,yaw) of this agent should be published or not
+// // > The default behaviour is: do not publish,
+// // > This varaible is changed based on parameters loaded from the YAML file
+// bool shouldPublishCurrent_xyz_yaw = false;
 
 
-// ROS Publisher for my current (x,y,z,yaw) position
-ros::Publisher my_current_xyz_yaw_publisher;
+// // ROS Publisher for my current (x,y,z,yaw) position
+// ros::Publisher my_current_xyz_yaw_publisher;
 
-// ROS Publisher for the current setpoint
-ros::Publisher pickerSetpointToGUIPublisher;
+// // ROS Publisher for the current setpoint
+// ros::Publisher pickerSetpointToGUIPublisher;
 
 
 // RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-- 
GitLab


From e862f7ba29c966aaf344903f1ac1faf9e77435d7 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 10:21:09 +0100
Subject: [PATCH 39/87] Adjust the Picker Controller Node to be integrated with
 the GUI. Needs compiling and testing.

---
 .../include/nodes/PickerControllerConstants.h |    2 +-
 .../include/nodes/PickerControllerService.h   |  136 +-
 .../include/nodes/StudentControllerService.h  |    2 +-
 .../d_fall_pps/param/PickerController.yaml    |   46 +-
 .../src/nodes/PickerControllerService.cpp     | 1659 ++++++++++-------
 .../src/nodes/StudentControllerService.cpp    |    4 +-
 6 files changed, 1056 insertions(+), 793 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
index 3b1c36cd..41ab3321 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
@@ -36,7 +36,7 @@
 // TO IDENITFY THE STATE OF THE PICKER
 
 #define PICKER_STATE_UNKNOWN      -1
-#define PICKER_STATE_STANDBY       0
+#define PICKER_STATE_STANDBY      99
 #define PICKER_STATE_GOTO_START    1
 #define PICKER_STATE_ATTACH        2
 #define PICKER_STATE_LIFT_UP       3
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index e1cc4c15..359438b9 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -178,12 +178,18 @@ using namespace d_fall_pps;
 // ----------------------------------------
 // VARIABLES SPECIFIC TO THE PICKER SERVICE
 
+// The current state of the picker, i.e.,
+// {goto start, attach, lift up, goto end, put down,
+//  squat, jump, standby}
+int m_picker_current_state = PICKER_STATE_STANDBY;
+
 // Current time
-int m_time_ticks = 0;
-float m_time_seconds;
+//int m_time_ticks = 0;
+//float m_time_seconds;
 
 // > Total mass of the Crazyflie plus whatever it is carrying, in [grams]
-float m_mass_total_grams;
+float m_mass_total_in_grams;
+float m_weight_total_in_newtons;
 
 // The setpoint to be tracked, the ordering is (x,y,z,yaw),
 // with units [meters,meters,meters,radians]
@@ -226,7 +232,7 @@ std::string m_namespace_to_coordinator_parameter_service;
 // VARIABLES FOR THE CONTOLLER
 
 // > the mass of the crazyflie, in [grams]
-float yaml_cf_mass_in_grams = 25.0;
+float yaml_mass_cf_in_grams = 25.0;
 
 // > the coefficients of the 16-bit command to thrust conversion
 //std::vector<float> yaml_motorPoly(3);
@@ -240,10 +246,10 @@ float yaml_control_frequency = 200.0;
 std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
 
 // The weight of the Crazyflie in Newtons, i.e., mg
-float m_cf_weight_in_newtons = 0.0;
+float m_weight_cf_in_newtons = 0.0;
 
 // The location error of the Crazyflie at the "previous" time step
-float m_previous_stateErrorInertial[9];
+std::vector<float> m_previous_stateErrorInertial = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
 
 // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
 std::vector<float> yaml_gainMatrixThrust_NineStateVector (9,0.0);
@@ -252,15 +258,15 @@ std::vector<float> yaml_gainMatrixPitchRate              (9,0.0);
 std::vector<float> yaml_gainMatrixYawRate                (9,0.0);
 
 // The 16-bit command limits
-float yaml_cmd_sixteenbit_min;
-float yaml_cmd_sixteenbit_max;
+float yaml_cmd_sixteenbit_min = 1000;
+float yaml_cmd_sixteenbit_max = 60000;
 
 
 
 // VARIABLES FOR THE ESTIMATOR
 
 // Frequency at which the controller is running
-float yaml_estimator_frequency;
+float yaml_estimator_frequency = 200.0;
 
 // > A flag for which estimator to use:
 int yaml_estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
@@ -299,16 +305,16 @@ std::vector<float> yaml_PMKF_Kinf_for_angles         (2,0.0);
 // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
 
 // Boolean whether to execute the convert into body frame function
-bool shouldPerformConvertIntoBodyFrame = false;
+bool yaml_shouldPerformConvertIntoBodyFrame = false;
 
 
 // VARIABLES RELATING TO THE PUBLISHING OF A DEBUG MESSAGE
 
 // Boolean indiciating whether the "Debug Message" of this agent should be published or not
-bool shouldPublishDebugMessage = false;
+bool yaml_shouldPublishDebugMessage = false;
 
 // Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-bool shouldDisplayDebugInfo = false;
+bool yaml_shouldDisplayDebugInfo = false;
 
 // ROS Publisher for debugging variables
 ros::Publisher m_debugPublisher;
@@ -530,45 +536,46 @@ ros::Publisher m_setpointChangedPublisher;
 void perControlCycleOperations();
 
 // CALLBACK FROM ROS MESSAGES RECEIVED
-void buttonPressedCallback(const std_msgs::Int32& msg);
-void zSetpointCallback(const std_msgs::Float32& msg);
-void yawSetpointCallback(const std_msgs::Float32& msg);
-void massCallback(const std_msgs::Float32& msg);
-void xAdjustmentCallback(const std_msgs::Float32& msg);
-void yAdjustmentCallback(const std_msgs::Float32& msg);
+//void buttonPressedCallback(const std_msgs::Int32& msg);
+// void zSetpointCallback(const std_msgs::Float32& msg);
+// void yawSetpointCallback(const std_msgs::Float32& msg);
+// void massCallback(const std_msgs::Float32& msg);
+// void xAdjustmentCallback(const std_msgs::Float32& msg);
+// void yAdjustmentCallback(const std_msgs::Float32& msg);
 
 void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2);
 
 
 // SEPARATE CALLBACK FUNCTIONS FOR EACH BUTTON
-void buttonPressed_gotoStart();
+void buttonPressed_goto_start();
 void buttonPressed_attach();
-void buttonPressed_pickup();
-void buttonPressed_gotoEnd();
-void buttonPressed_putdown();
+void buttonPressed_lift_up();
+void buttonPressed_goto_end();
+void buttonPressed_put_down();
 void buttonPressed_squat();
 void buttonPressed_jump();
+void buttonPressed_standby();
 
-void buttonPressed_1();
-void buttonPressed_2();
-void buttonPressed_3();
-void buttonPressed_4();
+// void buttonPressed_1();
+// void buttonPressed_2();
+// void buttonPressed_3();
+// void buttonPressed_4();
 
 
 // SEPARATE CALLBACK FUNCTIONS FOR EACH BUTTON
 // > WITH A SETPOINT IN THE MESSAGE
-void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2);
 
-void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2);
-void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2);
+// void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2);
 
 
 
@@ -580,39 +587,39 @@ void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2);
 // > The function that is called to "start" all estimation and control computations
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
+// > The function that smooth changes in the setpoin
+void smoothSetpointChanges();
+
 // > The various functions that implement an LQR controller
-void calculateControlOutput_viaLQR(                     float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaLQRforMotors(            float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaLQRforActuators(         float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaLQRforRates(             float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaLQRforAngles(            float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
-void calculateControlOutput_viaAngleResponseTest(       float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
+void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller::Request &request, Controller::Response &response);
 
 // ESTIMATOR COMPUTATIONS
 void performEstimatorUpdate_forStateInterial(Controller::Request &request);
 void performEstimatorUpdate_forStateInterial_viaFiniteDifference();
 void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter();
 
-
 // PUBLISHING OF THE DEBUG MESSAGE
 void construct_and_publish_debug_message(Controller::Request &request, Controller::Response &response);
 
-
-// TRANSFORMATION FROM INTERIAL ESTIMATE TO BODY FRAME ERROR
+// TRANSFORMATION FROM INTERIAL ESTIMATE TO
+// BODY FRAME ERROR
 void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setpoint[4], float (&bodyFrameError)[12]);
 
-// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR INTO AN (x,y) BODY FRAME ERROR
+// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR
+// INTO AN (x,y) BODY FRAME ERROR
 void convertIntoBodyFrame(float stateInertial[12], float (&stateBody)[12], float yaw_measured);
 
 // CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
 float computeMotorPolyBackward(float thrust);
 
-// SETPOINT CHANGE CALLBACK
-void setpointCallback(const Setpoint& newSetpoint);
-void xyz_yaw_to_follow_callback(const Setpoint& newSetpoint);
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
 
-void publishCurrentSetpoint();
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw);
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
 
 // CUSTOM COMMAND RECEIVED CALLBACK
 //void customCommandReceivedCallback(const CustomButton& commandReceived);
@@ -620,15 +627,18 @@ void publishCurrentSetpoint();
 // PUBLISH THE CURRENT X,Y,Z, AND YAW
 void publish_current_xyz_yaw(float x, float y, float z, float yaw);
 
-// LOAD PARAMETERS
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-void  getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-int   getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-void  getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-int   getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-bool  getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-void processFetchedParameters();
+// FOR LOADING THE YAML PARAMETERS
+// float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
+// void  getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
+// int   getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
+// void  getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
+// int   getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
+// bool  getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
+
+void isReadyPickerControllerYamlCallback(const IntWithHeader & msg);
+void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle);
+
+//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
+//void fetchYamlParameters(ros::NodeHandle& nodeHandle);
+//void processFetchedParameters();
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 42276a73..7dccc05a 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -249,6 +249,6 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 // CUSTOM COMMAND RECEIVED CALLBACK
 void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
-// > For the LOADING of YAML PARAMETERS
+// FOR LOADING THE YAML PARAMETERS
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg);
 void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/pps_ws/src/d_fall_pps/param/PickerController.yaml b/pps_ws/src/d_fall_pps/param/PickerController.yaml
index 13776ed9..65e5fff4 100644
--- a/pps_ws/src/d_fall_pps/param/PickerController.yaml
+++ b/pps_ws/src/d_fall_pps/param/PickerController.yaml
@@ -1,35 +1,34 @@
-# Mass of the crazyflie
-mass_CF : 32
+
+# Max setpoint change per second
+max_setpoint_change_per_second_horizontal  :  0.20 # [meters]
+max_setpoint_change_per_second_vertical    :  0.10 # [meters]
+max_setpoint_change_per_second_yaw_degrees : 90.00 # [degrees]
+
+
+
 # Mass of the letters
-mass_E : 3.2
-mass_T : 2.9
-mass_H : 3.3
+#mass_E : 3.2
+#mass_T : 2.9
+#mass_H : 3.3
 
 # Thickness of the object at pick-up and put-down, in [meters]
 # > This should also account for extra height due to 
 #   the surface where the object is
-thickness_of_object_at_pickup  : 0.02
-thickness_of_object_at_putdown : 0.03
+#thickness_of_object_at_pickup  : 0.02
+#thickness_of_object_at_putdown : 0.03
 
 # (x,y) coordinates of the pickup location
-pickup_coordinates_xy : [-0.26, 0.12]
+#pickup_coordinates_xy : [-0.26, 0.12]
 
 # (x,y) coordinates of the drop off location
-dropoff_coordinates_xy_for_E : [ 0.33, -0.03]
-dropoff_coordinates_xy_for_T : [ 0.24, 0.00]
-dropoff_coordinates_xy_for_H : [ 0.28, 0.00]
+#dropoff_coordinates_xy_for_E : [ 0.33, -0.03]
+#dropoff_coordinates_xy_for_T : [ 0.24, 0.00]
+#dropoff_coordinates_xy_for_H : [ 0.28, 0.00]
 
 # Length of the string from the Crazyflie
 # to the end of the Picker, in [meters]
-picker_string_length : 0.30
+#picker_string_length : 0.30
 
-# Max setpoint change per second
-max_setpoint_change_per_second_horizontal  :  0.20 # [meters]
-max_setpoint_change_per_second_vertical    :  0.10 # [meters]
-max_setpoint_change_per_second_yaw_degrees : 90.00 # [degrees]
-
-# Frequency of the controller, in hertz
-vicon_frequency : 200
 
 
 
@@ -40,10 +39,11 @@ vicon_frequency : 200
 
 
 
+# ------------------------------------------------------
+# PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
-
-# THE FOLLOWING PARAMETERS ARE USED
-# FOR THE LOW-LEVEL CONTROLLER
+# Mass of the crazyflie
+mass_cf_in_grams : 32
 
 # Frequency of the controller, in hertz
 control_frequency : 200
@@ -55,7 +55,7 @@ motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
 shouldPerformConvertIntoBodyFrame : true
 
 # Boolean indiciating whether the (x,y,z,yaw) of this agent should be published or not
-shouldPublishCurrent_xyz_yaw : true
+#shouldPublishCurrent_xyz_yaw : true
 
 # Boolean indiciating whether the "Debug Message" of this agent should be published or not
 shouldPublishDebugMessage : true
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
index 273d4a7f..ee97a8c3 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -89,12 +89,12 @@
 // // Boolean for whether to limit rate of change of the setpoint
 // bool m_shouldSmoothSetpointChanges = true;
 // // Max setpoint change per second
-// float m_max_setpoint_change_per_second_horizontal;
-// float m_max_setpoint_change_per_second_vertical;
-// float m_max_setpoint_change_per_second_yaw_degrees;
+// float yaml_max_setpoint_change_per_second_horizontal;
+// float yaml_max_setpoint_change_per_second_vertical;
+// float yaml_max_setpoint_change_per_second_yaw_degrees;
 // float m_max_setpoint_change_per_second_yaw_radians;
 // // Frequency at which the controller is running
-// float m_vicon_frequency;
+// float m_control_frequency;
 
 
 // A FEW EXTRA COMMENTS ABOUT THE MOST IMPORTANT VARIABLES
@@ -122,65 +122,15 @@
 
 
 
-// THIS FUNCTION IS CALLED AT "m_vicon_frequency" HERTZ.
+// THIS FUNCTION IS CALLED AT "m_control_frequency" HERTZ.
 // IT CAN BE USED TO ADJUST THINGS IN "REAL TIME".
 // For example, the equation:
-// >> m_max_setpoint_change_per_second_horizontal / m_vicon_frequency
+// >> yaml_max_setpoint_change_per_second_horizontal / m_control_frequency
 // will convert the "change per second" to a "change per cycle".
 
 void perControlCycleOperations()
 {
-	if (m_shouldSmoothSetpointChanges)
-	{
-		for(int i = 0; i < 4; ++i)
-		{
-			float max_for_this_coordinate;
-			// FILLE IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
-			switch (i)
-			{
-				case 0:
-					max_for_this_coordinate = m_max_setpoint_change_per_second_horizontal / m_vicon_frequency;
-					break;
-				case 1:
-					max_for_this_coordinate = m_max_setpoint_change_per_second_horizontal / m_vicon_frequency;
-					break;
-				case 2:
-					max_for_this_coordinate = m_max_setpoint_change_per_second_vertical / m_vicon_frequency;
-					break;
-				case 3:
-					max_for_this_coordinate = m_max_setpoint_change_per_second_yaw_radians / m_vicon_frequency;
-					break;
-				// Handle the exception
-				default:
-					max_for_this_coordinate = 0.0f;
-					break;
-			}
-
-			// Compute the difference in setpoint
-			float setpoint_difference = m_setpoint[i] - m_setpoint_for_controller[i];
-
-			// Clip the difference to the maximum
-			if (setpoint_difference > max_for_this_coordinate)
-			{
-				setpoint_difference = max_for_this_coordinate;
-			}
-			else if (setpoint_difference < -max_for_this_coordinate)
-			{
-				setpoint_difference = -max_for_this_coordinate;
-			}
-
-			// Update the setpoint of the controller
-			m_setpoint_for_controller[i] += setpoint_difference;
-		}
-		
-	}
-	else
-	{
-		m_setpoint_for_controller[0] = m_setpoint[0];
-		m_setpoint_for_controller[1] = m_setpoint[1];
-		m_setpoint_for_controller[2] = m_setpoint[2];
-		m_setpoint_for_controller[3] = m_setpoint[3];
-	}
+	
 }
 
 
@@ -191,169 +141,182 @@ void perControlCycleOperations()
 
 // CALLBACK FUNCTION THAT RUN WHEN THE RESPECTIVE BUTTON IS PRESSED
 
-void buttonPressed_gotoStart()
+// These functions are called from:
+// >> "buttonPressedWithSetpointCallback"
+// And in that function the following variable are already
+// updated appropriately:
+// >> "m_picker_current_state"
+// >> "m_mass_total_grams"
+// >> "m_shouldSmoothSetpointChanges"
+
+void buttonPressed_goto_start()
 {
 	ROS_INFO("[PICKER CONTROLLER] Goto Start button pressed");
 
-	// The drone should move smoothly to the start point:
-	m_shouldSmoothSetpointChanges = true;
-	// Set the (x,y) coordinates for the start point:
-	m_setpoint[0] = m_pickup_coordinates_xy[0];
-	m_setpoint[1] = m_pickup_coordinates_xy[1];
-	// Set the z coordinate to be a little more than the
-	// length of the "picker string"
-	m_setpoint[2] = m_picker_string_length + 0.10;
-	// Publish the setpoint so that the GUI updates
-	publishCurrentSetpoint();
+	// // The drone should move smoothly to the start point:
+	// m_shouldSmoothSetpointChanges = true;
+	// // Set the (x,y) coordinates for the start point:
+	// m_setpoint[0] = m_pickup_coordinates_xy[0];
+	// m_setpoint[1] = m_pickup_coordinates_xy[1];
+	// // Set the z coordinate to be a little more than the
+	// // length of the "picker string"
+	// m_setpoint[2] = m_picker_string_length + 0.10;
+	// // Publish the setpoint so that the GUI updates
+	// publishCurrentSetpoint();
 }
 
 void buttonPressed_attach()
 {
 	ROS_INFO("[PICKER CONTROLLER] Attach button pressed");
 
-	m_shouldSmoothSetpointChanges = true;
-	m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_pickup;
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = true;
+	// m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_pickup;
+	// publishCurrentSetpoint();
 }
 
-void buttonPressed_pickup()
+void buttonPressed_lift_up()
 {
 	ROS_INFO("[PICKER CONTROLLER] Pick up button pressed");
 
-	m_shouldSmoothSetpointChanges = true;
-	m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
-	m_setpoint[2] = m_picker_string_length + 0.25;
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = true;
+	// m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
+	// m_setpoint[2] = m_picker_string_length + 0.25;
+	// publishCurrentSetpoint();
 }
 
-void buttonPressed_gotoEnd()
+void buttonPressed_goto_end()
 {
 	ROS_INFO("[PICKER CONTROLLER] Goto End button pressed");
 
-	m_shouldSmoothSetpointChanges = true;
-	m_setpoint[0] = m_dropoff_coordinates_xy_for_E[0];
-	m_setpoint[1] = m_dropoff_coordinates_xy_for_E[1];
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = true;
+	// m_setpoint[0] = m_dropoff_coordinates_xy_for_E[0];
+	// m_setpoint[1] = m_dropoff_coordinates_xy_for_E[1];
+	// publishCurrentSetpoint();
 }	
 
-void buttonPressed_putdown()
+void buttonPressed_put_down()
 {
 	ROS_INFO("[PICKER CONTROLLER] Put down button pressed");
 
-	m_shouldSmoothSetpointChanges = true;
-	m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_putdown;
-	m_mass_total_grams = m_mass_CF_grams;
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = true;
+	// m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_putdown;
+	// m_mass_total_grams = m_mass_CF_grams;
+	// publishCurrentSetpoint();
 }
 
 void buttonPressed_squat()
 {
 	ROS_INFO("[PICKER CONTROLLER] Squat button pressed");
 
-	m_shouldSmoothSetpointChanges = true;
-	m_setpoint[2] = m_picker_string_length - 0.10;
-	m_mass_total_grams = m_mass_CF_grams;
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = true;
+	// m_setpoint[2] = m_picker_string_length - 0.10;
+	// m_mass_total_grams = m_mass_CF_grams;
+	// publishCurrentSetpoint();
 }
 
 void buttonPressed_jump()
 {
 	ROS_INFO("[PICKER CONTROLLER] Jump button pressed");
 
-	m_shouldSmoothSetpointChanges = false;
-	m_setpoint[2] = m_picker_string_length + 0.10;
-	m_mass_total_grams = m_mass_CF_grams;
-	publishCurrentSetpoint();
+	// m_shouldSmoothSetpointChanges = false;
+	// m_setpoint[2] = m_picker_string_length + 0.10;
+	// m_mass_total_grams = m_mass_CF_grams;
+	// publishCurrentSetpoint();
 }
 
-
-
-// THESE CALLBACK FUNCTIONS ALLOW YOU TO IMPLEMENT SOME
-// CUSTOM ACTION IN RESPONSE TO THE RESPECTIVE BUTTON PRESSES
-
-void buttonPressed_1()
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed");
-}
-void buttonPressed_2()
+void buttonPressed_standby()
 {
-	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed");
-}
+	ROS_INFO("[PICKER CONTROLLER] Standby button pressed");
 
-void buttonPressed_3()
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed");
+	// m_shouldSmoothSetpointChanges = false;
+	// m_setpoint[2] = m_picker_string_length + 0.10;
+	// m_mass_total_grams = m_mass_CF_grams;
+	// publishCurrentSetpoint();
 }
 
-void buttonPressed_4()
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed");
-}
 
 
+// THESE CALLBACK FUNCTIONS ALLOW YOU TO IMPLEMENT SOME
+// CUSTOM ACTION IN RESPONSE TO THE RESPECTIVE BUTTON PRESSES
 
+// void buttonPressed_1()
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed");
+// }
+// void buttonPressed_2()
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed");
+// }
 
+// void buttonPressed_3()
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed");
+// }
 
+// void buttonPressed_4()
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed");
+// }
 
 
 
 
 
-void zSetpointCallback(const std_msgs::Float32& msg)
-{
-	// The "data" in the message is z-height in [meters]
-	float z_height = msg.data;
-	// Display the data
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Z Slider changed to " << z_height << " [m]" );
-	// Update the z-component of the setpoint class variable
-	m_setpoint[2] = z_height;
-}
 
 
-void yawSetpointCallback(const std_msgs::Float32& msg)
-{
-	// The "data" in the message is yaw-angle in [radians]
-	float yaw_angle = msg.data;
-	// Display the data
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Yaw Dial changed to " << (yaw_angle*RAD2DEG) << " [deg]" );
-	// Update the yaw-component of the setpoint class variable
-	m_setpoint[3] = yaw_angle;
-}
 
-void massCallback(const std_msgs::Float32& msg)
-{
-	// The "data" in the message is mass in [grams]
-	float mass = msg.data;
-	// Display the data
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Mass slider changed to " << mass << " [grams]" );
-	// Update the total mass class variable
-	m_mass_total_grams = mass;
-}
 
-void xAdjustmentCallback(const std_msgs::Float32& msg)
-{
-	// The "data" in the message is adjustment in [meters]
-	float x_adjustment = msg.data;
-	// Display the data
-	ROS_INFO_STREAM("[PICKER CONTROLLER] X adjustment slider changed to " << x_adjustment << " [m]" );
-	// Update the x-adjustment class variable
-	m_xAdjustment = x_adjustment;
-}
 
-void yAdjustmentCallback(const std_msgs::Float32& msg)
-{
-	// The "data" in the message is adjustment in [meters]
-	float y_adjustment = msg.data;
-	// Display the data
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Y adjustment slider changed to " << y_adjustment << " [m]" );
-	// Update the y-adjustment class variable
-	m_yAdjustment = y_adjustment;
-}
+// void zSetpointCallback(const std_msgs::Float32& msg)
+// {
+// 	// The "data" in the message is z-height in [meters]
+// 	float z_height = msg.data;
+// 	// Display the data
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Z Slider changed to " << z_height << " [m]" );
+// 	// Update the z-component of the setpoint class variable
+// 	m_setpoint[2] = z_height;
+// }
 
 
+// void yawSetpointCallback(const std_msgs::Float32& msg)
+// {
+// 	// The "data" in the message is yaw-angle in [radians]
+// 	float yaw_angle = msg.data;
+// 	// Display the data
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Yaw Dial changed to " << (yaw_angle*RAD2DEG) << " [deg]" );
+// 	// Update the yaw-component of the setpoint class variable
+// 	m_setpoint[3] = yaw_angle;
+// }
 
+// void massCallback(const std_msgs::Float32& msg)
+// {
+// 	// The "data" in the message is mass in [grams]
+// 	float mass = msg.data;
+// 	// Display the data
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Mass slider changed to " << mass << " [grams]" );
+// 	// Update the total mass class variable
+// 	m_mass_total_grams = mass;
+// }
 
+// void xAdjustmentCallback(const std_msgs::Float32& msg)
+// {
+// 	// The "data" in the message is adjustment in [meters]
+// 	float x_adjustment = msg.data;
+// 	// Display the data
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] X adjustment slider changed to " << x_adjustment << " [m]" );
+// 	// Update the x-adjustment class variable
+// 	m_xAdjustment = x_adjustment;
+// }
 
+// void yAdjustmentCallback(const std_msgs::Float32& msg)
+// {
+// 	// The "data" in the message is adjustment in [meters]
+// 	float y_adjustment = msg.data;
+// 	// Display the data
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Y adjustment slider changed to " << y_adjustment << " [m]" );
+// 	// Update the y-adjustment class variable
+// 	m_yAdjustment = y_adjustment;
+// }
 
 
 
@@ -363,123 +326,189 @@ void yAdjustmentCallback(const std_msgs::Float32& msg)
 
 
 
-// CALLBACK FUNCTION THAT RUN WHEN THE RESPECTIVE BUTTON IS PRESSED
-// > AND A SETPOINT IS PROVIDED
 
-void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto Start button pressed: (x,y,z)=(" << newSetpointV2.x << "," << newSetpointV2.y << "," << newSetpointV2.z << "), smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the (x,y,z) coordinates:
-	m_setpoint[0] = newSetpointV2.x;
-	m_setpoint[1] = newSetpointV2.y;
-	m_setpoint[2] = newSetpointV2.z;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
 
-void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Attach button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the z coordinate:
-	m_setpoint[2] = newSetpointV2.z;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
 
-void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Pick up button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the z coordinate:
-	m_setpoint[2] = newSetpointV2.z;
-	// Update the mass of the Crazyflie
-	m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
 
-void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto End button pressed: (x,y)=(" << newSetpointV2.x << "," << newSetpointV2.y << "), smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the (x,y) coordinates:
-	m_setpoint[0] = newSetpointV2.x;
-	m_setpoint[1] = newSetpointV2.y;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
-
-void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Put down button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the z coordinate:
-	m_setpoint[2] = newSetpointV2.z;
-	// Update the mass of the Crazyflie
-	m_mass_total_grams = m_mass_CF_grams;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
-
-void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Squat button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the z coordinate:
-	m_setpoint[2] = newSetpointV2.z;
-	// Update the mass of the Crazyflie
-	m_mass_total_grams = m_mass_CF_grams;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
-
-void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO_STREAM("[PICKER CONTROLLER] Jump button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-	// Use the boolean for the smoothing flag
-	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-	// Set the z coordinate:
-	m_setpoint[2] = newSetpointV2.z;
-	// Update the mass of the Crazyflie
-	m_mass_total_grams = m_mass_CF_grams;
-	// Publish the setpoint so that the GUI updates
-	//publishCurrentSetpoint();
-}
 
+// CALLBACK FUNCTION THAT RUN WHEN THE RESPECTIVE BUTTON IS PRESSED
+// > AND A SETPOINT IS PROVIDED
 
-void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2)
+// void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto Start button pressed: (x,y,z)=(" << newSetpointV2.x << "," << newSetpointV2.y << "," << newSetpointV2.z << "), smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the (x,y,z) coordinates:
+// 	m_setpoint[0] = newSetpointV2.x;
+// 	m_setpoint[1] = newSetpointV2.y;
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Attach button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the z coordinate:
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Pick up button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the z coordinate:
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Update the mass of the Crazyflie
+// 	m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto End button pressed: (x,y)=(" << newSetpointV2.x << "," << newSetpointV2.y << "), smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the (x,y) coordinates:
+// 	m_setpoint[0] = newSetpointV2.x;
+// 	m_setpoint[1] = newSetpointV2.y;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Put down button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the z coordinate:
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Update the mass of the Crazyflie
+// 	m_mass_total_grams = m_mass_CF_grams;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Squat button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the z coordinate:
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Update the mass of the Crazyflie
+// 	m_mass_total_grams = m_mass_CF_grams;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+// void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Jump button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
+
+// 	// Use the boolean for the smoothing flag
+// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
+// 	// Set the z coordinate:
+// 	m_setpoint[2] = newSetpointV2.z;
+// 	// Update the mass of the Crazyflie
+// 	m_mass_total_grams = m_mass_CF_grams;
+// 	// Publish the setpoint so that the GUI updates
+// 	//publishCurrentSetpoint();
+// }
+
+
+// void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed with a setpoint provided");
+// }
+
+// void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed with a setpoint provided");
+// }
+
+// void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed with a setpoint provided");
+// }
+
+// void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2)
+// {
+// 	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed with a setpoint provided with a setpoint provided");
+// }
+
+
+
+
+
+
+
+void smoothSetpointChanges()
 {
-	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed with a setpoint provided");
-}
+	if (m_shouldSmoothSetpointChanges)
+	{
+		for(int i = 0; i < 4; ++i)
+		{
+			float max_for_this_coordinate;
+			// FILL IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
+			switch (i)
+			{
+				case 0:
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / m_control_frequency;
+					break;
+				case 1:
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / m_control_frequency;
+					break;
+				case 2:
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_vertical / m_control_frequency;
+					break;
+				case 3:
+					max_for_this_coordinate = m_max_setpoint_change_per_second_yaw_radians / m_control_frequency;
+					break;
+				// Handle the exception
+				default:
+					max_for_this_coordinate = 0.0f;
+					break;
+			}
 
-void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed with a setpoint provided");
-}
+			// Compute the difference in setpoint
+			float setpoint_difference = m_setpoint[i] - m_setpoint_for_controller[i];
 
-void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed with a setpoint provided");
-}
+			// Clip the difference to the maximum
+			if (setpoint_difference > max_for_this_coordinate)
+			{
+				setpoint_difference = max_for_this_coordinate;
+			}
+			else if (setpoint_difference < -max_for_this_coordinate)
+			{
+				setpoint_difference = -max_for_this_coordinate;
+			}
 
-void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2)
-{
-	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed with a setpoint provided with a setpoint provided");
+			// Update the setpoint of the controller
+			m_setpoint_for_controller[i] += setpoint_difference;
+		}
+		
+	}
+	else
+	{
+		m_setpoint_for_controller[0] = m_setpoint[0];
+		m_setpoint_for_controller[1] = m_setpoint[1];
+		m_setpoint_for_controller[2] = m_setpoint[2];
+		m_setpoint_for_controller[3] = m_setpoint[3];
+	}
 }
 
 
@@ -494,10 +523,6 @@ void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2)
 
 
 
-
-
-
-
 //    ------------------------------------------------------------------------------
 //     OOO   U   U  TTTTT  EEEEE  RRRR 
 //    O   O  U   U    T    E      R   R
@@ -606,8 +631,8 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 {
 
 	// Keep track of time
-	m_time_ticks++;
-	m_time_seconds = float(m_time_ticks) / m_vicon_frequency;
+	//m_time_ticks++;
+	//m_time_seconds = float(m_time_ticks) / m_control_frequency;
 
 
 	// CALL THE FUNCTION FOR PER CYLCE OPERATIONS
@@ -621,17 +646,21 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 	// PERFORM THE ESTIMATOR UPDATE FOR THE INTERIAL FRAME STATE
 	// > After this function is complete the class variable
-	//   "current_stateInertialEstimate" is updated and ready
+	//   "m_current_stateInertialEstimate" is updated and ready
 	//   to be used for subsequent controller copmutations
 	performEstimatorUpdate_forStateInterial(request);
 
+
+	// SMOOTH ANY CHANGES THAT MAY HAVE OCCURRED IN THE
+	// SETPOINT
+	smoothSetpointChanges();
 	
 	// CONVERT THE CURRENT INERTIAL FRAME STATE ESTIMATE, INTO
 	// THE BODY FRAME ERROR REQUIRED BY THE CONTROLLER
 	// > Define a local array to fill in with the body frame error
 	float current_bodyFrameError[12];
 	// > Call the function to perform the conversion
-	convert_stateInertial_to_bodyFrameError(current_stateInertialEstimate,m_setpoint_for_controller,current_bodyFrameError);
+	convert_stateInertial_to_bodyFrameError(m_current_stateInertialEstimate,m_setpoint_for_controller,current_bodyFrameError);
 
 	
 
@@ -641,14 +670,14 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 
 
-	// PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
-	if (shouldPublishCurrent_xyz_yaw)
-	{
-		publish_current_xyz_yaw(request.ownCrazyflie.x,request.ownCrazyflie.y,request.ownCrazyflie.z,request.ownCrazyflie.yaw);
-	}
+	// // PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
+	// if (shouldPublishCurrent_xyz_yaw)
+	// {
+	// 	publish_current_xyz_yaw(request.ownCrazyflie.x,request.ownCrazyflie.y,request.ownCrazyflie.z,request.ownCrazyflie.yaw);
+	// }
 
 	// PUBLISH THE DEBUG MESSAGE (if required)
-	if (shouldPublishDebugMessage)
+	if (yaml_shouldPublishDebugMessage)
 	{
 		construct_and_publish_debug_message(request,response);
 	}
@@ -672,13 +701,13 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 
 	// PUT THE CURRENT MEASURED DATA INTO THE CLASS VARIABLE
 	// > for (x,y,z) position
-	current_xzy_rpy_measurement[0] = request.ownCrazyflie.x;
-	current_xzy_rpy_measurement[1] = request.ownCrazyflie.y;
-	current_xzy_rpy_measurement[2] = request.ownCrazyflie.z;
+	m_current_xzy_rpy_measurement[0] = request.ownCrazyflie.x;
+	m_current_xzy_rpy_measurement[1] = request.ownCrazyflie.y;
+	m_current_xzy_rpy_measurement[2] = request.ownCrazyflie.z;
 	// > for (roll,pitch,yaw) angles
-	current_xzy_rpy_measurement[3] = request.ownCrazyflie.roll;
-	current_xzy_rpy_measurement[4] = request.ownCrazyflie.pitch;
-	current_xzy_rpy_measurement[5] = request.ownCrazyflie.yaw;
+	m_current_xzy_rpy_measurement[3] = request.ownCrazyflie.roll;
+	m_current_xzy_rpy_measurement[4] = request.ownCrazyflie.pitch;
+	m_current_xzy_rpy_measurement[5] = request.ownCrazyflie.yaw;
 
 
 	// RUN THE FINITE DIFFERENCE ESTIMATOR
@@ -690,7 +719,7 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 
 
 	// FILLE IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
-	switch (estimator_method)
+	switch (yaml_estimator_method)
 	{
 		// Estimator based on finte differences
 		case ESTIMATOR_METHOD_FINITE_DIFFERENCE:
@@ -698,7 +727,7 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 			// Transfer the estimate
 			for(int i = 0; i < 12; ++i)
 			{
-				current_stateInertialEstimate[i]  = stateInterialEstimate_viaFiniteDifference[i];
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
 			}
 			break;
 		}
@@ -708,19 +737,19 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 			// Transfer the estimate
 			for(int i = 0; i < 12; ++i)
 			{
-				current_stateInertialEstimate[i]  = stateInterialEstimate_viaPointMassKalmanFilter[i];
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
 			}
 			break;
 		}
 		// Handle the exception
 		default:
 		{
-			// Display that the "estimator_method" was not recognised
-			ROS_INFO_STREAM("[PICKER CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'PickerControllerService': the 'estimator_method' is not recognised.");
+			// Display that the "yaml_estimator_method" was not recognised
+			ROS_INFO_STREAM("[PICKER CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'PickerControllerService': the 'yaml_estimator_method' is not recognised.");
 			// Transfer the finite difference estimate by default
 			for(int i = 0; i < 12; ++i)
 			{
-				current_stateInertialEstimate[i]  = stateInterialEstimate_viaFiniteDifference[i];
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
 			}
 			break;
 		}
@@ -730,13 +759,13 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 	// NOW THAT THE ESTIMATORS HAVE ALL BEEN RUN, PUT THE CURRENT
 	// MEASURED DATA INTO THE CLASS VARIABLE FOR THE PREVIOUS 
 	// > for (x,y,z) position
-	previous_xzy_rpy_measurement[0] = current_xzy_rpy_measurement[0];
-	previous_xzy_rpy_measurement[1] = current_xzy_rpy_measurement[1];
-	previous_xzy_rpy_measurement[2] = current_xzy_rpy_measurement[2];
+	m_previous_xzy_rpy_measurement[0] = m_current_xzy_rpy_measurement[0];
+	m_previous_xzy_rpy_measurement[1] = m_current_xzy_rpy_measurement[1];
+	m_previous_xzy_rpy_measurement[2] = m_current_xzy_rpy_measurement[2];
 	// > for (roll,pitch,yaw) angles
-	previous_xzy_rpy_measurement[3] = current_xzy_rpy_measurement[3];
-	previous_xzy_rpy_measurement[4] = current_xzy_rpy_measurement[4];
-	previous_xzy_rpy_measurement[5] = current_xzy_rpy_measurement[5];
+	m_previous_xzy_rpy_measurement[3] = m_current_xzy_rpy_measurement[3];
+	m_previous_xzy_rpy_measurement[4] = m_current_xzy_rpy_measurement[4];
+	m_previous_xzy_rpy_measurement[5] = m_current_xzy_rpy_measurement[5];
 }
 
 
@@ -745,23 +774,23 @@ void performEstimatorUpdate_forStateInterial_viaFiniteDifference()
 {
 	// PUT IN THE CURRENT MEASUREMENT DIRECTLY
 	// > for (x,y,z) position
-	stateInterialEstimate_viaFiniteDifference[0]  = current_xzy_rpy_measurement[0];
-	stateInterialEstimate_viaFiniteDifference[1]  = current_xzy_rpy_measurement[1];
-	stateInterialEstimate_viaFiniteDifference[2]  = current_xzy_rpy_measurement[2];
+	m_stateInterialEstimate_viaFiniteDifference[0]  = m_current_xzy_rpy_measurement[0];
+	m_stateInterialEstimate_viaFiniteDifference[1]  = m_current_xzy_rpy_measurement[1];
+	m_stateInterialEstimate_viaFiniteDifference[2]  = m_current_xzy_rpy_measurement[2];
 	// > for (roll,pitch,yaw) angles
-	stateInterialEstimate_viaFiniteDifference[6]  = current_xzy_rpy_measurement[3];
-	stateInterialEstimate_viaFiniteDifference[7]  = current_xzy_rpy_measurement[4];
-	stateInterialEstimate_viaFiniteDifference[8]  = current_xzy_rpy_measurement[5];
+	m_stateInterialEstimate_viaFiniteDifference[6]  = m_current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaFiniteDifference[7]  = m_current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaFiniteDifference[8]  = m_current_xzy_rpy_measurement[5];
 
 	// COMPUTE THE VELOCITIES VIA FINITE DIFFERENCE
 	// > for (x,y,z) velocities
-	stateInterialEstimate_viaFiniteDifference[3]  = (current_xzy_rpy_measurement[0] - previous_xzy_rpy_measurement[0]) * estimator_frequency;
-	stateInterialEstimate_viaFiniteDifference[4]  = (current_xzy_rpy_measurement[1] - previous_xzy_rpy_measurement[1]) * estimator_frequency;
-	stateInterialEstimate_viaFiniteDifference[5]  = (current_xzy_rpy_measurement[2] - previous_xzy_rpy_measurement[2]) * estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[3]  = (m_current_xzy_rpy_measurement[0] - m_previous_xzy_rpy_measurement[0]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[4]  = (m_current_xzy_rpy_measurement[1] - m_previous_xzy_rpy_measurement[1]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[5]  = (m_current_xzy_rpy_measurement[2] - m_previous_xzy_rpy_measurement[2]) * m_estimator_frequency;
 	// > for (roll,pitch,yaw) velocities
-	stateInterialEstimate_viaFiniteDifference[9]  = (current_xzy_rpy_measurement[3] - previous_xzy_rpy_measurement[3]) * estimator_frequency;
-	stateInterialEstimate_viaFiniteDifference[10] = (current_xzy_rpy_measurement[4] - previous_xzy_rpy_measurement[4]) * estimator_frequency;
-	stateInterialEstimate_viaFiniteDifference[11] = (current_xzy_rpy_measurement[5] - previous_xzy_rpy_measurement[5]) * estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[9]  = (m_current_xzy_rpy_measurement[3] - m_previous_xzy_rpy_measurement[3]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[10] = (m_current_xzy_rpy_measurement[4] - m_previous_xzy_rpy_measurement[4]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[11] = (m_current_xzy_rpy_measurement[5] - m_previous_xzy_rpy_measurement[5]) * m_estimator_frequency;
 }
 
 
@@ -773,28 +802,28 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter()
 	float temp_PMKFstate[12];
 	for(int i = 0; i < 12; ++i)
 	{
-		temp_PMKFstate[i]  = stateInterialEstimate_viaPointMassKalmanFilter[i];
+		temp_PMKFstate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
 	}
 	// > Now perform update for:
 	// > x position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[0] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[0] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[3] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[0];
-	stateInterialEstimate_viaPointMassKalmanFilter[3] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[0] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[3] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[0];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[0] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[0] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[3] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[0];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[3] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[0] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[3] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[0];
 	// > y position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[1] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[1] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[4] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[1];
-	stateInterialEstimate_viaPointMassKalmanFilter[4] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[1] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[4] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[1];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[1] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[1] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[4] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[1];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[4] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[1] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[4] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[1];
 	// > z position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[2] = PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[2] + PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[5] + PMKF_Kinf_for_positions[0]*current_xzy_rpy_measurement[2];
-	stateInterialEstimate_viaPointMassKalmanFilter[5] = PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[2] + PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[5] + PMKF_Kinf_for_positions[1]*current_xzy_rpy_measurement[2];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[2] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[2];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[5] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[2];
 
 	// > roll  position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[6]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[6] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[9]  + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[3];
-	stateInterialEstimate_viaPointMassKalmanFilter[9]  = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[6] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[9]  + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[6]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[9]  = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[3];
 	// > pitch position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[7]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[7] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[10] + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[4];
-	stateInterialEstimate_viaPointMassKalmanFilter[10] = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[7] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[10] + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[7]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[10] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[4];
 	// > yaw   position and velocity:
-	stateInterialEstimate_viaPointMassKalmanFilter[8]  = PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[8] + PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[11] + PMKF_Kinf_for_angles[0]*current_xzy_rpy_measurement[5];
-	stateInterialEstimate_viaPointMassKalmanFilter[11] = PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[8] + PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[11] + PMKF_Kinf_for_angles[1]*current_xzy_rpy_measurement[5];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[8]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[5];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[11] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[5];
 }
 
 
@@ -828,13 +857,13 @@ void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller:
 	for(int i = 0; i < 9; ++i)
 	{
 		// BODY FRAME Y CONTROLLER
-		rollRate_forResponse  -= gainMatrixRollRate[i] * stateErrorBody[i];
+		rollRate_forResponse  -= yaml_gainMatrixRollRate[i] * stateErrorBody[i];
 		// BODY FRAME X CONTROLLER
-		pitchRate_forResponse -= gainMatrixPitchRate[i] * stateErrorBody[i];
+		pitchRate_forResponse -= yaml_gainMatrixPitchRate[i] * stateErrorBody[i];
 		// BODY FRAME YAW CONTROLLER
-		yawRate_forResponse   -= gainMatrixYawRate[i] * stateErrorBody[i];
+		yawRate_forResponse   -= yaml_gainMatrixYawRate[i] * stateErrorBody[i];
 		// > ALITUDE CONTROLLER (i.e., z-controller):
-		thrustAdjustment      -= gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
+		thrustAdjustment      -= yaml_gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
 	}
 
 
@@ -851,7 +880,7 @@ void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller:
 	//         controller needed to be divided by 4 or not.
 	thrustAdjustment = thrustAdjustment / 4.0;
 	// > Compute the feed-forward force
-	float feed_forward_thrust_per_motor = m_mass_total_grams * 9.81/(1000*4);
+	float feed_forward_thrust_per_motor = m_weight_total_in_newtons / 4.0;
 	// > Put in the per motor commands
 	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
 	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
@@ -867,7 +896,7 @@ void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller:
 
 	// An alternate debugging technique is to print out data directly to the
 	// command line from which this node was launched.
-	if (shouldDisplayDebugInfo)
+	if (yaml_shouldDisplayDebugInfo)
 	{
 		// An example of "printing out" the data from the "request" argument to the
 		// command line. This might be useful for debugging.
@@ -886,9 +915,9 @@ void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller:
 		ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
 
 		// An example of "printing out" the "thrust-to-command" conversion parameters.
-		ROS_INFO_STREAM("motorPoly 0:" << motorPoly[0]);
-		ROS_INFO_STREAM("motorPoly 0:" << motorPoly[1]);
-		ROS_INFO_STREAM("motorPoly 0:" << motorPoly[2]);
+		ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
+		ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
+		ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
 
 		// An example of "printing out" the per motor 16-bit command computed.
 		ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
@@ -939,7 +968,7 @@ void construct_and_publish_debug_message(Controller::Request &request, Controlle
 	// debugMsg.value_10 = your_variable_name;
 
 	// Publish the "debugMsg"
-	debugPublisher.publish(debugMsg);
+	m_debugPublisher.publish(debugMsg);
 }
 
 
@@ -959,7 +988,7 @@ void construct_and_publish_debug_message(Controller::Request &request, Controlle
 
 void convertIntoBodyFrame(float stateInertial[12], float (&stateBody)[12], float yaw_measured)
 {
-	if (shouldPerformConvertIntoBodyFrame)
+	if (yaml_shouldPerformConvertIntoBodyFrame)
 	{
 		float sinYaw = sin(yaw_measured);
     	float cosYaw = cos(yaw_measured);
@@ -1017,17 +1046,18 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	float temp_stateInertial_yaw = stateInertial[8];
 
 	// Adjust the INERTIAL (x,y,z) position for the setpoint
-	stateInertial[0] = stateInertial[0] - setpoint[0] - m_xAdjustment;
-	stateInertial[1] = stateInertial[1] - setpoint[1] - m_yAdjustment;
+	stateInertial[0] = stateInertial[0] - setpoint[0];
+	stateInertial[1] = stateInertial[1] - setpoint[1];
 	stateInertial[2] = stateInertial[2] - setpoint[2];
 
-	if (stateInertial[2] > 40.0f)
+	// Clip the z-coordination to +/-0.40 meters
+	if (stateInertial[2] > 0.40f)
 	{
-		stateInertial[2] = 40.0f;
+		stateInertial[2] = 0.40f;
 	}
-	else if (stateInertial[2] < -40.0f)
+	else if (stateInertial[2] < -0.40f)
 	{
-		stateInertial[2] = -40.0f;
+		stateInertial[2] = -0.40f;
 	}
 
 	// Fill in the yaw angle error
@@ -1081,16 +1111,16 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 float computeMotorPolyBackward(float thrust)
 {
 	// Compute the 16-bit command signal that generates the "thrust" force
-	float cmd = (-motorPoly[1] + sqrt(motorPoly[1] * motorPoly[1] - 4 * motorPoly[2] * (motorPoly[0] - thrust))) / (2 * motorPoly[2]);
+	float cmd = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
 
 	// Saturate the signal to be 0 or in the range [1000,65000]
-	if (cmd < cmd_sixteenbit_min)
+	if (cmd < yaml_cmd_sixteenbit_min)
 	{
 		cmd = 0;
 	}
-	else if (cmd > cmd_sixteenbit_max)
+	else if (cmd > yaml_cmd_sixteenbit_max)
 	{
-		cmd = cmd_sixteenbit_max;
+		cmd = yaml_cmd_sixteenbit_max;
 	}
 
     return cmd;
@@ -1113,28 +1143,184 @@ 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
-void setpointCallback(const Setpoint& newSetpoint)
+
+// REQUEST SETPOINT CHANGE CALLBACK
+// This function does NOT need to be edited 
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
 {
-    m_setpoint[0] = newSetpoint.x;
-    m_setpoint[1] = newSetpoint.y;
-    m_setpoint[2] = newSetpoint.z;
-    m_setpoint[3] = newSetpoint.yaw;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newSetpoint.shouldCheckForAgentID , newSetpoint.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Check that the ".buttonID" property is
+		// actually one of the possible states
+		int button_index = newSetpoint.buttonID;
+		switch(button_index)
+		{
+			case PICKER_STATE_STANDBY:
+			case PICKER_STATE_GOTO_START:
+			case PICKER_STATE_ATTACH:
+			case PICKER_STATE_LIFT_UP:
+			case PICKER_STATE_GOTO_END:
+			case PICKER_STATE_PUT_DOWN:
+			case PICKER_STATE_SQUAT:
+			case PICKER_STATE_JUMP:
+			{
+				// Call the function for actually setting the setpoint
+				setNewSetpoint(
+						newSetpoint.buttonID,
+						newSetpoint.isChecked,
+						newSetpoint.x,
+						newSetpoint.y,
+						newSetpoint.z,
+						newSetpoint.yaw,
+						newSetpoint.mass
+					);
+				break;
+			}
+			default:
+			{
+				// Let the user know that the command was not recognised
+				ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
+				break;
+			}
+		}
+		
+		// Call the specific function for each button
+		switch(button_index)
+		{
+			case PICKER_STATE_STANDBY:
+			{
+				buttonPressed_standby();
+				break;
+			}
+			case PICKER_STATE_GOTO_START:
+			{
+				buttonPressed_goto_start();
+				break;
+			}
+			case PICKER_STATE_ATTACH:
+			{
+				buttonPressed_attach();
+				break;
+			}
+			case PICKER_STATE_LIFT_UP:
+			{
+				buttonPressed_lift_up();
+				break;
+			}
+			case PICKER_STATE_GOTO_END:
+			{
+				buttonPressed_goto_end();
+				break;
+			}
+			case PICKER_STATE_PUT_DOWN:
+			{
+				buttonPressed_put_down();
+				break;
+			}
+			case PICKER_STATE_SQUAT:
+			{
+				buttonPressed_squat();
+				break;
+			}
+			case PICKER_STATE_JUMP:
+			{
+				buttonPressed_jump();
+				break;
+			}
+		}
+	}
 }
 
 
-void publishCurrentSetpoint()
+// CHANGE SETPOINT FUNCTION
+// This function does NOT need to be edited 
+void setNewSetpoint(int state, bool should_smooth, float x, float y, float z, float yaw, float mass)
 {
-	Setpoint msg_setpoint;
-    msg_setpoint.x   = m_setpoint[0];
-    msg_setpoint.y   = m_setpoint[1];
-    msg_setpoint.z   = m_setpoint[2];
-    msg_setpoint.yaw = m_setpoint[3];
+	// Put the state into the class variable
+	m_picker_current_state = state;
+
+	// Put the smoothing flag in the class variable
+	m_shouldSmoothSetpointChanges = should_smooth;
+
+	// Put the new setpoint into the class variable
+	m_setpoint[0] = x;
+	m_setpoint[1] = y;
+	m_setpoint[2] = z;
+	m_setpoint[3] = yaw;
+
+	// Put the mass into the class variable
+	m_mass_total_in_grams = mass;
+	m_weight_total_in_newtons = m_mass_total_in_grams * (9.81/1000.0);
+
+	// Publish the change so that the network is updated
+	// (mainly the "flying agent GUI" is interested in
+	// displaying this change to the user)
+
+	// Instantiate a local variable of type "SetpointWithHeader"
+	SetpointWithHeader msg;
+	// Fill in the setpoint
+	msg.buttonID  = state;
+	msg.isChecked = should_smooth;
+	msg.x         = x;
+	msg.y         = y;
+	msg.z         = z;
+	msg.yaw       = yaw;
+	msg.mass      = mass;
+	// Publish the message
+	m_setpointChangedPublisher.publish(msg);
+}
 
-    pickerSetpointToGUIPublisher.publish(msg_setpoint);
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+// This function does NOT need to be edited 
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response)
+{
+	// Directly put the current setpoint into the response
+	response.setpointWithHeader.buttonID  = m_picker_current_state;
+	response.setpointWithHeader.isChecked = m_shouldSmoothSetpointChanges;
+	response.setpointWithHeader.x         = m_setpoint[0];
+	response.setpointWithHeader.y         = m_setpoint[1];
+	response.setpointWithHeader.z         = m_setpoint[2];
+	response.setpointWithHeader.yaw       = m_setpoint[3];
+	response.setpointWithHeader.mass      = m_mass_total_in_grams;
+	// Return
+	return true;
 }
 
 
+
+
+
+
+// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// void setpointCallback(const Setpoint& newSetpoint)
+// {
+//     m_setpoint[0] = newSetpoint.x;
+//     m_setpoint[1] = newSetpoint.y;
+//     m_setpoint[2] = newSetpoint.z;
+//     m_setpoint[3] = newSetpoint.yaw;
+// }
+
+
+// void publishCurrentSetpoint()
+// {
+// 	Setpoint msg_setpoint;
+//     msg_setpoint.x   = m_setpoint[0];
+//     msg_setpoint.y   = m_setpoint[1];
+//     msg_setpoint.z   = m_setpoint[2];
+//     msg_setpoint.yaw = m_setpoint[3];
+
+//     pickerSetpointToGUIPublisher.publish(msg_setpoint);
+// }
+
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //     CCCC  U   U   SSSS  TTTTT   OOO   M   M
 //    C      U   U  S        T    O   O  MM MM
@@ -1150,107 +1336,107 @@ void publishCurrentSetpoint()
 //    ----------------------------------------------------------------------------------
 
 // CUSTOM COMMAND RECEIVED CALLBACK
-void buttonPressedCallback(const std_msgs::Int32& msg)
-{
-	// Extract the data from the message
-	int button_index = msg.data;
-
-	// Switch between the button pressed
-	switch(button_index)
-	{
-		case PICKER_BUTTON_GOTOSTART:
-			buttonPressed_gotoStart();
-			break;
-		case PICKER_BUTTON_ATTACH:
-			buttonPressed_attach();
-			break;
-		case PICKER_BUTTON_PICKUP:
-			buttonPressed_pickup();
-			break;
-		case PICKER_BUTTON_GOTOEND:
-			buttonPressed_gotoEnd();
-			break;
-		case PICKER_BUTTON_PUTDOWN:
-			buttonPressed_putdown();
-			break;
-		case PICKER_BUTTON_SQUAT:
-			buttonPressed_squat();
-			break;
-		case PICKER_BUTTON_JUMP:
-			buttonPressed_jump();
-			break;
-		case PICKER_BUTTON_1:
-			buttonPressed_1();
-			break;
-		case PICKER_BUTTON_2:
-			buttonPressed_2();
-			break;
-		case PICKER_BUTTON_3:
-			buttonPressed_3();
-			break;
-		case PICKER_BUTTON_4:
-			buttonPressed_4();
-			break;
-		default:
-		{
-			// Let the user know that the command was not recognised
-			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
-			break;
-		}
-	}
-}
-
-
-
-void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2)
-{
-	// Extract the "buttonID" from the message
-	int button_index = newSetpointV2.buttonID;
-
-	// Switch between the button pressed
-	switch(button_index)
-	{
-		case PICKER_BUTTON_GOTOSTART:
-			buttonPressedWithSetpoint_gotoStart(newSetpointV2);
-			break;
-		case PICKER_BUTTON_ATTACH:
-			buttonPressedWithSetpoint_attach(newSetpointV2);
-			break;
-		case PICKER_BUTTON_PICKUP:
-			buttonPressedWithSetpoint_pickup(newSetpointV2);
-			break;
-		case PICKER_BUTTON_GOTOEND:
-			buttonPressedWithSetpoint_gotoEnd(newSetpointV2);
-			break;
-		case PICKER_BUTTON_PUTDOWN:
-			buttonPressedWithSetpoint_putdown(newSetpointV2);
-			break;
-		case PICKER_BUTTON_SQUAT:
-			buttonPressedWithSetpoint_squat(newSetpointV2);
-			break;
-		case PICKER_BUTTON_JUMP:
-			buttonPressedWithSetpoint_jump(newSetpointV2);
-			break;
-		case PICKER_BUTTON_1:
-			buttonPressedWithSetpoint_1(newSetpointV2);
-			break;
-		case PICKER_BUTTON_2:
-			buttonPressedWithSetpoint_2(newSetpointV2);
-			break;
-		case PICKER_BUTTON_3:
-			buttonPressedWithSetpoint_3(newSetpointV2);
-			break;
-		case PICKER_BUTTON_4:
-			buttonPressedWithSetpoint_4(newSetpointV2);
-			break;
-		default:
-		{
-			// Let the user know that the command was not recognised
-			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
-			break;
-		}
-	}
-}
+// void buttonPressedCallback(const std_msgs::Int32& msg)
+// {
+// 	// Extract the data from the message
+// 	int button_index = msg.data;
+
+// 	// Switch between the button pressed
+// 	switch(button_index)
+// 	{
+// 		case PICKER_BUTTON_GOTOSTART:
+// 			buttonPressed_gotoStart();
+// 			break;
+// 		case PICKER_BUTTON_ATTACH:
+// 			buttonPressed_attach();
+// 			break;
+// 		case PICKER_BUTTON_PICKUP:
+// 			buttonPressed_pickup();
+// 			break;
+// 		case PICKER_BUTTON_GOTOEND:
+// 			buttonPressed_gotoEnd();
+// 			break;
+// 		case PICKER_BUTTON_PUTDOWN:
+// 			buttonPressed_putdown();
+// 			break;
+// 		case PICKER_BUTTON_SQUAT:
+// 			buttonPressed_squat();
+// 			break;
+// 		case PICKER_BUTTON_JUMP:
+// 			buttonPressed_jump();
+// 			break;
+// 		case PICKER_BUTTON_1:
+// 			buttonPressed_1();
+// 			break;
+// 		case PICKER_BUTTON_2:
+// 			buttonPressed_2();
+// 			break;
+// 		case PICKER_BUTTON_3:
+// 			buttonPressed_3();
+// 			break;
+// 		case PICKER_BUTTON_4:
+// 			buttonPressed_4();
+// 			break;
+// 		default:
+// 		{
+// 			// Let the user know that the command was not recognised
+// 			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
+// 			break;
+// 		}
+// 	}
+// }
+
+
+
+// void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2)
+// {
+// 	// Extract the "buttonID" from the message
+// 	int button_index = newSetpointV2.buttonID;
+
+// 	// Switch between the button pressed
+// 	switch(button_index)
+// 	{
+// 		case PICKER_BUTTON_GOTOSTART:
+// 			buttonPressedWithSetpoint_gotoStart(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_ATTACH:
+// 			buttonPressedWithSetpoint_attach(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_PICKUP:
+// 			buttonPressedWithSetpoint_pickup(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_GOTOEND:
+// 			buttonPressedWithSetpoint_gotoEnd(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_PUTDOWN:
+// 			buttonPressedWithSetpoint_putdown(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_SQUAT:
+// 			buttonPressedWithSetpoint_squat(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_JUMP:
+// 			buttonPressedWithSetpoint_jump(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_1:
+// 			buttonPressedWithSetpoint_1(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_2:
+// 			buttonPressedWithSetpoint_2(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_3:
+// 			buttonPressedWithSetpoint_3(newSetpointV2);
+// 			break;
+// 		case PICKER_BUTTON_4:
+// 			buttonPressedWithSetpoint_4(newSetpointV2);
+// 			break;
+// 		default:
+// 		{
+// 			// Let the user know that the command was not recognised
+// 			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
+// 			break;
+// 		}
+// 	}
+// }
 
 
 
@@ -1294,168 +1480,156 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+// LOADING OF YAML PARAMETERS
+void isReadyPickerControllerYamlCallback(const IntWithHeader & msg)
 {
-	// Extract from the "msg" for which controller the and from where to fetch the YAML
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
+	// Continue if the message is relevant
+	if (isRevelant)
 	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[PICKER CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR:
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
 		{
-			// Let the user know that this message was received
-			ROS_INFO("[PICKER CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[PICKER CONTROLLER] Now fetching the PickerController 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("[PICKER CONTROLLER] Now fetching the PickerController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
 
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The PickerControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
+			default:
+			{
+				ROS_ERROR("[PICKER CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
 		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchPickerControllerYamlParameters(nodeHandle_to_use);
 	}
 }
 
 
-// This function CAN BE edited for successful completion of the PPS 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)
+void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
-	// Here we load the parameters that are specified in the PickerController.yaml file
+	// Here we load the parameters that are specified in the file:
+	// StudentController.yaml
 
 	// Add the "PickerController" namespace to the "nodeHandle"
-	ros::NodeHandle nodeHandle_for_pickerController(nodeHandle, "PickerController");
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "PickerController");
+
 
-	// > The mass of the crazyflie
-	m_mass_CF_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_CF");
 
-	// > The mass of the letters
-	m_mass_E_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_E");
-	m_mass_T_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_T");
-	m_mass_H_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_H");
+	// GET THE PARAMETERS:
 
-	// Thickness of the object at pick-up and put-down, in [meters]
-	// > This should also account for extra height due to the surface where the object is
-	m_thickness_of_object_at_pickup  = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_pickup");
-	m_thickness_of_object_at_putdown = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_putdown");
+	// // // > The mass of the letters
+	// m_mass_E_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_E");
+	// m_mass_T_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_T");
+	// m_mass_H_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_H");
 
-	// (x,y) coordinates of the pickup location
-	getParameterFloatVector(nodeHandle_for_pickerController, "pickup_coordinates_xy", m_pickup_coordinates_xy, 2);
+	// // Thickness of the object at pick-up and put-down, in [meters]
+	// // > This should also account for extra height due to the surface where the object is
+	// m_thickness_of_object_at_pickup  = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_pickup");
+	// m_thickness_of_object_at_putdown = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_putdown");
 
-	// (x,y) coordinates of the drop off location
-	getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_E", m_dropoff_coordinates_xy_for_E, 2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_T", m_dropoff_coordinates_xy_for_T, 2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_H", m_dropoff_coordinates_xy_for_H, 2);
+	// // (x,y) coordinates of the pickup location
+	// getParameterFloatVector(nodeHandle_for_pickerController, "pickup_coordinates_xy", m_pickup_coordinates_xy, 2);
 
-	// Length of the string from the Crazyflie to the end of the Picker, in [meters]
-	m_picker_string_length = getParameterFloat(nodeHandle_for_pickerController , "picker_string_length");
+	// // (x,y) coordinates of the drop off location
+	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_E", m_dropoff_coordinates_xy_for_E, 2);
+	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_T", m_dropoff_coordinates_xy_for_T, 2);
+	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_H", m_dropoff_coordinates_xy_for_H, 2);
+
+	// // Length of the string from the Crazyflie to the end of the Picker, in [meters]
+	// m_picker_string_length = getParameterFloat(nodeHandle_for_pickerController , "picker_string_length");
 
 	// Max setpoint change per second
-	m_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_horizontal");
-	m_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_vertical");
-	m_max_setpoint_change_per_second_yaw_degrees = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_yaw_degrees");
+	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_horizontal");
+	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_vertical");
+	yaml_max_setpoint_change_per_second_yaw_degrees = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_yaw_degrees");
+
+	
 
-	// THE FOLLOWING PARAMETERS ARE USED FOR THE LOW-LEVEL CONTROLLER
+	// ------------------------------------------------------
+	// PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
-	// > The frequency at which the "computeControlOutput" is being called, as determined
-	//   by the frequency at which the Vicon system provides position and attitude data
-	m_vicon_frequency = getParameterFloat(nodeHandle_for_pickerController, "vicon_frequency");
+	// > The mass of the crazyflie
+	yaml_mass_cf_in_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_cf_in_grams");
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	control_frequency = getParameterFloat(nodeHandle_for_pickerController, "control_frequency");
+	yaml_control_frequency = getParameterFloat(nodeHandle_for_pickerController, "control_frequency");
 
 	// > The co-efficients of the quadratic conversation from 16-bit motor command to
 	//   thrust force in Newtons
-	getParameterFloatVector(nodeHandle_for_pickerController, "motorPoly", motorPoly, 3);
+	getParameterFloatVector(nodeHandle_for_pickerController, "motorPoly", yaml_motorPoly, 3);
 
 	// > The boolean for whether to execute the convert into body frame function
-	shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_pickerController, "shouldPerformConvertIntoBodyFrame");
+	yaml_shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_pickerController, "shouldPerformConvertIntoBodyFrame");
 
-	// > The boolean indicating whether the (x,y,z,yaw) of this agent should be published
-	//   or not
-	shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_pickerController, "shouldPublishCurrent_xyz_yaw");
+	// // > The boolean indicating whether the (x,y,z,yaw) of this agent should be published
+	// //   or not
+	// shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_pickerController, "shouldPublishCurrent_xyz_yaw");
 
 	// Boolean indiciating whether the "Debug Message" of this agent should be published or not
-	shouldPublishDebugMessage = getParameterBool(nodeHandle_for_pickerController, "shouldPublishDebugMessage");
+	yaml_shouldPublishDebugMessage = getParameterBool(nodeHandle_for_pickerController, "shouldPublishDebugMessage");
 
 	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-	shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_pickerController, "shouldDisplayDebugInfo");
-
-
-	// THE CONTROLLER GAINS:
+	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_pickerController, "shouldDisplayDebugInfo");
 
 	// A flag for which estimator to use:
-	estimator_method = getParameterInt( nodeHandle_for_pickerController , "estimator_method" );
+	yaml_estimator_method = getParameterInt( nodeHandle_for_pickerController , "estimator_method" );
 
 	// The LQR Controller parameters for "LQR_MODE_RATE"
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixThrust_NineStateVector", gainMatrixThrust_NineStateVector, 9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixRollRate",               gainMatrixRollRate,               9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixPitchRate",              gainMatrixPitchRate,              9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixYawRate",                gainMatrixYawRate,                9);
+	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
 		
 	// 16-BIT COMMAND LIMITS
-	cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_min");
-	cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_max");
-
+	yaml_cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_min");
+	yaml_cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_max");
 
 	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 	// > For the (x,y,z) position
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_positions",  yaml_PMKF_Ahat_row1_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_positions",  yaml_PMKF_Ahat_row2_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_positions"     ,  yaml_PMKF_Kinf_for_positions     ,  2);
 	// > For the (roll,pitch,yaw) angles
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_angles",  yaml_PMKF_Ahat_row1_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_angles",  yaml_PMKF_Ahat_row2_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_angles"     ,  yaml_PMKF_Kinf_for_angles     ,  2);
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
-	ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: the fetched PickerController/mass_CF = " << m_mass_CF_grams);
+	ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: the fetched PickerController/mass_cf_in_grams = " << yaml_mass_cf_in_grams);
 
-	// Call the function that computes details an values that are needed from these
-	// parameters loaded above
-	processFetchedParameters();
 
-}
 
-
-// This function CAN BE edited for successful completion of the PPS 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()
-{
+	// PROCESS THE PARAMTERS
 	// Convert from degrees to radians
-	m_max_setpoint_change_per_second_yaw_radians = DEG2RAD * m_max_setpoint_change_per_second_yaw_degrees;
+	m_max_setpoint_change_per_second_yaw_radians = DEG2RAD * yaml_max_setpoint_change_per_second_yaw_degrees;
 
     // Set that the estimator frequency is the same as the control frequency
-    estimator_frequency = m_vicon_frequency;
-}
+    m_estimator_frequency = yaml_control_frequency;
 
+}
 
 
 
@@ -1468,64 +1642,64 @@ void processFetchedParameters()
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val.size();
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
-{
-    bool val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
+// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
+// {
+//     float val;
+//     if(!nodeHandle.getParam(name, val))
+//     {
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     return val;
+// }
+// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
+// {
+//     if(!nodeHandle.getParam(name, val)){
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     if(val.size() != length) {
+//         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 getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
+// {
+//     int val;
+//     if(!nodeHandle.getParam(name, val))
+//     {
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     return val;
+// }
+// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
+// {
+//     if(!nodeHandle.getParam(name, val)){
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     if(val.size() != length) {
+//         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 getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
+// {
+//     if(!nodeHandle.getParam(name, val)){
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     return val.size();
+// }
+// // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
+// bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
+// {
+//     bool val;
+//     if(!nodeHandle.getParam(name, val))
+//     {
+//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
+//     }
+//     return val;
+// }
     
 
 
@@ -1546,107 +1720,186 @@ int main(int argc, char* argv[]) {
     // Starting the ROS-node
     ros::init(argc, argv, "PickerControllerService");
 
-    // Create a "ros::NodeHandle" type local variable "nodeHandle" as the current node,
-    // the "~" indcates that "self" is the node handle assigned to this variable.
+    // 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 "PickerControllerService" node
     std::string m_namespace = ros::this_node::getNamespace();
     ROS_INFO_STREAM("[PICKER CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
 
-    // Get the agent ID as the "ROS_NAMESPACE" this computer.
-    // NOTES:
-    // > 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"
-    // > 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");
-    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
-    {
-    	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[PICKER CONTROLLER] Failed to get agentID from PPSClient");
+
+
+	// 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
+	//   "PPSClient" node.
+	// > 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 ID of the agent and its coordinator
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[PICKER CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[PICKER CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
 	}
 
+    
 
-	// *********************************************************************************
-	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
+	// 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.
 
-	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+	// 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";
 
-	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-    // namespace string for the parameter service that is running on the machine of this
-    // agent
-    namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
-    // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[PICKER CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[PICKER CONTROLLER] m_namespace_to_coordinator_parameter_service  =  " << m_namespace_to_coordinator_parameter_service);
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+	// 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+
+
+
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber pickerContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "PickerController", 1, isReadyStudentControllerYamlCallback);
+	ros::Subscriber pickerContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("PickerController", 1, isReadyStudentControllerYamlCallback);
+
+
+
+	// GIVE YAML VARIABLES AN INITIAL VALUE
+	// This can be done either here or as part of declaring the
+	// variables in the header file
+
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// The yaml files for the controllers are not added to
+	// "Parameter Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// service call containing the filename of the *.yaml file,
+	// and then a message will be received on the above subscribers
+	// when the paramters are ready.
+	// > NOTE IMPORTANTLY that by using a serice client
+	//   we stall the availability of this node until the
+	//   paramter service is ready
+
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyStudentControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+		// Inform the user
+		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
+	}
 
 
-    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-    //       is very important because it specifies that the name is global
-    namespace_to_coordinator_parameter_service = "/ParameterService";
 
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-    
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    // INITIALISE OTHER VARIABLES AS REQUIRED
+    m_mass_total_in_grams = yaml_mass_cf_in_grams;
+    m_weight_total_in_newtons = m_mass_total_in_grams * (9.81/1000.0);
 
 
-    // PRINT OUT SOME INFORMATION
 
-    // Let the user know what namespaces are being used for linking to the parameter service
-    ROS_INFO_STREAM("[PICKER CONTROLLER] the namespace strings for accessing the Paramter Services are:");
-    ROS_INFO_STREAM("[PICKER CONTROLLER] namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
-    ROS_INFO_STREAM("[PICKER CONTROLLER] namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
 
 
-    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
+    // PUBLISHERS AND SUBSCRIBERS
 
-	// Call the class function that loads the parameters for this class.
-    fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+    // Instantiate the class variable "m_debugPublisher" to be a
+    // "ros::Publisher". This variable advertises under the name
+    // "DebugTopic" and is a message with the structure defined
+    //  in the file "DebugMsg.msg" (located in the "msg" folder).
+    m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-    // Initialise the total mass to be just the crazyflie
-    m_mass_total_grams = m_mass_CF_grams;
+    // Instantiate the local variable "requestSetpointChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestSetpointChange" topic and calls the class function
+	// "requestSetpointChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the setpoint is changed
+	// by the user.
+	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
 
-    // *********************************************************************************
+	// Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("PickerControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
 
+	// Instantiate the class variable "m_setpointChangedPublisher" to
+	// be a "ros::Publisher". This variable advertises under the name
+	// "SetpointChanged" and is a message with the structure defined
+	// in the file "SetpointWithHeader.msg" (located in the "msg" folder).
+	// This publisher is used by the "flying agent GUI" to update the
+	// field that displays the current setpoint for this controller.
+	m_setpointChangedPublisher = nodeHandle.advertise<SetpointWithHeader>("SetpointChanged", 1);
 
+	// Instantiate the local variable "getCurrentSetpointService" to be
+	// a "ros::ServiceServer" type variable that advertises the service
+	// called "GetCurrentSetpoint". This service has the input-output
+	// behaviour defined in the "GetSetpointService.srv" file (located
+	// in the "srv" folder). This service, when called, is provided with
+	// an integer (that is essentially ignored), and is expected to respond
+	// with the current setpoint of the controller. When a request is made
+	// of this service the "getCurrentSetpointCallback" function is called.
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);
 
-    // Instantiate the instance variable "debugPublisher" to be a "ros::Publisher" that
-    // advertises under the name "DebugTopic" and is a message with the structure
-    // defined in the file "DebugMsg.msg" (located in the "msg" folder).
-    debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-    // Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "Setpoint" topic and calls the class function
-    // "setpointCallback" each time a messaged is received on this topic and the message
-    // is passed as an input argument to the "setpointCallback" class function.
-    ros::Subscriber setpointSubscriber = nodeHandle.subscribe("Setpoint", 1, setpointCallback);
 
     // Instantiate the local variable "service" to be a "ros::ServiceServer" type
     // variable that advertises the service called "PickerController". This service has
@@ -1662,13 +1915,13 @@ int main(int argc, char* argv[]) {
     // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
     //     "using namespace d_fall_pps;"
     // in the "DEFINES" section at the top of this file.
-    ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
     // Instantiate the instance variable "my_current_xyz_yaw_publisher" to be a "ros::Publisher"
     // that advertises under the name "<my_agentID>/my_current_xyz_yaw_topic" where <my_agentID>
     // is filled in with the student ID number of this computer. The messages published will
     // have the structure defined in the file "Setpoint.msg" (located in the "msg" folder).
-    my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
+    //my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
 
     // Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
     // type variable that subscribes to the "StudentCustomButton" topic and calls the class
@@ -1678,17 +1931,17 @@ int main(int argc, char* argv[]) {
 
 
 
-    // ADDED FOR THE PICKER
-    ros::Subscriber pickerButtonPressedSubscriber  =  nodeHandle.subscribe("ButtonPressed", 1, buttonPressedCallback);
-    ros::Subscriber pickerZSetpointSubscriber      =  nodeHandle.subscribe("ZSetpoint", 1, zSetpointCallback);
-    ros::Subscriber pickerYawSetpointSubscriber    =  nodeHandle.subscribe("YawSetpoint", 1, yawSetpointCallback);
-    ros::Subscriber pickerMassSubscriber           =  nodeHandle.subscribe("Mass", 1, massCallback);
-    ros::Subscriber pickerXAdjustmentSubscriber    =  nodeHandle.subscribe("XAdjustment", 1, xAdjustmentCallback);
-    ros::Subscriber pickerYAdjustmentSubscriber    =  nodeHandle.subscribe("YAdjustment", 1, yAdjustmentCallback);
+    // // ADDED FOR THE PICKER
+    // ros::Subscriber pickerButtonPressedSubscriber  =  nodeHandle.subscribe("ButtonPressed", 1, buttonPressedCallback);
+    // ros::Subscriber pickerZSetpointSubscriber      =  nodeHandle.subscribe("ZSetpoint", 1, zSetpointCallback);
+    // ros::Subscriber pickerYawSetpointSubscriber    =  nodeHandle.subscribe("YawSetpoint", 1, yawSetpointCallback);
+    // ros::Subscriber pickerMassSubscriber           =  nodeHandle.subscribe("Mass", 1, massCallback);
+    // ros::Subscriber pickerXAdjustmentSubscriber    =  nodeHandle.subscribe("XAdjustment", 1, xAdjustmentCallback);
+    // ros::Subscriber pickerYAdjustmentSubscriber    =  nodeHandle.subscribe("YAdjustment", 1, yAdjustmentCallback);
 
-    pickerSetpointToGUIPublisher = nodeHandle.advertise<Setpoint>("SetpointToGUI", 1);
+    // pickerSetpointToGUIPublisher = nodeHandle.advertise<Setpoint>("SetpointToGUI", 1);
 
-    ros::Subscriber pickerButtonPressedWithSetpointSubscriber  =  nodeHandle.subscribe("ButtonPressedWithSetpoint", 1, buttonPressedWithSetpointCallback);
+    // ros::Subscriber pickerButtonPressedWithSetpointSubscriber  =  nodeHandle.subscribe("ButtonPressedWithSetpoint", 1, buttonPressedWithSetpointCallback);
 
 
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index c7e22404..426be3b4 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -962,7 +962,7 @@ int main(int argc, char* argv[]) {
 	}
 	else
 	{
-	// Inform the user
+		// Inform the user
 		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
 	}
 
@@ -1011,7 +1011,7 @@ int main(int argc, char* argv[]) {
 	// an integer (that is essentially ignored), and is expected to respond
 	// with the current setpoint of the controller. When a request is made
 	// of this service the "getCurrentSetpointCallback" function is called.
-	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);	
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);
 
 
 
-- 
GitLab


From b0e82186eb09a5e99b75388e390649cbdf74bf19 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 12:15:12 +0100
Subject: [PATCH 40/87] Changes to the Picker Controller Service so that it now
 compiles. Needs testing

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   3 +-
 .../include/nodes/PickerControllerService.h   |  19 ++--
 .../src/nodes/PickerControllerService.cpp     | 102 +++++++++---------
 3 files changed, 63 insertions(+), 61 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 961c45c4..1748c5e2 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -339,7 +339,8 @@ add_executable(StudentControllerService  src/nodes/StudentControllerService.cpp
 add_executable(MpcControllerService      src/nodes/MpcControllerService.cpp)
 add_executable(RemoteControllerService   src/nodes/RemoteControllerService.cpp)
 add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp)
-add_executable(PickerControllerService   src/nodes/PickerControllerService.cpp)
+add_executable(PickerControllerService   src/nodes/PickerControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(CentralManagerService     src/nodes/CentralManagerService.cpp src/CrazyflieIO.cpp)
 add_executable(ParameterService          src/nodes/ParameterService.cpp)
 
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index 359438b9..c5107230 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -77,7 +77,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
-#include "nodes/PickerContorllerConstants.h"
+#include "nodes/PickerControllerConstants.h"
 
 // Include other classes
 #include "classes/GetParamtersAndNamespaces.h"
@@ -157,9 +157,9 @@ using namespace d_fall_pps;
 // ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED
 //       Uses the model of the quad-rotor and the previous inputs
 //
-// #define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
-// #define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
-// #define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3
+#define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
+#define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
+#define ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED      3
 
 
 
@@ -193,11 +193,11 @@ float m_weight_total_in_newtons;
 
 // The setpoint to be tracked, the ordering is (x,y,z,yaw),
 // with units [meters,meters,meters,radians]
-std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
+float  m_setpoint[4] = {0.0,0.0,0.4,0.0};
 
 // The setpoint that is actually used by the controller, this
 // differs from the setpoint when smoothing is turned on
-std::vector<float> m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
+float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
 
 // Boolean for whether to limit rate of change of the setpoint
 bool m_shouldSmoothSetpointChanges = true;
@@ -266,7 +266,7 @@ float yaml_cmd_sixteenbit_max = 60000;
 // VARIABLES FOR THE ESTIMATOR
 
 // Frequency at which the controller is running
-float yaml_estimator_frequency = 200.0;
+float m_estimator_frequency = 200.0;
 
 // > A flag for which estimator to use:
 int yaml_estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
@@ -543,7 +543,7 @@ void perControlCycleOperations();
 // void xAdjustmentCallback(const std_msgs::Float32& msg);
 // void yAdjustmentCallback(const std_msgs::Float32& msg);
 
-void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2);
+//void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2);
 
 
 // SEPARATE CALLBACK FUNCTIONS FOR EACH BUTTON
@@ -616,7 +616,8 @@ float computeMotorPolyBackward(float thrust);
 void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
 
 // CHANGE SETPOINT FUNCTION
-void setNewSetpoint(float x, float y, float z, float yaw);
+//void setNewSetpoint(float x, float y, float z, float yaw);
+void setNewSetpoint(int state, bool should_smooth, float x, float y, float z, float yaw, float mass);
 
 // GET CURRENT SETPOINT SERVICE CALLBACK
 bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
index ee97a8c3..d762170a 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
@@ -94,7 +94,7 @@
 // float yaml_max_setpoint_change_per_second_yaw_degrees;
 // float m_max_setpoint_change_per_second_yaw_radians;
 // // Frequency at which the controller is running
-// float m_control_frequency;
+// float yaml_control_frequency;
 
 
 // A FEW EXTRA COMMENTS ABOUT THE MOST IMPORTANT VARIABLES
@@ -142,7 +142,7 @@ void perControlCycleOperations()
 // CALLBACK FUNCTION THAT RUN WHEN THE RESPECTIVE BUTTON IS PRESSED
 
 // These functions are called from:
-// >> "buttonPressedWithSetpointCallback"
+// >> "requestSetpointChangeCallback"
 // And in that function the following variable are already
 // updated appropriately:
 // >> "m_picker_current_state"
@@ -467,16 +467,16 @@ void smoothSetpointChanges()
 			switch (i)
 			{
 				case 0:
-					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / m_control_frequency;
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / yaml_control_frequency;
 					break;
 				case 1:
-					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / m_control_frequency;
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_horizontal / yaml_control_frequency;
 					break;
 				case 2:
-					max_for_this_coordinate = yaml_max_setpoint_change_per_second_vertical / m_control_frequency;
+					max_for_this_coordinate = yaml_max_setpoint_change_per_second_vertical / yaml_control_frequency;
 					break;
 				case 3:
-					max_for_this_coordinate = m_max_setpoint_change_per_second_yaw_radians / m_control_frequency;
+					max_for_this_coordinate = m_max_setpoint_change_per_second_yaw_radians / yaml_control_frequency;
 					break;
 				// Handle the exception
 				default:
@@ -632,7 +632,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 	// Keep track of time
 	//m_time_ticks++;
-	//m_time_seconds = float(m_time_ticks) / m_control_frequency;
+	//m_time_seconds = float(m_time_ticks) / yaml_control_frequency;
 
 
 	// CALL THE FUNCTION FOR PER CYLCE OPERATIONS
@@ -1450,15 +1450,15 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 // PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
 void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 {
-	// publish setpoint for FollowController of another student group
-	Setpoint temp_current_xyz_yaw;
-	// Fill in the x,y,z, and yaw info directly from the data provided to this
-	// function
-	temp_current_xyz_yaw.x   = x;
-	temp_current_xyz_yaw.y   = y;
-	temp_current_xyz_yaw.z   = z;
-	temp_current_xyz_yaw.yaw = yaw;
-	my_current_xyz_yaw_publisher.publish(temp_current_xyz_yaw);
+	// // publish setpoint for FollowController of another student group
+	// SetpointWithHeader temp_current_xyz_yaw;
+	// // Fill in the x,y,z, and yaw info directly from the data provided to this
+	// // function
+	// temp_current_xyz_yaw.x   = x;
+	// temp_current_xyz_yaw.y   = y;
+	// temp_current_xyz_yaw.z   = z;
+	// temp_current_xyz_yaw.yaw = yaw;
+	// m_current_xyz_yaw_publisher.publish(temp_current_xyz_yaw);
 }
 
 
@@ -1539,30 +1539,30 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// GET THE PARAMETERS:
 
 	// // // > The mass of the letters
-	// m_mass_E_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_E");
-	// m_mass_T_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_T");
-	// m_mass_H_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_H");
+	// m_mass_E_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_E");
+	// m_mass_T_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_T");
+	// m_mass_H_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_H");
 
 	// // Thickness of the object at pick-up and put-down, in [meters]
 	// // > This should also account for extra height due to the surface where the object is
-	// m_thickness_of_object_at_pickup  = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_pickup");
-	// m_thickness_of_object_at_putdown = getParameterFloat(nodeHandle_for_pickerController , "thickness_of_object_at_putdown");
+	// m_thickness_of_object_at_pickup  = getParameterFloat(nodeHandle_for_paramaters , "thickness_of_object_at_pickup");
+	// m_thickness_of_object_at_putdown = getParameterFloat(nodeHandle_for_paramaters , "thickness_of_object_at_putdown");
 
 	// // (x,y) coordinates of the pickup location
-	// getParameterFloatVector(nodeHandle_for_pickerController, "pickup_coordinates_xy", m_pickup_coordinates_xy, 2);
+	// getParameterFloatVector(nodeHandle_for_paramaters, "pickup_coordinates_xy", m_pickup_coordinates_xy, 2);
 
 	// // (x,y) coordinates of the drop off location
-	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_E", m_dropoff_coordinates_xy_for_E, 2);
-	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_T", m_dropoff_coordinates_xy_for_T, 2);
-	// getParameterFloatVector(nodeHandle_for_pickerController, "dropoff_coordinates_xy_for_H", m_dropoff_coordinates_xy_for_H, 2);
+	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_E", m_dropoff_coordinates_xy_for_E, 2);
+	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_T", m_dropoff_coordinates_xy_for_T, 2);
+	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_H", m_dropoff_coordinates_xy_for_H, 2);
 
 	// // Length of the string from the Crazyflie to the end of the Picker, in [meters]
-	// m_picker_string_length = getParameterFloat(nodeHandle_for_pickerController , "picker_string_length");
+	// m_picker_string_length = getParameterFloat(nodeHandle_for_paramaters , "picker_string_length");
 
 	// Max setpoint change per second
-	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_horizontal");
-	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_vertical");
-	yaml_max_setpoint_change_per_second_yaw_degrees = getParameterFloat(nodeHandle_for_pickerController , "max_setpoint_change_per_second_yaw_degrees");
+	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_horizontal");
+	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_vertical");
+	yaml_max_setpoint_change_per_second_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_yaw_degrees");
 
 	
 
@@ -1570,51 +1570,51 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
 	// > The mass of the crazyflie
-	yaml_mass_cf_in_grams = getParameterFloat(nodeHandle_for_pickerController , "mass_cf_in_grams");
+	yaml_mass_cf_in_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_cf_in_grams");
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	yaml_control_frequency = getParameterFloat(nodeHandle_for_pickerController, "control_frequency");
+	yaml_control_frequency = getParameterFloat(nodeHandle_for_paramaters, "control_frequency");
 
 	// > The co-efficients of the quadratic conversation from 16-bit motor command to
 	//   thrust force in Newtons
-	getParameterFloatVector(nodeHandle_for_pickerController, "motorPoly", yaml_motorPoly, 3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", yaml_motorPoly, 3);
 
 	// > The boolean for whether to execute the convert into body frame function
-	yaml_shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_pickerController, "shouldPerformConvertIntoBodyFrame");
+	yaml_shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_paramaters, "shouldPerformConvertIntoBodyFrame");
 
 	// // > The boolean indicating whether the (x,y,z,yaw) of this agent should be published
 	// //   or not
-	// shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_pickerController, "shouldPublishCurrent_xyz_yaw");
+	// shouldPublishCurrent_xyz_yaw = getParameterBool(nodeHandle_for_paramaters, "shouldPublishCurrent_xyz_yaw");
 
 	// Boolean indiciating whether the "Debug Message" of this agent should be published or not
-	yaml_shouldPublishDebugMessage = getParameterBool(nodeHandle_for_pickerController, "shouldPublishDebugMessage");
+	yaml_shouldPublishDebugMessage = getParameterBool(nodeHandle_for_paramaters, "shouldPublishDebugMessage");
 
 	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_pickerController, "shouldDisplayDebugInfo");
+	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paramaters, "shouldDisplayDebugInfo");
 
 	// A flag for which estimator to use:
-	yaml_estimator_method = getParameterInt( nodeHandle_for_pickerController , "estimator_method" );
+	yaml_estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );
 
 	// The LQR Controller parameters for "LQR_MODE_RATE"
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
-	getParameterFloatVector(nodeHandle_for_pickerController, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
 		
 	// 16-BIT COMMAND LIMITS
-	yaml_cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_min");
-	yaml_cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_pickerController, "command_sixteenbit_max");
+	yaml_cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_min");
+	yaml_cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_max");
 
 	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 	// > For the (x,y,z) position
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_positions",  yaml_PMKF_Ahat_row1_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_positions",  yaml_PMKF_Ahat_row2_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_positions"     ,  yaml_PMKF_Kinf_for_positions     ,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_positions",  yaml_PMKF_Ahat_row1_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_positions",  yaml_PMKF_Ahat_row2_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_positions"     ,  yaml_PMKF_Kinf_for_positions     ,  2);
 	// > For the (roll,pitch,yaw) angles
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row1_for_angles",  yaml_PMKF_Ahat_row1_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Ahat_row2_for_angles",  yaml_PMKF_Ahat_row2_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_pickerController, "PMKF_Kinf_for_angles"     ,  yaml_PMKF_Kinf_for_angles     ,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_angles",  yaml_PMKF_Ahat_row1_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_angles",  yaml_PMKF_Ahat_row2_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_angles"     ,  yaml_PMKF_Kinf_for_angles     ,  2);
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
@@ -1797,8 +1797,8 @@ int main(int argc, char* argv[]) {
 
 	// The parameter service publishes messages with names of the form:
 	// /dfall/.../ParameterService/<filename with .yaml extension>
-	ros::Subscriber pickerContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "PickerController", 1, isReadyStudentControllerYamlCallback);
-	ros::Subscriber pickerContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("PickerController", 1, isReadyStudentControllerYamlCallback);
+	ros::Subscriber pickerContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "PickerController", 1, isReadyPickerControllerYamlCallback);
+	ros::Subscriber pickerContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("PickerController", 1, isReadyPickerControllerYamlCallback);
 
 
 
-- 
GitLab


From 8fbe898c30afc8a3c61d85a8c14949d482d764cf Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 15:56:59 +0100
Subject: [PATCH 41/87] Fixed bug that was causing the GUI to crash when
 setting the green frame for which state is active

---
 .../include/pickercontrollertab.h             |   7 +-
 .../src/pickercontrollertab.cpp               | 200 ++++++++++++------
 2 files changed, 142 insertions(+), 65 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 6247cc79..08769c25 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -3,6 +3,7 @@
 
 #include <QWidget>
 #include <QMutex>
+#include <QTimer>
 #include <QVector>
 #include <QTextStream>
 
@@ -87,6 +88,9 @@ public slots:
 
 
 private slots:
+
+    // FOR ALL THE GUI BUTTONS AND FIELDS
+
     void on_button_goto_start_clicked();
 
     void on_button_attach_clicked();
@@ -258,7 +262,8 @@ private:
     QMutex m_agentIDs_toCoordinate_mutex;
 
     // THE CURRENT STATE OF THE PICKER
-    int current_picker_state = PICKER_STATE_STANDBY;
+    int m_current_picker_state = PICKER_STATE_UNKNOWN;
+    QMutex m_current_picker_state_mutex;
 
 #ifdef CATKIN_MAKE
     // PUBLISHER
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index 17b4ef60..c59fed6f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -10,14 +10,24 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
 
     // HIDE ALL THE "GREEN FRAMES"
     // > These indicate which state is currently active
-    ui->frame_goto_start_active->setVisible(false);
-    ui->frame_attach_active    ->setVisible(false);
-    ui->frame_lift_up_active   ->setVisible(false);
-    ui->frame_goto_end_active  ->setVisible(false);
-    ui->frame_put_down_active  ->setVisible(false);
-    ui->frame_squat_active     ->setVisible(false);
-    ui->frame_jump_active      ->setVisible(false);
-    ui->frame_standby_active   ->setVisible(false);
+    ui->frame_goto_start_active->setVisible(true);
+    ui->frame_attach_active    ->setVisible(true);
+    ui->frame_lift_up_active   ->setVisible(true);
+    ui->frame_goto_end_active  ->setVisible(true);
+    ui->frame_put_down_active  ->setVisible(true);
+    ui->frame_squat_active     ->setVisible(true);
+    ui->frame_jump_active      ->setVisible(true);
+    ui->frame_standby_active   ->setVisible(true);
+    // > Make them all white
+    ui->frame_goto_start_active->setStyleSheet("background-color:white;");
+    ui->frame_attach_active    ->setStyleSheet("background-color:white;");
+    ui->frame_lift_up_active   ->setStyleSheet("background-color:white;");
+    ui->frame_goto_end_active  ->setStyleSheet("background-color:white;");
+    ui->frame_put_down_active  ->setStyleSheet("background-color:white;");
+    ui->frame_squat_active     ->setStyleSheet("background-color:white;");
+    ui->frame_jump_active      ->setStyleSheet("background-color:white;");
+    ui->frame_standby_active   ->setStyleSheet("background-color:white;");
+    
 
     // SET DEFAULTS FOR THE INCREMENT
     ui->lineEdit_increment_x   ->setText(QString::number( DEFAULT_INCREMENT_POSITION_XY,   'f', DECIMAL_PLACES_POSITION));
@@ -152,10 +162,12 @@ PickerControllerTab::~PickerControllerTab()
 
 void PickerControllerTab::publish_setpoint_if_current_state_matches(QVector<int> state_to_match)
 {
-    if ( state_to_match.contains(current_picker_state) )
+    m_current_picker_state_mutex.lock();
+    if ( state_to_match.contains(m_current_picker_state) )
     {
-        publish_request_setpoint_change_for_state(current_picker_state);
+        publish_request_setpoint_change_for_state(m_current_picker_state);
     }
+    m_current_picker_state_mutex.unlock();
 }
 
 void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to_publish)
@@ -354,73 +366,133 @@ void PickerControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWith
     ui->checkbox_current->setChecked(smooth);
 
 
+
     // MAKE THE "GREEN FRAME" VISIBLE ONLY FOR THE CURRENT STATE
+    // Lock the mutex that we will access "m_current_picker_state"
+    m_current_picker_state_mutex.lock();
 
-    // First make all of them NOT visible
-    ui->frame_goto_start_active->setVisible(false);
-    ui->frame_attach_active    ->setVisible(false);
-    ui->frame_lift_up_active   ->setVisible(false);
-    ui->frame_goto_end_active  ->setVisible(false);
-    ui->frame_put_down_active  ->setVisible(false);
-    ui->frame_squat_active     ->setVisible(false);
-    ui->frame_jump_active      ->setVisible(false);
-    ui->frame_standby_active   ->setVisible(false);
+    // Put things into more readable variables
+    int new_state = state;
+    int previous_state = m_current_picker_state;
 
-    // Switch between the possible states
-    switch (state)
-    {
-    case PICKER_STATE_STANDBY:
-    {
-        ui->frame_standby_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_GOTO_START:
-    {
-        ui->frame_goto_start_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_ATTACH:
-    {
-        ui->frame_attach_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_LIFT_UP:
-    {
-        ui->frame_lift_up_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_GOTO_END:
-    {
-        ui->frame_goto_end_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_PUT_DOWN:
-    {
-        ui->frame_put_down_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_SQUAT:
-    {
-        ui->frame_squat_active->setVisible(true);
-        break;
-    }
-    case PICKER_STATE_JUMP:
+    // Update the class variable for tracking the state
+    if ( new_state != previous_state )
+        m_current_picker_state = new_state;
+
+    // Change the "GREEN FRAME" if the state changed
+    if ( new_state != previous_state )
     {
-        ui->frame_standby_active->setVisible(true);
-        break;
+        // Make the new one green
+        switch (new_state)
+        {
+        case PICKER_STATE_STANDBY:
+        {
+            ui->frame_standby_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_GOTO_START:
+        {
+            ui->frame_goto_start_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_ATTACH:
+        {
+            ui->frame_attach_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_LIFT_UP:
+        {
+            ui->frame_lift_up_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_GOTO_END:
+        {
+            ui->frame_goto_end_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_PUT_DOWN:
+        {
+            ui->frame_put_down_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_SQUAT:
+        {
+            ui->frame_squat_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        case PICKER_STATE_JUMP:
+        {
+            ui->frame_jump_active->setStyleSheet("background-color:green;");
+            break;
+        }
+        default:
+        {
+            break;
+        }
+        }
+
+        // And the old one not white
+        switch (previous_state)
+        {
+        case PICKER_STATE_STANDBY:
+        {
+            ui->frame_standby_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_GOTO_START:
+        {
+            ui->frame_goto_start_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_ATTACH:
+        {
+            ui->frame_attach_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_LIFT_UP:
+        {
+            ui->frame_lift_up_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_GOTO_END:
+        {
+            ui->frame_goto_end_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_PUT_DOWN:
+        {
+            ui->frame_put_down_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_SQUAT:
+        {
+            ui->frame_squat_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        case PICKER_STATE_JUMP:
+        {
+            ui->frame_jump_active->setStyleSheet("background-color:white;");
+            break;
+        }
+        default:
+        {
+            break;
+        }
+        }
     }
-    default:
+    else
     {
-        break;
+        // NOTHING TO CHANGE
     }
-    }
-
+    // Unlock the mutex for accessing "m_current_picker_state"
+    m_current_picker_state_mutex.unlock();
 }
 #endif
 
 
 
 
+
 //    ----------------------------------------------------------------------------------
 //    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
 //    P   P  O   O  S      E         D   D   A A     T     A A
-- 
GitLab


From fcffdbb4bb05240d79de8f6fc105fb762fd252ff Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 16:25:36 +0100
Subject: [PATCH 42/87] Fixed small error for loading yaml file for picker
 controller

---
 .../d_fall_pps/include/nodes/PickerControllerService.h    | 2 +-
 pps_ws/src/d_fall_pps/param/PickerController.yaml         | 2 +-
 .../src/d_fall_pps/src/nodes/PickerControllerService.cpp  | 8 ++++----
 3 files changed, 6 insertions(+), 6 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index c5107230..67173f96 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -232,7 +232,7 @@ std::string m_namespace_to_coordinator_parameter_service;
 // VARIABLES FOR THE CONTOLLER
 
 // > the mass of the crazyflie, in [grams]
-float yaml_mass_cf_in_grams = 25.0;
+float yaml_mass_cf_in_grams = 30.0;
 
 // > the coefficients of the 16-bit command to thrust conversion
 //std::vector<float> yaml_motorPoly(3);
diff --git a/pps_ws/src/d_fall_pps/param/PickerController.yaml b/pps_ws/src/d_fall_pps/param/PickerController.yaml
index 65e5fff4..e9ee0b09 100644
--- a/pps_ws/src/d_fall_pps/param/PickerController.yaml
+++ b/pps_ws/src/d_fall_pps/param/PickerController.yaml
@@ -58,7 +58,7 @@ shouldPerformConvertIntoBodyFrame : true
 #shouldPublishCurrent_xyz_yaw : true
 
 # Boolean indiciating whether the "Debug Message" of this agent should be published or not
-shouldPublishDebugMessage : true
+shouldPublishDebugMessage : false
 
 # Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
 shouldDisplayDebugInfo : false
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
index d762170a..63346c0f 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
@@ -638,6 +638,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// CALL THE FUNCTION FOR PER CYLCE OPERATIONS
 	perControlCycleOperations();
 
+
 	// THIS IS THE START OF THE "OUTER" CONTROL LOOP
 	// > i.e., this is the control loop run on this laptop
 	// > this function is called at the frequency specified
@@ -654,7 +655,8 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// SMOOTH ANY CHANGES THAT MAY HAVE OCCURRED IN THE
 	// SETPOINT
 	smoothSetpointChanges();
-	
+
+
 	// CONVERT THE CURRENT INERTIAL FRAME STATE ESTIMATE, INTO
 	// THE BODY FRAME ERROR REQUIRED BY THE CONTROLLER
 	// > Define a local array to fill in with the body frame error
@@ -662,14 +664,12 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// > Call the function to perform the conversion
 	convert_stateInertial_to_bodyFrameError(m_current_stateInertialEstimate,m_setpoint_for_controller,current_bodyFrameError);
 
-	
 
 	// CARRY OUT THE CONTROLLER COMPUTATIONS
 	// Call the function that performs the control computations for this mode
 	calculateControlOutput_viaLQRforRates(current_bodyFrameError,request,response);
 
 
-
 	// // PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
 	// if (shouldPublishCurrent_xyz_yaw)
 	// {
@@ -1825,7 +1825,7 @@ int main(int argc, char* argv[]) {
 	// Create the service call as a local variable
 	LoadYamlFromFilename loadYamlFromFilenameCall;
 	// Specify the Yaml filename as a string
-	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "PickerController";
 	// Set for whom this applies to
 	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
 	// Wait until the serivce exists
-- 
GitLab


From 27872271e8901c7c1495b46f05976c1f90508566 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 16:29:47 +0100
Subject: [PATCH 43/87] Removed horizontal lines from Picker GUI to make it fit
 the screen better

---
 .../forms/pickercontrollertab.ui              | 2231 ++++++++---------
 1 file changed, 1042 insertions(+), 1189 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
index 232408bd..7175ab3c 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
@@ -80,44 +80,59 @@
        <property name="bottomMargin">
         <number>6</number>
        </property>
-       <item row="19" column="3">
-        <widget class="Line" name="line_24">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
+       <item row="13" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_11">
+         <item>
+          <widget class="QCheckBox" name="checkbox_standby">
+           <property name="enabled">
+            <bool>true</bool>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>30</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+           <property name="checkable">
+            <bool>true</bool>
+           </property>
+           <property name="checked">
+            <bool>false</bool>
+           </property>
+          </widget>
+         </item>
+        </layout>
        </item>
-       <item row="16" column="6">
-        <widget class="QLineEdit" name="lineEdit_increment_y">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-        </widget>
+       <item row="10" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_24">
+         <item>
+          <widget class="QCheckBox" name="checkbox_squat">
+           <property name="maximumSize">
+            <size>
+             <width>30</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
        </item>
-       <item row="8" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_22">
+       <item row="5" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_14">
          <item>
-          <widget class="QCheckBox" name="checkbox_goto_end">
+          <widget class="QCheckBox" name="checkbox_goto_start">
            <property name="maximumSize">
             <size>
              <width>30</width>
@@ -134,13 +149,47 @@
          </item>
         </layout>
        </item>
-       <item row="8" column="4">
-        <layout class="QHBoxLayout" name="horizontalLayout_13">
+       <item row="11" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_29">
+         <item>
+          <widget class="QCheckBox" name="checkbox_jump">
+           <property name="maximumSize">
+            <size>
+             <width>30</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="14" column="6">
+        <widget class="Line" name="line_19">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="14" column="3">
+        <widget class="Line" name="line_17">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="13" column="9">
+        <layout class="QHBoxLayout" name="horizontalLayout_41">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_end_x">
+          <widget class="QLineEdit" name="lineEdit_standby_mass">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -167,7 +216,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_end_inc_minus_x">
+          <widget class="QPushButton" name="button_stanby_inc_minus_mass">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -180,7 +229,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_end_inc_plus_x">
+          <widget class="QPushButton" name="button_stanby_inc_plus_mass">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -194,13 +243,20 @@
          </item>
         </layout>
        </item>
-       <item row="8" column="8">
-        <layout class="QHBoxLayout" name="horizontalLayout_35">
+       <item row="14" column="8">
+        <widget class="Line" name="line_21">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="7" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_28">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_end_yaw">
+          <widget class="QLineEdit" name="lineEdit_lift_up_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -227,7 +283,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_end_inc_minus_yaw">
+          <widget class="QPushButton" name="button_lift_up_inc_minus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -240,7 +296,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_end_inc_plus_yaw">
+          <widget class="QPushButton" name="button_lift_up_inc_plus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -254,8 +310,8 @@
          </item>
         </layout>
        </item>
-       <item row="16" column="7">
-        <widget class="QLineEdit" name="lineEdit_increment_z">
+       <item row="15" column="4">
+        <widget class="QLineEdit" name="lineEdit_increment_x">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -281,67 +337,77 @@
          </property>
         </widget>
        </item>
-       <item row="7" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_4">
+       <item row="8" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_13">
+         <property name="spacing">
+          <number>0</number>
+         </property>
          <item>
-          <widget class="QPushButton" name="button_lift_up">
+          <widget class="QLineEdit" name="lineEdit_goto_end_x">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
            <property name="text">
-            <string>Lift Up</string>
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_lift_up_active">
-           <property name="minimumSize">
+          <widget class="QPushButton" name="button_goto_end_inc_minus_x">
+           <property name="maximumSize">
             <size>
-             <width>20</width>
-             <height>0</height>
+             <width>40</width>
+             <height>16777215</height>
             </size>
            </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_end_inc_plus_x">
            <property name="maximumSize">
             <size>
-             <width>20</width>
+             <width>40</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
+           <property name="text">
+            <string>+</string>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="12" column="6">
-        <widget class="Line" name="line_4">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="17" column="8">
-        <widget class="Line" name="line_13">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="9" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_6">
+       <item row="8" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_5">
          <item>
-          <widget class="QPushButton" name="button_put_down">
+          <widget class="QPushButton" name="button_goto_end">
            <property name="text">
-            <string>Put Down</string>
+            <string>Goto End</string>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_put_down_active">
+          <widget class="QFrame" name="frame_goto_end_active">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -367,13 +433,6 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="0">
-        <widget class="QLabel" name="label_function_column">
-         <property name="text">
-          <string>Function</string>
-         </property>
-        </widget>
-       </item>
        <item row="2" column="3">
         <widget class="QLabel" name="label_smooth_column">
          <property name="text">
@@ -384,85 +443,40 @@
          </property>
         </widget>
        </item>
-       <item row="6" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_3">
-         <item>
-          <widget class="QPushButton" name="button_attach">
-           <property name="text">
-            <string>Attach</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QFrame" name="frame_attach_active">
-           <property name="minimumSize">
-            <size>
-             <width>20</width>
-             <height>0</height>
-            </size>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>20</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
-           </property>
-          </widget>
-         </item>
-        </layout>
-       </item>
-       <item row="10" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_7">
-         <item>
-          <widget class="QPushButton" name="button_squat">
-           <property name="text">
-            <string>Squaut</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QFrame" name="frame_squat_active">
-           <property name="minimumSize">
-            <size>
-             <width>20</width>
-             <height>0</height>
-            </size>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>20</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
-           </property>
-          </widget>
-         </item>
-        </layout>
+       <item row="15" column="6">
+        <widget class="QLineEdit" name="lineEdit_increment_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
        </item>
-       <item row="5" column="8">
-        <layout class="QHBoxLayout" name="horizontalLayout_34">
+       <item row="7" column="9">
+        <layout class="QHBoxLayout" name="horizontalLayout_44">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_start_yaw">
+          <widget class="QLineEdit" name="lineEdit_lift_up_mass">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -489,7 +503,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_minus_yaw">
+          <widget class="QPushButton" name="button_lift_up_inc_minus_mass">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -502,7 +516,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_plus_yaw">
+          <widget class="QPushButton" name="button_lift_up_inc_plus_mass">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -516,82 +530,15 @@
          </item>
         </layout>
        </item>
-       <item row="18" column="0">
-        <widget class="QLabel" name="label_current">
-         <property name="text">
-          <string>Current:</string>
-         </property>
-        </widget>
-       </item>
-       <item row="18" column="8">
-        <widget class="QLineEdit" name="lineEdit_current_yaw">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
-         </property>
-        </widget>
-       </item>
-       <item row="12" column="0">
-        <widget class="Line" name="line">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="2" column="7">
-        <widget class="QLabel" name="label_z_column">
-         <property name="text">
-          <string>z[m]</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="2" column="4">
-        <widget class="QLabel" name="label_x_column">
-         <property name="text">
-          <string>x[m]</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="12" column="9">
-        <widget class="Line" name="line_7">
+       <item row="16" column="4">
+        <widget class="Line" name="line_10">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="18" column="4">
-        <widget class="QLineEdit" name="lineEdit_current_x">
-         <property name="enabled">
-          <bool>true</bool>
-         </property>
+       <item row="17" column="6">
+        <widget class="QLineEdit" name="lineEdit_current_y">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -620,13 +567,13 @@
          </property>
         </widget>
        </item>
-       <item row="8" column="6">
-        <layout class="QHBoxLayout" name="horizontalLayout_21">
+       <item row="19" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_20">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_end_y">
+          <widget class="QLineEdit" name="lineEdit_measured_x">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -650,57 +597,13 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_goto_end_inc_minus_y">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_goto_end_inc_plus_y">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="text">
-            <string>+</string>
-           </property>
-          </widget>
-         </item>
-        </layout>
-       </item>
-       <item row="2" column="6">
-        <widget class="QLabel" name="label_y_column">
-         <property name="text">
-          <string>y[m]</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="8" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_5">
-         <item>
-          <widget class="QPushButton" name="button_goto_end">
-           <property name="text">
-            <string>Goto End</string>
+           <property name="readOnly">
+            <bool>true</bool>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_goto_end_active">
+          <widget class="QFrame" name="frame_x_unavailable">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -714,7 +617,7 @@
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
+            <string notr="true">background-color:red;</string>
            </property>
            <property name="frameShape">
             <enum>QFrame::StyledPanel</enum>
@@ -724,15 +627,28 @@
            </property>
           </widget>
          </item>
+         <item>
+          <spacer name="horizontalSpacer_2">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
         </layout>
        </item>
-       <item row="14" column="6">
-        <layout class="QHBoxLayout" name="horizontalLayout_17">
+       <item row="19" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_36">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_standby_y">
+          <widget class="QLineEdit" name="lineEdit_measured_yaw">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -756,43 +672,68 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_minus_y">
-           <property name="maximumSize">
+          <widget class="QFrame" name="frame_yaw_unavailable">
+           <property name="minimumSize">
             <size>
-             <width>40</width>
-             <height>16777215</height>
+             <width>20</width>
+             <height>0</height>
             </size>
            </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_stanby_inc_plus_y">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>20</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="text">
-            <string>+</string>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
           </widget>
          </item>
+         <item>
+          <spacer name="horizontalSpacer_3">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
         </layout>
        </item>
-       <item row="5" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_26">
+       <item row="2" column="6">
+        <widget class="QLabel" name="label_y_column">
+         <property name="text">
+          <string>y[m]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="9" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_30">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_start_z">
+          <widget class="QLineEdit" name="lineEdit_put_down_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -819,7 +760,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_minus_z">
+          <widget class="QPushButton" name="button_put_down_inc_minus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -832,7 +773,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_plus_z">
+          <widget class="QPushButton" name="button_put_down_inc_plus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -846,74 +787,27 @@
          </item>
         </layout>
        </item>
-       <item row="16" column="8">
-        <widget class="QLineEdit" name="lineEdit_increment_yaw">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="21" column="8">
-        <widget class="Line" name="line_35">
+       <item row="14" column="0">
+        <widget class="Line" name="line_16">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="16" column="9">
-        <widget class="QLineEdit" name="lineEdit_increment_mass">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       <item row="14" column="4">
+        <widget class="Line" name="line_18">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="11" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_32">
+       <item row="19" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_38">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_jump_z">
+          <widget class="QLineEdit" name="lineEdit_measured_y">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -937,121 +831,13 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_jump_inc_minus_z">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_jump_inc_plus_z">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="text">
-            <string>+</string>
-           </property>
-          </widget>
-         </item>
-        </layout>
-       </item>
-       <item row="18" column="7">
-        <widget class="QLineEdit" name="lineEdit_current_z">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
-         </property>
-        </widget>
-       </item>
-       <item row="17" column="0">
-        <widget class="Line" name="line_8">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="2" column="9">
-        <widget class="QLabel" name="label_mass_column">
-         <property name="text">
-          <string>mass[g]</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="12" column="8">
-        <widget class="Line" name="line_6">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="6" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_16">
-         <item>
-          <widget class="QCheckBox" name="checkbox_attach">
-           <property name="maximumSize">
-            <size>
-             <width>30</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-           </property>
-           <property name="text">
-            <string/>
-           </property>
-          </widget>
-         </item>
-        </layout>
-       </item>
-       <item row="5" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_2">
-         <item>
-          <widget class="QPushButton" name="button_goto_start">
-           <property name="text">
-            <string>Goto Start</string>
+           <property name="readOnly">
+            <bool>true</bool>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_goto_start_active">
+          <widget class="QFrame" name="frame_y_unavailable">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -1065,7 +851,7 @@
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
+            <string notr="true">background-color:red;</string>
            </property>
            <property name="frameShape">
             <enum>QFrame::StyledPanel</enum>
@@ -1075,15 +861,28 @@
            </property>
           </widget>
          </item>
+         <item>
+          <spacer name="horizontalSpacer_5">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
         </layout>
        </item>
-       <item row="7" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_28">
+       <item row="19" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_37">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_lift_up_z">
+          <widget class="QLineEdit" name="lineEdit_measured_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1107,77 +906,75 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_lift_up_inc_minus_z">
-           <property name="maximumSize">
+          <widget class="QFrame" name="frame_z_unavailable">
+           <property name="minimumSize">
             <size>
-             <width>40</width>
-             <height>16777215</height>
+             <width>20</width>
+             <height>0</height>
             </size>
            </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_lift_up_inc_plus_z">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>20</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="text">
-            <string>+</string>
+           <property name="styleSheet">
+            <string notr="true">background-color:red;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
           </widget>
          </item>
+         <item>
+          <spacer name="horizontalSpacer_4">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>40</width>
+             <height>20</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
         </layout>
        </item>
-       <item row="17" column="9">
-        <widget class="Line" name="line_14">
+       <item row="16" column="8">
+        <widget class="Line" name="line_13">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="16" column="4">
-        <widget class="QLineEdit" name="lineEdit_increment_x">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
+       <item row="2" column="4">
+        <widget class="QLabel" name="label_x_column">
          <property name="text">
-          <string>xx.xx</string>
+          <string>x[m]</string>
          </property>
          <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+          <set>Qt::AlignCenter</set>
          </property>
         </widget>
        </item>
-       <item row="7" column="9">
-        <layout class="QHBoxLayout" name="horizontalLayout_44">
+       <item row="10" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_31">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_lift_up_mass">
+          <widget class="QLineEdit" name="lineEdit_squat_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1204,7 +1001,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_lift_up_inc_minus_mass">
+          <widget class="QPushButton" name="button_squat_inc_minus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1217,7 +1014,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_lift_up_inc_plus_mass">
+          <widget class="QPushButton" name="button_squat_inc_plus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1231,110 +1028,13 @@
          </item>
         </layout>
        </item>
-       <item row="18" column="6">
-        <widget class="QLineEdit" name="lineEdit_current_y">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
-         </property>
-        </widget>
-       </item>
-       <item row="12" column="3">
-        <widget class="Line" name="line_2">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="17" column="4">
-        <widget class="Line" name="line_10">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="2" column="8">
-        <widget class="QLabel" name="label_yaw_column">
-         <property name="text">
-          <string>yaw[deg]</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignCenter</set>
-         </property>
-        </widget>
-       </item>
-       <item row="17" column="6">
-        <widget class="Line" name="line_11">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="11" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout_8">
-         <item>
-          <widget class="QPushButton" name="button_jump">
-           <property name="text">
-            <string>Jump</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QFrame" name="frame_jump_active">
-           <property name="minimumSize">
-            <size>
-             <width>20</width>
-             <height>0</height>
-            </size>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>20</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">background-color:green;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
-           </property>
-          </widget>
-         </item>
-        </layout>
-       </item>
-       <item row="10" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_31">
+       <item row="5" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_34">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_squat_z">
+          <widget class="QLineEdit" name="lineEdit_goto_start_yaw">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1361,7 +1061,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_squat_inc_minus_z">
+          <widget class="QPushButton" name="button_goto_start_inc_minus_yaw">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1374,7 +1074,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_squat_inc_plus_z">
+          <widget class="QPushButton" name="button_goto_start_inc_plus_yaw">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1388,84 +1088,44 @@
          </item>
         </layout>
        </item>
-       <item row="17" column="7">
-        <widget class="Line" name="line_12">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="17" column="0">
+        <widget class="QLabel" name="label_current">
+         <property name="text">
+          <string>Current:</string>
          </property>
         </widget>
        </item>
-       <item row="6" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_27">
-         <property name="spacing">
-          <number>0</number>
-         </property>
-         <item>
-          <widget class="QLineEdit" name="lineEdit_attach_z">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>180</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="font">
-            <font>
-             <family>Courier</family>
-            </font>
-           </property>
-           <property name="text">
-            <string>xx.xx</string>
-           </property>
-           <property name="alignment">
-            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-           </property>
-          </widget>
-         </item>
+       <item row="8" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_22">
          <item>
-          <widget class="QPushButton" name="button_attach_inc_minus_z">
+          <widget class="QCheckBox" name="checkbox_goto_end">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_attach_inc_plus_z">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
-            <string>+</string>
+            <string/>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="14" column="0">
-        <layout class="QHBoxLayout" name="horizontalLayout">
+       <item row="6" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_3">
          <item>
-          <widget class="QPushButton" name="button_standby">
+          <widget class="QPushButton" name="button_attach">
            <property name="text">
-            <string>Standby</string>
+            <string>Attach</string>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_standby_active">
+          <widget class="QFrame" name="frame_attach_active">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -1491,13 +1151,13 @@
          </item>
         </layout>
        </item>
-       <item row="5" column="4">
-        <layout class="QHBoxLayout" name="horizontalLayout_10">
+       <item row="5" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_26">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_start_x">
+          <widget class="QLineEdit" name="lineEdit_goto_start_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1524,7 +1184,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_minus_x">
+          <widget class="QPushButton" name="button_goto_start_inc_minus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1537,7 +1197,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_plus_x">
+          <widget class="QPushButton" name="button_goto_start_inc_plus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1551,27 +1211,34 @@
          </item>
         </layout>
        </item>
-       <item row="12" column="7">
-        <widget class="Line" name="line_5">
+       <item row="14" column="9">
+        <widget class="Line" name="line_22">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="16" column="0">
-        <widget class="QLabel" name="label_increment">
+       <item row="18" column="0">
+        <widget class="QLabel" name="label_error">
          <property name="text">
-          <string>Increment:</string>
+          <string>Error:</string>
          </property>
         </widget>
        </item>
-       <item row="5" column="6">
-        <layout class="QHBoxLayout" name="horizontalLayout_18">
+       <item row="19" column="0">
+        <widget class="QLabel" name="label_measured">
+         <property name="text">
+          <string>Measured:</string>
+         </property>
+        </widget>
+       </item>
+       <item row="11" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_32">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_goto_start_y">
+          <widget class="QLineEdit" name="lineEdit_jump_z">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1598,7 +1265,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_minus_y">
+          <widget class="QPushButton" name="button_jump_inc_minus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1611,7 +1278,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_goto_start_inc_plus_y">
+          <widget class="QPushButton" name="button_jump_inc_plus_z">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1625,13 +1292,13 @@
          </item>
         </layout>
        </item>
-       <item row="9" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_30">
+       <item row="8" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_21">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_put_down_z">
+          <widget class="QLineEdit" name="lineEdit_goto_end_y">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1658,7 +1325,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_put_down_inc_minus_z">
+          <widget class="QPushButton" name="button_goto_end_inc_minus_y">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1671,7 +1338,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_put_down_inc_plus_z">
+          <widget class="QPushButton" name="button_goto_end_inc_plus_y">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1685,94 +1352,53 @@
          </item>
         </layout>
        </item>
-       <item row="12" column="4">
-        <widget class="Line" name="line_3">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="17" column="3">
-        <widget class="Line" name="line_9">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="15" column="0">
-        <widget class="Line" name="line_16">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="14" column="8">
-        <layout class="QHBoxLayout" name="horizontalLayout_33">
-         <property name="spacing">
-          <number>0</number>
-         </property>
+       <item row="9" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_23">
          <item>
-          <widget class="QLineEdit" name="lineEdit_standby_yaw">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
+          <widget class="QCheckBox" name="checkbox_put_down">
            <property name="maximumSize">
             <size>
-             <width>180</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="font">
-            <font>
-             <family>Courier</family>
-            </font>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
-            <string>xx.xx</string>
-           </property>
-           <property name="alignment">
-            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+            <string/>
            </property>
           </widget>
          </item>
+        </layout>
+       </item>
+       <item row="7" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_19">
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_minus_yaw">
+          <widget class="QCheckBox" name="checkbox_lift_up">
            <property name="maximumSize">
             <size>
-             <width>40</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="text">
-            <string>-</string>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <widget class="QPushButton" name="button_stanby_inc_plus_yaw">
-           <property name="maximumSize">
-            <size>
-             <width>40</width>
-             <height>16777215</height>
-            </size>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
            <property name="text">
-            <string>+</string>
+            <string/>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="14" column="4">
-        <layout class="QHBoxLayout" name="horizontalLayout_9">
+       <item row="8" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_35">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_standby_x">
+          <widget class="QLineEdit" name="lineEdit_goto_end_yaw">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -1799,7 +1425,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_minus_x">
+          <widget class="QPushButton" name="button_goto_end_inc_minus_yaw">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1812,7 +1438,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_plus_x">
+          <widget class="QPushButton" name="button_goto_end_inc_plus_yaw">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -1826,143 +1452,375 @@
          </item>
         </layout>
        </item>
-       <item row="5" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_14">
+       <item row="15" column="7">
+        <widget class="QLineEdit" name="lineEdit_increment_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="17" column="8">
+        <widget class="QLineEdit" name="lineEdit_current_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="7">
+        <widget class="QLabel" name="label_z_column">
+         <property name="text">
+          <string>z[m]</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="7" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_4">
          <item>
-          <widget class="QCheckBox" name="checkbox_goto_start">
-           <property name="maximumSize">
-            <size>
-             <width>30</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-           </property>
+          <widget class="QPushButton" name="button_lift_up">
            <property name="text">
-            <string/>
+            <string>Lift Up</string>
            </property>
           </widget>
          </item>
-        </layout>
-       </item>
-       <item row="11" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_29">
          <item>
-          <widget class="QCheckBox" name="checkbox_jump">
+          <widget class="QFrame" name="frame_lift_up_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
            <property name="maximumSize">
             <size>
-             <width>30</width>
+             <width>20</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+            <string notr="true">background-color:green;</string>
            </property>
-           <property name="text">
-            <string/>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="15" column="3">
-        <widget class="Line" name="line_17">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="2" column="0">
+        <widget class="QLabel" name="label_function_column">
+         <property name="text">
+          <string>Function</string>
          </property>
         </widget>
        </item>
-       <item row="9" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_23">
+       <item row="10" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_7">
          <item>
-          <widget class="QCheckBox" name="checkbox_put_down">
-           <property name="maximumSize">
-            <size>
-             <width>30</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-           </property>
+          <widget class="QPushButton" name="button_squat">
            <property name="text">
-            <string/>
+            <string>Squaut</string>
            </property>
           </widget>
          </item>
-        </layout>
-       </item>
-       <item row="7" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_19">
          <item>
-          <widget class="QCheckBox" name="checkbox_lift_up">
+          <widget class="QFrame" name="frame_squat_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
            <property name="maximumSize">
             <size>
-             <width>30</width>
+             <width>20</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+            <string notr="true">background-color:green;</string>
            </property>
-           <property name="text">
-            <string/>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="14" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_11">
+       <item row="6" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_27">
+         <property name="spacing">
+          <number>0</number>
+         </property>
          <item>
-          <widget class="QCheckBox" name="checkbox_standby">
-           <property name="enabled">
-            <bool>true</bool>
+          <widget class="QLineEdit" name="lineEdit_attach_z">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
            </property>
            <property name="maximumSize">
             <size>
-             <width>30</width>
+             <width>180</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
            </property>
            <property name="text">
-            <string/>
+            <string>xx.xx</string>
            </property>
-           <property name="checkable">
-            <bool>true</bool>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
-           <property name="checked">
-            <bool>false</bool>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_attach_inc_minus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_attach_inc_plus_z">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="10" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_24">
+       <item row="17" column="9">
+        <widget class="QLineEdit" name="lineEdit_current_mass">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="9" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_6">
          <item>
-          <widget class="QCheckBox" name="checkbox_squat">
+          <widget class="QPushButton" name="button_put_down">
+           <property name="text">
+            <string>Put Down</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_put_down_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
            <property name="maximumSize">
             <size>
-             <width>30</width>
+             <width>20</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="17" column="4">
+        <widget class="QLineEdit" name="lineEdit_current_x">
+         <property name="enabled">
+          <bool>true</bool>
+         </property>
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="15" column="9">
+        <widget class="QLineEdit" name="lineEdit_increment_mass">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="11" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_8">
+         <item>
+          <widget class="QPushButton" name="button_jump">
            <property name="text">
-            <string/>
+            <string>Jump</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QFrame" name="frame_jump_active">
+           <property name="minimumSize">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>20</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true">background-color:green;</string>
+           </property>
+           <property name="frameShape">
+            <enum>QFrame::StyledPanel</enum>
+           </property>
+           <property name="frameShadow">
+            <enum>QFrame::Raised</enum>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="14" column="7">
+       <item row="13" column="7">
         <layout class="QHBoxLayout" name="horizontalLayout_25">
          <property name="spacing">
           <number>0</number>
@@ -2022,20 +1880,20 @@
          </item>
         </layout>
        </item>
-       <item row="15" column="4">
-        <widget class="Line" name="line_18">
+       <item row="14" column="7">
+        <widget class="Line" name="line_20">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="14" column="9">
-        <layout class="QHBoxLayout" name="horizontalLayout_41">
+       <item row="5" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_10">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_standby_mass">
+          <widget class="QLineEdit" name="lineEdit_goto_start_x">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -2062,7 +1920,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_minus_mass">
+          <widget class="QPushButton" name="button_goto_start_inc_minus_x">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -2075,7 +1933,7 @@
           </widget>
          </item>
          <item>
-          <widget class="QPushButton" name="button_stanby_inc_plus_mass">
+          <widget class="QPushButton" name="button_goto_start_inc_plus_x">
            <property name="maximumSize">
             <size>
              <width>40</width>
@@ -2089,55 +1947,20 @@
          </item>
         </layout>
        </item>
-       <item row="15" column="6">
-        <widget class="Line" name="line_19">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="15" column="7">
-        <widget class="Line" name="line_20">
+       <item row="16" column="3">
+        <widget class="Line" name="line_9">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="15" column="8">
-        <widget class="Line" name="line_21">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="15" column="9">
-        <widget class="Line" name="line_22">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="20" column="0">
-        <widget class="QLabel" name="label_error">
-         <property name="text">
-          <string>Error:</string>
-         </property>
-        </widget>
-       </item>
-       <item row="22" column="0">
-        <widget class="QLabel" name="label_measured">
-         <property name="text">
-          <string>Measured:</string>
-         </property>
-        </widget>
-       </item>
-       <item row="18" column="9">
-        <widget class="QLineEdit" name="lineEdit_current_mass">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
+       <item row="17" column="7">
+        <widget class="QLineEdit" name="lineEdit_current_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
          </property>
          <property name="maximumSize">
           <size>
@@ -2161,174 +1984,228 @@
          </property>
         </widget>
        </item>
-       <item row="19" column="0">
-        <widget class="Line" name="line_23">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="21" column="9">
-        <widget class="Line" name="line_36">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="19" column="4">
-        <widget class="Line" name="line_25">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="19" column="6">
-        <widget class="Line" name="line_26">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="19" column="7">
-        <widget class="Line" name="line_27">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="19" column="9">
-        <widget class="Line" name="line_29">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="19" column="8">
-        <widget class="Line" name="line_28">
+       <item row="16" column="9">
+        <widget class="Line" name="line_14">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="21" column="3">
-        <widget class="Line" name="line_31">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="2" column="9">
+        <widget class="QLabel" name="label_mass_column">
+         <property name="text">
+          <string>mass[g]</string>
          </property>
-        </widget>
-       </item>
-       <item row="21" column="0">
-        <widget class="Line" name="line_30">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
          </property>
         </widget>
        </item>
-       <item row="21" column="4">
-        <widget class="Line" name="line_32">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="13" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_17">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_standby_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
        </item>
-       <item row="21" column="6">
-        <widget class="Line" name="line_33">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="5" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_18">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_goto_start_y">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_minus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_goto_start_inc_plus_y">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
        </item>
-       <item row="21" column="7">
-        <widget class="Line" name="line_34">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
+       <item row="13" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_33">
+         <property name="spacing">
+          <number>0</number>
          </property>
-        </widget>
-       </item>
-       <item row="18" column="3">
-        <layout class="QHBoxLayout" name="horizontalLayout_15">
          <item>
-          <widget class="QCheckBox" name="checkbox_current">
-           <property name="enabled">
-            <bool>false</bool>
+          <widget class="QLineEdit" name="lineEdit_standby_yaw">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
            </property>
            <property name="maximumSize">
             <size>
-             <width>30</width>
+             <width>180</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="styleSheet">
-            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
            </property>
            <property name="text">
-            <string/>
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_minus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>-</string>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QPushButton" name="button_stanby_inc_plus_yaw">
+           <property name="maximumSize">
+            <size>
+             <width>40</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="text">
+            <string>+</string>
            </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="20" column="4">
-        <widget class="QLineEdit" name="lineEdit_error_x">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
-         <property name="text">
-          <string>xx.xx</string>
-         </property>
-         <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-         </property>
-         <property name="readOnly">
-          <bool>true</bool>
+       <item row="16" column="6">
+        <widget class="Line" name="line_11">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="20" column="6">
-        <widget class="QLineEdit" name="lineEdit_error_y">
-         <property name="sizePolicy">
-          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-           <horstretch>0</horstretch>
-           <verstretch>0</verstretch>
-          </sizepolicy>
-         </property>
-         <property name="maximumSize">
-          <size>
-           <width>180</width>
-           <height>16777215</height>
-          </size>
-         </property>
-         <property name="font">
-          <font>
-           <family>Courier</family>
-          </font>
-         </property>
+       <item row="2" column="8">
+        <widget class="QLabel" name="label_yaw_column">
          <property name="text">
-          <string>xx.xx</string>
+          <string>yaw[deg]</string>
          </property>
          <property name="alignment">
-          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+          <set>Qt::AlignCenter</set>
          </property>
-         <property name="readOnly">
-          <bool>true</bool>
+        </widget>
+       </item>
+       <item row="16" column="7">
+        <widget class="Line" name="line_12">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="20" column="7">
+       <item row="18" column="7">
         <widget class="QLineEdit" name="lineEdit_error_z">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
@@ -2358,7 +2235,7 @@
          </property>
         </widget>
        </item>
-       <item row="20" column="8">
+       <item row="18" column="8">
         <widget class="QLineEdit" name="lineEdit_error_yaw">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
@@ -2388,88 +2265,67 @@
          </property>
         </widget>
        </item>
-       <item row="22" column="4">
-        <layout class="QHBoxLayout" name="horizontalLayout_20">
-         <property name="spacing">
-          <number>0</number>
-         </property>
-         <item>
-          <widget class="QLineEdit" name="lineEdit_measured_x">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>180</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="font">
-            <font>
-             <family>Courier</family>
-            </font>
-           </property>
-           <property name="text">
-            <string>xx.xx</string>
-           </property>
-           <property name="alignment">
-            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-           </property>
-           <property name="readOnly">
-            <bool>true</bool>
-           </property>
-          </widget>
-         </item>
+       <item row="6" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_16">
          <item>
-          <widget class="QFrame" name="frame_x_unavailable">
-           <property name="minimumSize">
-            <size>
-             <width>20</width>
-             <height>0</height>
-            </size>
-           </property>
+          <widget class="QCheckBox" name="checkbox_attach">
            <property name="maximumSize">
             <size>
-             <width>20</width>
+             <width>30</width>
              <height>16777215</height>
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">background-color:red;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
-           </property>
-          </widget>
-         </item>
-         <item>
-          <spacer name="horizontalSpacer_2">
-           <property name="orientation">
-            <enum>Qt::Horizontal</enum>
-           </property>
-           <property name="sizeHint" stdset="0">
-            <size>
-             <width>40</width>
-             <height>20</height>
-            </size>
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
            </property>
-          </spacer>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
          </item>
         </layout>
        </item>
-       <item row="22" column="8">
-        <layout class="QHBoxLayout" name="horizontalLayout_36">
+       <item row="15" column="8">
+        <widget class="QLineEdit" name="lineEdit_increment_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item row="16" column="0">
+        <widget class="Line" name="line_8">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="13" column="4">
+        <layout class="QHBoxLayout" name="horizontalLayout_9">
          <property name="spacing">
           <number>0</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_measured_yaw">
+          <widget class="QLineEdit" name="lineEdit_standby_x">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -2493,88 +2349,54 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
-           <property name="readOnly">
-            <bool>true</bool>
-           </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_yaw_unavailable">
-           <property name="minimumSize">
-            <size>
-             <width>20</width>
-             <height>0</height>
-            </size>
-           </property>
+          <widget class="QPushButton" name="button_stanby_inc_minus_x">
            <property name="maximumSize">
             <size>
-             <width>20</width>
+             <width>40</width>
              <height>16777215</height>
             </size>
            </property>
-           <property name="styleSheet">
-            <string notr="true">background-color:red;</string>
-           </property>
-           <property name="frameShape">
-            <enum>QFrame::StyledPanel</enum>
-           </property>
-           <property name="frameShadow">
-            <enum>QFrame::Raised</enum>
+           <property name="text">
+            <string>-</string>
            </property>
           </widget>
          </item>
          <item>
-          <spacer name="horizontalSpacer_3">
-           <property name="orientation">
-            <enum>Qt::Horizontal</enum>
-           </property>
-           <property name="sizeHint" stdset="0">
+          <widget class="QPushButton" name="button_stanby_inc_plus_x">
+           <property name="maximumSize">
             <size>
              <width>40</width>
-             <height>20</height>
+             <height>16777215</height>
             </size>
            </property>
-          </spacer>
+           <property name="text">
+            <string>+</string>
+           </property>
+          </widget>
          </item>
         </layout>
        </item>
-       <item row="22" column="7">
-        <layout class="QHBoxLayout" name="horizontalLayout_37">
-         <property name="spacing">
-          <number>0</number>
+       <item row="15" column="0">
+        <widget class="QLabel" name="label_increment">
+         <property name="text">
+          <string>Increment:</string>
          </property>
+        </widget>
+       </item>
+       <item row="13" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout">
          <item>
-          <widget class="QLineEdit" name="lineEdit_measured_z">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>180</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="font">
-            <font>
-             <family>Courier</family>
-            </font>
-           </property>
+          <widget class="QPushButton" name="button_standby">
            <property name="text">
-            <string>xx.xx</string>
-           </property>
-           <property name="alignment">
-            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-           </property>
-           <property name="readOnly">
-            <bool>true</bool>
+            <string>Standby</string>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_z_unavailable">
+          <widget class="QFrame" name="frame_standby_active">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -2588,7 +2410,7 @@
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">background-color:red;</string>
+            <string notr="true">background-color:green;</string>
            </property>
            <property name="frameShape">
             <enum>QFrame::StyledPanel</enum>
@@ -2598,58 +2420,19 @@
            </property>
           </widget>
          </item>
-         <item>
-          <spacer name="horizontalSpacer_4">
-           <property name="orientation">
-            <enum>Qt::Horizontal</enum>
-           </property>
-           <property name="sizeHint" stdset="0">
-            <size>
-             <width>40</width>
-             <height>20</height>
-            </size>
-           </property>
-          </spacer>
-         </item>
         </layout>
        </item>
-       <item row="22" column="6">
-        <layout class="QHBoxLayout" name="horizontalLayout_38">
-         <property name="spacing">
-          <number>0</number>
-         </property>
+       <item row="5" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_2">
          <item>
-          <widget class="QLineEdit" name="lineEdit_measured_y">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <property name="maximumSize">
-            <size>
-             <width>180</width>
-             <height>16777215</height>
-            </size>
-           </property>
-           <property name="font">
-            <font>
-             <family>Courier</family>
-            </font>
-           </property>
+          <widget class="QPushButton" name="button_goto_start">
            <property name="text">
-            <string>xx.xx</string>
-           </property>
-           <property name="alignment">
-            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-           </property>
-           <property name="readOnly">
-            <bool>true</bool>
+            <string>Goto Start</string>
            </property>
           </widget>
          </item>
          <item>
-          <widget class="QFrame" name="frame_y_unavailable">
+          <widget class="QFrame" name="frame_goto_start_active">
            <property name="minimumSize">
             <size>
              <width>20</width>
@@ -2663,7 +2446,7 @@
             </size>
            </property>
            <property name="styleSheet">
-            <string notr="true">background-color:red;</string>
+            <string notr="true">background-color:green;</string>
            </property>
            <property name="frameShape">
             <enum>QFrame::StyledPanel</enum>
@@ -2673,21 +2456,91 @@
            </property>
           </widget>
          </item>
+        </layout>
+       </item>
+       <item row="17" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_15">
          <item>
-          <spacer name="horizontalSpacer_5">
-           <property name="orientation">
-            <enum>Qt::Horizontal</enum>
+          <widget class="QCheckBox" name="checkbox_current">
+           <property name="enabled">
+            <bool>false</bool>
            </property>
-           <property name="sizeHint" stdset="0">
+           <property name="maximumSize">
             <size>
-             <width>40</width>
-             <height>20</height>
+             <width>30</width>
+             <height>16777215</height>
             </size>
            </property>
-          </spacer>
+           <property name="styleSheet">
+            <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
+           </property>
+           <property name="text">
+            <string/>
+           </property>
+          </widget>
          </item>
         </layout>
        </item>
+       <item row="18" column="4">
+        <widget class="QLineEdit" name="lineEdit_error_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+       <item row="18" column="6">
+        <widget class="QLineEdit" name="lineEdit_error_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
       </layout>
      </item>
      <item row="2" column="0">
-- 
GitLab


From 929383ba5111e28888fb9b0788b24fcc2a07b1ef Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 4 Feb 2019 17:52:17 +0100
Subject: [PATCH 44/87] Added first draft of the new Tuning GUI. Needs
 connecting in Qt and in ROS

---
 .../GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro  |   8 +-
 .../flyingAgentGUI/forms/controllertabs.ui    |  20 +-
 .../forms/enablecontrollerloadyamlbar.ui      | 154 ++--
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |  12 +
 .../forms/studentcontrollertab.ui             |  81 ++
 .../forms/tuningcontrollertab.ui              | 703 ++++++++++++++++++
 .../flyingAgentGUI/include/controllertabs.h   |   1 +
 .../include/enablecontrollerloadyamlbar.h     |   3 +
 .../flyingAgentGUI/include/mainwindow.h       |   1 +
 .../include/tuningcontrollertab.h             |  22 +
 .../flyingAgentGUI/src/controllertabs.cpp     |   8 +-
 .../src/enablecontrollerloadyamlbar.cpp       |  45 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |   9 +
 .../src/tuningcontrollertab.cpp               |  14 +
 14 files changed, 1018 insertions(+), 63 deletions(-)
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
 create mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
index dba7e186..69b60535 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
@@ -27,7 +27,8 @@ SOURCES += src/main.cpp\
     src/coordinatorrow.cpp \
     src/studentcontrollertab.cpp \
     src/defaultcontrollertab.cpp \
-    src/pickercontrollertab.cpp
+    src/pickercontrollertab.cpp \
+    src/tuningcontrollertab.cpp
 
 HEADERS  += include/mainwindow.h \
     include/topbanner.h \
@@ -40,8 +41,10 @@ HEADERS  += include/mainwindow.h \
     include/studentcontrollertab.h \
     include/defaultcontrollertab.h \
     include/pickercontrollertab.h \
+    include/tuningcontrollertab.h \
     include/Constants_for_Qt_compile.h
 
+
 FORMS    += forms/mainwindow.ui \
     forms/topbanner.ui \
     forms/connectstartstopbar.ui \
@@ -52,7 +55,8 @@ FORMS    += forms/mainwindow.ui \
     forms/coordinatorrow.ui \
     forms/studentcontrollertab.ui \
     forms/defaultcontrollertab.ui \
-    forms/pickercontrollertab.ui
+    forms/pickercontrollertab.ui \
+    forms/tuningcontrollertab.ui
 
 RESOURCES += \
     flyingagentgui.qrc
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index 928aa115..75157907 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -28,7 +28,7 @@
    <item row="0" column="0">
     <widget class="QTabWidget" name="controller_tabs_widget">
      <property name="currentIndex">
-      <number>0</number>
+      <number>3</number>
      </property>
      <property name="movable">
       <bool>true</bool>
@@ -63,13 +63,23 @@
        </item>
       </layout>
      </widget>
+     <widget class="QWidget" name="tuning_tab">
+      <attribute name="title">
+       <string>Tuning</string>
+      </attribute>
+      <layout class="QGridLayout" name="gridLayout_6">
+       <item row="0" column="0">
+        <widget class="TuningControllerTab" name="tuning_controller_tab_widget" native="true"/>
+       </item>
+      </layout>
+     </widget>
      <widget class="QWidget" name="safe_tab">
       <attribute name="title">
        <string>Safe</string>
       </attribute>
       <layout class="QGridLayout" name="gridLayout_3">
        <item row="0" column="0">
-        <widget class="SafeControllerTab" name="widget_2" native="true"/>
+        <widget class="SafeControllerTab" name="safe_controller_tab_widget" native="true"/>
        </item>
       </layout>
      </widget>
@@ -102,6 +112,12 @@
    <header>pickercontrollertab.h</header>
    <container>1</container>
   </customwidget>
+  <customwidget>
+   <class>TuningControllerTab</class>
+   <extends>QWidget</extends>
+   <header>tuningcontrollertab.h</header>
+   <container>1</container>
+  </customwidget>
  </customwidgets>
  <resources/>
  <connections/>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index 4201e18d..b11f354f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -30,8 +30,8 @@
      <property name="spacing">
       <number>12</number>
      </property>
-     <item row="0" column="4">
-      <widget class="QPushButton" name="enable_safe_button">
+     <item row="0" column="2">
+      <widget class="QPushButton" name="enable_student_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -57,12 +57,12 @@
         </font>
        </property>
        <property name="text">
-        <string>Safe</string>
+        <string>Student</string>
        </property>
       </widget>
      </item>
-     <item row="0" column="0">
-      <widget class="QLabel" name="enable_controller_label">
+     <item row="1" column="0">
+      <widget class="QLabel" name="load_yaml_label">
        <property name="sizePolicy">
         <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -88,15 +88,28 @@
         </font>
        </property>
        <property name="text">
-        <string>Enable</string>
+        <string>Load YAML</string>
        </property>
        <property name="alignment">
         <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item row="0" column="1">
-      <widget class="QPushButton" name="enable_default_button">
+     <item row="0" column="6">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="0" column="5">
+      <widget class="QPushButton" name="enable_safe_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -122,46 +135,37 @@
         </font>
        </property>
        <property name="text">
-        <string>Default</string>
+        <string>Safe</string>
        </property>
       </widget>
      </item>
-     <item row="1" column="0">
-      <widget class="QLabel" name="load_yaml_label">
+     <item row="1" column="3">
+      <widget class="QPushButton" name="load_yaml_picker_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="minimumSize">
         <size>
-         <width>0</width>
+         <width>60</width>
          <height>50</height>
         </size>
        </property>
        <property name="maximumSize">
         <size>
-         <width>16777215</width>
+         <width>180</width>
          <height>50</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <weight>75</weight>
-         <bold>true</bold>
-        </font>
-       </property>
        <property name="text">
-        <string>Load YAML</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignCenter</set>
+        <string>Picker</string>
        </property>
       </widget>
      </item>
-     <item row="1" column="4">
-      <widget class="QPushButton" name="load_yaml_safe_button">
+     <item row="1" column="2">
+      <widget class="QPushButton" name="load_yaml_student_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -181,12 +185,12 @@
         </size>
        </property>
        <property name="text">
-        <string>Safe</string>
+        <string>Student</string>
        </property>
       </widget>
      </item>
-     <item row="1" column="1">
-      <widget class="QPushButton" name="load_yaml_default_button">
+     <item row="0" column="1">
+      <widget class="QPushButton" name="enable_default_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -205,13 +209,53 @@
          <height>50</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <weight>50</weight>
+         <bold>false</bold>
+        </font>
+       </property>
        <property name="text">
         <string>Default</string>
        </property>
       </widget>
      </item>
-     <item row="1" column="2">
-      <widget class="QPushButton" name="load_yaml_student_button">
+     <item row="0" column="0">
+      <widget class="QLabel" name="enable_controller_label">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="minimumSize">
+        <size>
+         <width>0</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Enable</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="5">
+      <widget class="QPushButton" name="load_yaml_safe_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -231,12 +275,12 @@
         </size>
        </property>
        <property name="text">
-        <string>Student</string>
+        <string>Safe</string>
        </property>
       </widget>
      </item>
-     <item row="0" column="2">
-      <widget class="QPushButton" name="enable_student_button">
+     <item row="1" column="1">
+      <widget class="QPushButton" name="load_yaml_default_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -255,14 +299,8 @@
          <height>50</height>
         </size>
        </property>
-       <property name="font">
-        <font>
-         <weight>50</weight>
-         <bold>false</bold>
-        </font>
-       </property>
        <property name="text">
-        <string>Student</string>
+        <string>Default</string>
        </property>
       </widget>
      </item>
@@ -297,8 +335,8 @@
        </property>
       </widget>
      </item>
-     <item row="1" column="3">
-      <widget class="QPushButton" name="load_yaml_picker_button">
+     <item row="0" column="4">
+      <widget class="QPushButton" name="enable_tuning_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -318,22 +356,34 @@
         </size>
        </property>
        <property name="text">
-        <string>Picker</string>
+        <string>Tuning</string>
        </property>
       </widget>
      </item>
-     <item row="0" column="5">
-      <spacer name="horizontalSpacer">
-       <property name="orientation">
-        <enum>Qt::Horizontal</enum>
+     <item row="1" column="4">
+      <widget class="QPushButton" name="load_yaml_tuning_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
        </property>
-       <property name="sizeHint" stdset="0">
+       <property name="minimumSize">
         <size>
-         <width>40</width>
-         <height>20</height>
+         <width>60</width>
+         <height>50</height>
         </size>
        </property>
-      </spacer>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Tuning</string>
+       </property>
+      </widget>
      </item>
     </layout>
    </item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index 90eb9f73..2a7f180b 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -213,6 +213,7 @@
     <addaction name="action_showHideController_default"/>
     <addaction name="action_showHideController_student"/>
     <addaction name="action_showHideController_picker"/>
+    <addaction name="action_showHideController_tuning"/>
     <addaction name="action_showHideController_safe"/>
    </widget>
    <addaction name="menuFile"/>
@@ -290,6 +291,17 @@
     <string>Safe</string>
    </property>
   </action>
+  <action name="action_showHideController_tuning">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Tuning</string>
+   </property>
+  </action>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <customwidgets>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index 98d17bfe..c1df7fef 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -88,6 +88,9 @@
          <height>60</height>
         </size>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="0" column="2">
@@ -174,6 +177,9 @@
          <height>60</height>
         </size>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="1" column="2">
@@ -190,6 +196,9 @@
          <height>60</height>
         </size>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="1" column="3">
@@ -206,6 +215,9 @@
          <height>60</height>
         </size>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="1" column="4">
@@ -222,6 +234,9 @@
          <height>60</height>
         </size>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
     </layout>
@@ -278,6 +293,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -438,6 +456,9 @@
            <family>Courier</family>
           </font>
          </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
         </widget>
        </item>
        <item>
@@ -493,6 +514,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -520,6 +544,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -563,6 +590,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -590,6 +620,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -617,6 +650,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -644,6 +680,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -784,6 +823,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -811,6 +853,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -838,6 +883,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -881,6 +929,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -908,6 +959,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -935,6 +989,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -962,6 +1019,9 @@
        <property name="text">
         <string>xx.xx</string>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
        <property name="readOnly">
         <bool>true</bool>
        </property>
@@ -1002,6 +1062,9 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="7" column="4">
@@ -1042,6 +1105,9 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="5" column="4">
@@ -1063,6 +1129,9 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="3" column="4">
@@ -1084,6 +1153,9 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
       </widget>
      </item>
      <item row="1" column="6">
@@ -1136,6 +1208,9 @@
            <family>Courier</family>
           </font>
          </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
         </widget>
        </item>
        <item>
@@ -1199,6 +1274,9 @@
            <family>Courier</family>
           </font>
          </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
         </widget>
        </item>
        <item>
@@ -1262,6 +1340,9 @@
            <family>Courier</family>
           </font>
          </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
         </widget>
        </item>
        <item>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
new file mode 100644
index 00000000..72ae921f
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
@@ -0,0 +1,703 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TuningControllerTab</class>
+ <widget class="QWidget" name="TuningControllerTab">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1503</width>
+    <height>814</height>
+   </rect>
+  </property>
+  <property name="font">
+   <font>
+    <pointsize>16</pointsize>
+   </font>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <property name="leftMargin">
+      <number>6</number>
+     </property>
+     <property name="topMargin">
+      <number>6</number>
+     </property>
+     <property name="rightMargin">
+      <number>6</number>
+     </property>
+     <property name="bottomMargin">
+      <number>6</number>
+     </property>
+     <item row="0" column="0">
+      <layout class="QGridLayout" name="gridLayout_3">
+       <property name="leftMargin">
+        <number>6</number>
+       </property>
+       <property name="topMargin">
+        <number>6</number>
+       </property>
+       <property name="rightMargin">
+        <number>6</number>
+       </property>
+       <property name="bottomMargin">
+        <number>6</number>
+       </property>
+       <item row="0" column="9">
+        <layout class="QVBoxLayout" name="verticalLayout_6">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <spacer name="verticalSpacer_6">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_13">
+           <property name="text">
+            <string>velocity</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_14">
+           <property name="text">
+            <string>[meters/second]</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="verticalSpacer_7">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="2">
+        <layout class="QVBoxLayout" name="verticalLayout_4">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_7">
+           <property name="text">
+            <string>gain</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="9">
+        <layout class="QHBoxLayout" name="horizontalLayout_10">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_5">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="0">
+        <layout class="QVBoxLayout" name="verticalLayout">
+         <property name="leftMargin">
+          <number>6</number>
+         </property>
+         <property name="rightMargin">
+          <number>6</number>
+         </property>
+         <item>
+          <spacer name="verticalSpacer_3">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_2">
+           <property name="text">
+            <string>angle</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_5">
+           <property name="text">
+            <string>[degrees]</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="verticalSpacer_2">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="2">
+        <layout class="QHBoxLayout" name="horizontalLayout_3">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="7">
+        <layout class="QVBoxLayout" name="verticalLayout_5">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_4">
+           <property name="text">
+            <string>gain</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="0">
+        <layout class="QHBoxLayout" name="horizontalLayout_4">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_2">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="5">
+        <layout class="QVBoxLayout" name="verticalLayout_2">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <spacer name="verticalSpacer_5">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_9">
+           <property name="text">
+            <string>position</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_10">
+           <property name="text">
+            <string>error</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <widget class="QLabel" name="label_11">
+           <property name="text">
+            <string>[meters]</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+         <item>
+          <spacer name="verticalSpacer_4">
+           <property name="orientation">
+            <enum>Qt::Vertical</enum>
+           </property>
+           <property name="sizeHint" stdset="0">
+            <size>
+             <width>20</width>
+             <height>0</height>
+            </size>
+           </property>
+          </spacer>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_7">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_8">
+           <property name="text">
+            <string>x</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="3" column="2">
+        <widget class="QSlider" name="horizontalSlider">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="0" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_6">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_12">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="text">
+            <string>+</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="1">
+        <layout class="QHBoxLayout" name="horizontalLayout_8">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_6">
+           <property name="text">
+            <string>=</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="7">
+        <layout class="QHBoxLayout" name="horizontalLayout_9">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_4">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="0" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout_2">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_3">
+           <property name="text">
+            <string>x</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="5">
+        <layout class="QHBoxLayout" name="horizontalLayout_5">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLineEdit" name="lineEdit_3">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>180</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="font">
+            <font>
+             <family>Courier</family>
+            </font>
+           </property>
+           <property name="text">
+            <string>xx.xx</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="1" column="0">
+        <widget class="Line" name="line">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="1">
+        <widget class="Line" name="line_2">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="2">
+        <widget class="Line" name="line_3">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="3">
+        <widget class="Line" name="line_4">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="5">
+        <widget class="Line" name="line_5">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="9">
+        <layout class="QVBoxLayout" name="verticalLayout_3">
+         <property name="leftMargin">
+          <number>0</number>
+         </property>
+         <property name="topMargin">
+          <number>6</number>
+         </property>
+         <property name="bottomMargin">
+          <number>6</number>
+         </property>
+         <item>
+          <widget class="Line" name="line_6">
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="1" column="6">
+        <widget class="Line" name="line_7">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="7">
+        <widget class="Line" name="line_8">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="1" column="8">
+        <widget class="Line" name="line_9">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+        </widget>
+       </item>
+       <item row="2" column="3">
+        <layout class="QHBoxLayout" name="horizontalLayout">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label">
+           <property name="text">
+            <string>x</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="6">
+        <layout class="QHBoxLayout" name="horizontalLayout_11">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_15">
+           <property name="text">
+            <string>+</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+       <item row="2" column="8">
+        <layout class="QHBoxLayout" name="horizontalLayout_12">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_16">
+           <property name="text">
+            <string>x</string>
+           </property>
+           <property name="alignment">
+            <set>Qt::AlignCenter</set>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
+      </layout>
+     </item>
+     <item row="1" column="0">
+      <spacer name="verticalSpacer">
+       <property name="orientation">
+        <enum>Qt::Vertical</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>40</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 7650f45f..c159378e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -50,6 +50,7 @@ public:
     void showHideController_default_changed();
     void showHideController_student_changed();
     void showHideController_picker_changed();
+    void showHideController_tuning_changed();
     void showHideController_safe_changed();
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 53139bfe..1f81bf8e 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -64,6 +64,7 @@ public:
     void showHideController_default_changed();
     void showHideController_student_changed();
     void showHideController_picker_changed();
+    void showHideController_tuning_changed();
     void showHideController_safe_changed();
 
 
@@ -75,12 +76,14 @@ private slots:
 
     // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
     void on_enable_safe_button_clicked();
+    void on_enable_tuning_button_clicked();
     void on_enable_picker_button_clicked();
     void on_enable_student_button_clicked();
     void on_enable_default_button_clicked();
 
     // LOAD YAML BUTTONS ON-CLICK CALLBACK
     void on_load_yaml_safe_button_clicked();
+    void on_load_yaml_tuning_button_clicked();
     void on_load_yaml_picker_button_clicked();
     void on_load_yaml_student_button_clicked();
     void on_load_yaml_default_button_clicked();
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index d456f45d..91e68c96 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -127,6 +127,7 @@ private slots:
     void on_action_showHideController_default_changed();
     void on_action_showHideController_student_changed();
     void on_action_showHideController_picker_changed();
+    void on_action_showHideController_tuning_changed();
     void on_action_showHideController_safe_changed();
 
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
new file mode 100644
index 00000000..2d4eaf3d
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -0,0 +1,22 @@
+#ifndef TUNINGCONTROLLERTAB_H
+#define TUNINGCONTROLLERTAB_H
+
+#include <QWidget>
+
+namespace Ui {
+class TuningControllerTab;
+}
+
+class TuningControllerTab : public QWidget
+{
+    Q_OBJECT
+
+public:
+    explicit TuningControllerTab(QWidget *parent = 0);
+    ~TuningControllerTab();
+
+private:
+    Ui::TuningControllerTab *ui;
+};
+
+#endif // TUNINGCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 7f58a1c9..9b112789 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -164,6 +164,11 @@ void ControllerTabs::showHideController_picker_changed()
     showHideController_toggle("Picker",ui->picker_tab);
 }
 
+void ControllerTabs::showHideController_tuning_changed()
+{
+    showHideController_toggle("Tuning",ui->tuning_tab);
+}
+
 void ControllerTabs::showHideController_safe_changed()
 {
     showHideController_toggle("Safe",ui->safe_tab);
@@ -302,7 +307,7 @@ void ControllerTabs::setControllerEnabled(int new_controller)
         }
         case TUNING_CONTROLLER:
         {
-            //ui->controller_enabled_label->setText("Tuning");
+            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->tuning_tab );
             break;
         }
         case PICKER_CONTROLLER:
@@ -324,6 +329,7 @@ void ControllerTabs::setAllTabLabelsToNormalColouring()
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->default_tab );
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->student_tab );
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->picker_tab );
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->tuning_tab );
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->safe_tab );
 }
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index ca509b8f..e3afc90f 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -61,10 +61,16 @@ void EnableControllerLoadYamlBar::showHideController_student_changed()
 
 void EnableControllerLoadYamlBar::showHideController_picker_changed()
 {
-    ui->enable_picker_button   ->setHidden(    !(ui->enable_picker_button->isHidden()) );
+    ui->enable_picker_button   ->setHidden( !(ui->enable_picker_button->isHidden()) );
     ui->load_yaml_picker_button->setHidden( !(ui->load_yaml_picker_button->isHidden()) );
 }
 
+void EnableControllerLoadYamlBar::showHideController_tuning_changed()
+{
+    ui->enable_tuning_button   ->setHidden( !(ui->enable_tuning_button->isHidden()) );
+    ui->load_yaml_tuning_button->setHidden( !(ui->load_yaml_tuning_button->isHidden()) );
+}
+
 void EnableControllerLoadYamlBar::showHideController_safe_changed()
 {
     ui->enable_safe_button   ->setHidden( !(ui->enable_safe_button->isHidden()) );
@@ -89,6 +95,17 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 #endif
 }
 
+void EnableControllerLoadYamlBar::on_enable_tuning_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_USE_TUNING_CONTROLLER;
+    this->commandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Tuning Controller");
+#endif
+}
+
 void EnableControllerLoadYamlBar::on_enable_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
@@ -114,11 +131,11 @@ void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    //d_fall_pps::IntWithHeader msg;
-    //fillIntMessageHeader(msg);
-    //msg.data = CMD_USE_STUDENT_CONTROLLER;
-    //this->commandPublisher.publish(msg);
-    //ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Student Controller");
+    d_fall_pps::IntWithHeader msg;
+    fillIntMessageHeader(msg);
+    msg.data = CMD_USE_SAFE_CONTROLLER;
+    this->commandPublisher.publish(msg);
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
 #endif
 }
 
@@ -132,6 +149,22 @@ void EnableControllerLoadYamlBar::on_load_yaml_safe_button_clicked()
 #endif
 }
 
+void EnableControllerLoadYamlBar::on_load_yaml_tuning_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Create a local variable for the message
+    d_fall_pps::StringWithHeader yaml_filename_msg;
+    // Set for whom this applies to
+    fillStringMessageHeader(yaml_filename_msg);
+    // Specify the data
+    yaml_filename_msg.data = "TuningController";
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+    // Inform the user that the menu item was selected
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Tuning Controller YAML was clicked.");
+#endif
+}
+
 void EnableControllerLoadYamlBar::on_load_yaml_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index f9173ae6..b96cbfa5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -140,6 +140,8 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
 
     // > For the picker controller
     ui->action_showHideController_picker->trigger();
+    // > For the tuning controller
+    ui->action_showHideController_tuning->trigger();
     // > For the safe controller
     ui->action_showHideController_safe->trigger();
 
@@ -234,6 +236,13 @@ void MainWindow::on_action_showHideController_picker_changed()
     ui->customWidget_controller_tabs->showHideController_picker_changed();
 }
 
+void MainWindow::on_action_showHideController_tuning_changed()
+{
+    // Notify the UI elements of this change
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_tuning_changed();
+    ui->customWidget_controller_tabs->showHideController_tuning_changed();
+}
+
 void MainWindow::on_action_showHideController_safe_changed()
 {
     // Notify the UI elements of this change
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
new file mode 100644
index 00000000..98a271f5
--- /dev/null
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -0,0 +1,14 @@
+#include "tuningcontrollertab.h"
+#include "ui_tuningcontrollertab.h"
+
+TuningControllerTab::TuningControllerTab(QWidget *parent) :
+    QWidget(parent),
+    ui(new Ui::TuningControllerTab)
+{
+    ui->setupUi(this);
+}
+
+TuningControllerTab::~TuningControllerTab()
+{
+    delete ui;
+}
-- 
GitLab


From f099085986545d396554c4dffe99c5c2c4de4918 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 05:59:12 +0100
Subject: [PATCH 45/87] Continued with building the appearance of the tuning
 controller tab GUI

---
 .../forms/tuningcontrollertab.ui              | 311 +++++++++++++++---
 .../include/tuningcontrollertab.h             |   7 +
 .../src/tuningcontrollertab.cpp               |  15 +
 3 files changed, 296 insertions(+), 37 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
index 72ae921f..9db1f6c5 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1503</width>
-    <height>814</height>
+    <width>1507</width>
+    <height>970</height>
    </rect>
   </property>
   <property name="font">
@@ -33,7 +33,37 @@
      <property name="bottomMargin">
       <number>6</number>
      </property>
-     <item row="0" column="0">
+     <item row="10" column="1">
+      <widget class="QLabel" name="label_21">
+       <property name="text">
+        <string>step 3: repeat steps 1 and 2 until desired performance is achieved</string>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="1">
+      <spacer name="verticalSpacer_10">
+       <property name="orientation">
+        <enum>Qt::Vertical</enum>
+       </property>
+       <property name="sizeType">
+        <enum>QSizePolicy::Fixed</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>10</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="4" column="1">
+      <widget class="Line" name="line_10">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="1">
       <layout class="QGridLayout" name="gridLayout_3">
        <property name="leftMargin">
         <number>6</number>
@@ -47,7 +77,7 @@
        <property name="bottomMargin">
         <number>6</number>
        </property>
-       <item row="0" column="9">
+       <item row="1" column="9">
         <layout class="QVBoxLayout" name="verticalLayout_6">
          <property name="leftMargin">
           <number>12</number>
@@ -103,7 +133,7 @@
          </item>
         </layout>
        </item>
-       <item row="0" column="2">
+       <item row="1" column="2">
         <layout class="QVBoxLayout" name="verticalLayout_4">
          <property name="leftMargin">
           <number>12</number>
@@ -123,7 +153,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="9">
+       <item row="3" column="9">
         <layout class="QHBoxLayout" name="horizontalLayout_10">
          <property name="leftMargin">
           <number>12</number>
@@ -156,11 +186,14 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="0" column="0">
+       <item row="1" column="0">
         <layout class="QVBoxLayout" name="verticalLayout">
          <property name="leftMargin">
           <number>6</number>
@@ -216,7 +249,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="2">
+       <item row="3" column="2">
         <layout class="QHBoxLayout" name="horizontalLayout_3">
          <property name="leftMargin">
           <number>12</number>
@@ -249,11 +282,14 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="0" column="7">
+       <item row="1" column="7">
         <layout class="QVBoxLayout" name="verticalLayout_5">
          <property name="leftMargin">
           <number>12</number>
@@ -273,7 +309,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="0">
+       <item row="3" column="0">
         <layout class="QHBoxLayout" name="horizontalLayout_4">
          <property name="leftMargin">
           <number>12</number>
@@ -306,11 +342,14 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="0" column="5">
+       <item row="1" column="5">
         <layout class="QVBoxLayout" name="verticalLayout_2">
          <property name="leftMargin">
           <number>12</number>
@@ -376,7 +415,7 @@
          </item>
         </layout>
        </item>
-       <item row="0" column="8">
+       <item row="1" column="8">
         <layout class="QHBoxLayout" name="horizontalLayout_7">
          <property name="leftMargin">
           <number>12</number>
@@ -396,14 +435,7 @@
          </item>
         </layout>
        </item>
-       <item row="3" column="2">
-        <widget class="QSlider" name="horizontalSlider">
-         <property name="orientation">
-          <enum>Qt::Horizontal</enum>
-         </property>
-        </widget>
-       </item>
-       <item row="0" column="6">
+       <item row="1" column="6">
         <layout class="QHBoxLayout" name="horizontalLayout_6">
          <property name="leftMargin">
           <number>12</number>
@@ -429,7 +461,7 @@
          </item>
         </layout>
        </item>
-       <item row="0" column="1">
+       <item row="1" column="1">
         <layout class="QHBoxLayout" name="horizontalLayout_8">
          <property name="leftMargin">
           <number>12</number>
@@ -449,7 +481,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="7">
+       <item row="3" column="7">
         <layout class="QHBoxLayout" name="horizontalLayout_9">
          <property name="leftMargin">
           <number>12</number>
@@ -482,11 +514,14 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="0" column="3">
+       <item row="1" column="3">
         <layout class="QHBoxLayout" name="horizontalLayout_2">
          <property name="leftMargin">
           <number>12</number>
@@ -506,7 +541,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="5">
+       <item row="3" column="5">
         <layout class="QHBoxLayout" name="horizontalLayout_5">
          <property name="leftMargin">
           <number>12</number>
@@ -539,46 +574,49 @@
            <property name="alignment">
             <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
            </property>
+           <property name="readOnly">
+            <bool>true</bool>
+           </property>
           </widget>
          </item>
         </layout>
        </item>
-       <item row="1" column="0">
+       <item row="2" column="0">
         <widget class="Line" name="line">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="1">
+       <item row="2" column="1">
         <widget class="Line" name="line_2">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="2">
+       <item row="2" column="2">
         <widget class="Line" name="line_3">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="3">
+       <item row="2" column="3">
         <widget class="Line" name="line_4">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="5">
+       <item row="2" column="5">
         <widget class="Line" name="line_5">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="9">
+       <item row="2" column="9">
         <layout class="QVBoxLayout" name="verticalLayout_3">
          <property name="leftMargin">
           <number>0</number>
@@ -598,28 +636,28 @@
          </item>
         </layout>
        </item>
-       <item row="1" column="6">
+       <item row="2" column="6">
         <widget class="Line" name="line_7">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="7">
+       <item row="2" column="7">
         <widget class="Line" name="line_8">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="1" column="8">
+       <item row="2" column="8">
         <widget class="Line" name="line_9">
          <property name="orientation">
           <enum>Qt::Horizontal</enum>
          </property>
         </widget>
        </item>
-       <item row="2" column="3">
+       <item row="3" column="3">
         <layout class="QHBoxLayout" name="horizontalLayout">
          <property name="leftMargin">
           <number>12</number>
@@ -639,7 +677,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="6">
+       <item row="3" column="6">
         <layout class="QHBoxLayout" name="horizontalLayout_11">
          <property name="leftMargin">
           <number>12</number>
@@ -659,7 +697,7 @@
          </item>
         </layout>
        </item>
-       <item row="2" column="8">
+       <item row="3" column="8">
         <layout class="QHBoxLayout" name="horizontalLayout_12">
          <property name="leftMargin">
           <number>12</number>
@@ -679,9 +717,65 @@
          </item>
         </layout>
        </item>
+       <item row="4" column="2">
+        <layout class="QHBoxLayout" name="horizontalLayout_14">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QSlider" name="slider_gain_P">
+           <property name="sizePolicy">
+            <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+             <horstretch>0</horstretch>
+             <verstretch>0</verstretch>
+            </sizepolicy>
+           </property>
+           <property name="maximumSize">
+            <size>
+             <width>220</width>
+             <height>16777215</height>
+            </size>
+           </property>
+           <property name="styleSheet">
+            <string notr="true"/>
+           </property>
+           <property name="maximum">
+            <number>1000</number>
+           </property>
+           <property name="pageStep">
+            <number>50</number>
+           </property>
+           <property name="value">
+            <number>100</number>
+           </property>
+           <property name="tracking">
+            <bool>false</bool>
+           </property>
+           <property name="orientation">
+            <enum>Qt::Horizontal</enum>
+           </property>
+           <property name="invertedAppearance">
+            <bool>false</bool>
+           </property>
+           <property name="invertedControls">
+            <bool>false</bool>
+           </property>
+           <property name="tickPosition">
+            <enum>QSlider::TicksBothSides</enum>
+           </property>
+           <property name="tickInterval">
+            <number>100</number>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
       </layout>
      </item>
-     <item row="1" column="0">
+     <item row="11" column="1">
       <spacer name="verticalSpacer">
        <property name="orientation">
         <enum>Qt::Vertical</enum>
@@ -694,6 +788,149 @@
        </property>
       </spacer>
      </item>
+     <item row="2" column="1">
+      <layout class="QHBoxLayout" name="horizontalLayout_13">
+       <property name="leftMargin">
+        <number>6</number>
+       </property>
+       <property name="topMargin">
+        <number>6</number>
+       </property>
+       <property name="rightMargin">
+        <number>6</number>
+       </property>
+       <property name="bottomMargin">
+        <number>6</number>
+       </property>
+       <item>
+        <widget class="QLabel" name="label_18">
+         <property name="text">
+          <string>setpoint =</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="button_setpoint_toggle">
+         <property name="text">
+          <string>toggle</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <spacer name="horizontalSpacer">
+         <property name="orientation">
+          <enum>Qt::Horizontal</enum>
+         </property>
+         <property name="sizeHint" stdset="0">
+          <size>
+           <width>40</width>
+           <height>20</height>
+          </size>
+         </property>
+        </spacer>
+       </item>
+      </layout>
+     </item>
+     <item row="9" column="1">
+      <widget class="QLabel" name="label_20">
+       <property name="text">
+        <string>step 2: click toggle button to test the performance</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="1">
+      <widget class="QLabel" name="label_17">
+       <property name="text">
+        <string>Horizontal Controller (Horizontal Regler)</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1">
+      <spacer name="verticalSpacer_8">
+       <property name="orientation">
+        <enum>Qt::Vertical</enum>
+       </property>
+       <property name="sizeType">
+        <enum>QSizePolicy::Fixed</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>10</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="8" column="1">
+      <widget class="QLabel" name="label_19">
+       <property name="text">
+        <string>step 1: adjust slider to change the gain</string>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="1">
+      <widget class="Line" name="line_11">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="1">
+      <spacer name="verticalSpacer_9">
+       <property name="orientation">
+        <enum>Qt::Vertical</enum>
+       </property>
+       <property name="sizeType">
+        <enum>QSizePolicy::Fixed</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>10</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="11" column="2">
+      <spacer name="horizontalSpacer_2">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
     </layout>
    </item>
   </layout>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index 2d4eaf3d..d296d0bb 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -15,6 +15,13 @@ public:
     explicit TuningControllerTab(QWidget *parent = 0);
     ~TuningControllerTab();
 
+private slots:
+    void on_button_setpoint_toggle_clicked();
+
+    void on_lineEdit_setpoint_editingFinished();
+
+    void on_slider_gain_P_valueChanged(int value);
+
 private:
     Ui::TuningControllerTab *ui;
 };
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index 98a271f5..801865dd 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -12,3 +12,18 @@ TuningControllerTab::~TuningControllerTab()
 {
     delete ui;
 }
+
+void TuningControllerTab::on_button_setpoint_toggle_clicked()
+{
+
+}
+
+void TuningControllerTab::on_lineEdit_setpoint_editingFinished()
+{
+
+}
+
+void TuningControllerTab::on_slider_gain_P_valueChanged(int value)
+{
+
+}
-- 
GitLab


From a5eb01bc734420b277ec71082107a45da1f5e540 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 09:17:33 +0100
Subject: [PATCH 46/87] Tuning controller GUI intergrated with ROS. Next step
 is to update the Tuning Controller Service Node

---
 .../forms/tuningcontrollertab.ui              |  29 +-
 .../include/tuningcontrollertab.h             | 139 ++++
 .../src/tuningcontrollertab.cpp               | 644 ++++++++++++++++++
 3 files changed, 806 insertions(+), 6 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
index 9db1f6c5..28732632 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
@@ -6,7 +6,7 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1507</width>
+    <width>1519</width>
     <height>970</height>
    </rect>
   </property>
@@ -162,7 +162,7 @@
           <number>12</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_5">
+          <widget class="QLineEdit" name="lineEdit_error_D">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -258,7 +258,7 @@
           <number>12</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit">
+          <widget class="QLineEdit" name="lineEdit_gain_P">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -318,7 +318,7 @@
           <number>12</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_2">
+          <widget class="QLineEdit" name="lineEdit_angle">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -490,7 +490,7 @@
           <number>12</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_4">
+          <widget class="QLineEdit" name="lineEdit_gain_D">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -550,7 +550,7 @@
           <number>12</number>
          </property>
          <item>
-          <widget class="QLineEdit" name="lineEdit_3">
+          <widget class="QLineEdit" name="lineEdit_error_P">
            <property name="sizePolicy">
             <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
              <horstretch>0</horstretch>
@@ -773,6 +773,23 @@
          </item>
         </layout>
        </item>
+       <item row="3" column="1">
+        <layout class="QHBoxLayout" name="horizontalLayout_15">
+         <property name="leftMargin">
+          <number>12</number>
+         </property>
+         <property name="rightMargin">
+          <number>12</number>
+         </property>
+         <item>
+          <widget class="QLabel" name="label_22">
+           <property name="text">
+            <string>=</string>
+           </property>
+          </widget>
+         </item>
+        </layout>
+       </item>
       </layout>
      </item>
      <item row="11" column="1">
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index d296d0bb..77738088 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -2,6 +2,64 @@
 #define TUNINGCONTROLLERTAB_H
 
 #include <QWidget>
+#include <QMutex>
+#include <QVector>
+#include <QLineEdit>
+#include <QTextStream>
+
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/FloatWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+#include "d_fall_pps/CustomButtonWithHeader.h"
+
+// Include the DFALL service types
+#include "d_fall_pps/GetSetpointService.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace d_fall_pps;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
+#endif
+
+
+#define P_GAIN_MIN_GUI  1
+#define P_GAIN_MAX_GUI  10
+#define P_TO_D_GAIN_RATIO_GUI 0.4
+
+#define DECIMAL_PLACES_POSITION_MEASURED 3
+#define DECIMAL_PLACES_ANGLE_DEGREES 1
+#define DECIMAL_PLACES_VELOCITY 2
+#define DECIMAL_PLACES_GAIN 2
+
+#define DECIMAL_PLACES_SETPOINT 2
+
+#define SETPOINT_X_MINUS -0.25
+#define SETPOINT_X_PLUS   0.25
+
+#define SETPOINT_Y  0.0
+#define SETPOINT_Z  0.4
+#define SETPOINT_YAW_DEGREES  0.0
+
+#define MEASUREMENT_FRQUENCY 200.0
+
+
 
 namespace Ui {
 class TuningControllerTab;
@@ -15,6 +73,15 @@ public:
     explicit TuningControllerTab(QWidget *parent = 0);
     ~TuningControllerTab();
 
+
+
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSlot();
+
+
+
 private slots:
     void on_button_setpoint_toggle_clicked();
 
@@ -22,8 +89,80 @@ private slots:
 
     void on_slider_gain_P_valueChanged(int value);
 
+
+
 private:
     Ui::TuningControllerTab *ui;
+
+    // --------------------------------------------------- //
+        // PRIVATE VARIABLES
+
+        // The type of this node, i.e., agent or a coordinator,
+        // specified as a parameter in the "*.launch" file
+        int m_type = 0;
+
+        // The ID  of this node
+        int m_ID;
+
+        // For coordinating multiple agents
+        std::vector<int> m_vector_of_agentIDs_toCoordinate;
+        bool m_shouldCoordinateAll = true;
+        QMutex m_agentIDs_toCoordinate_mutex;
+
+
+
+        float m_gain_P = 0.0;
+        float m_gain_D = 0.0;
+
+        float m_current_setpoint = 0.0;
+
+        QMutex m_gain_setpoint_mutex;
+
+        float m_x_previous = 0.0;
+
+
+
+    #ifdef CATKIN_MAKE
+        // PUBLISHER
+        // > For requesting the setpoint to be changed
+        ros::Publisher requestSetpointChangePublisher;
+
+        // SUBSCRIBER
+        // > For being notified when the setpoint is changed
+        ros::Subscriber setpointChangedSubscriber;
+
+        // PUBLISHER
+        // > For notifying the P gain is changed
+        ros::Publisher requestNewGainChangePublisher;
+
+        // PUBLISHER
+        // > For notifying that a custom button is pressed
+        //ros::Publisher customButtonPublisher;
+    #endif
+
+        // --------------------------------------------------- //
+        // PRIVATE FUNCTIONS
+
+
+    #ifdef CATKIN_MAKE
+        // For receiving message that the setpoint was changed
+        void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+
+        // Publish a message when a custom button is pressed
+        //void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer);
+
+        // Fill the header for a message
+        void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+        void fillFloatMessageHeader( d_fall_pps::FloatWithHeader & msg );
+
+        // Get the paramters that specify the type and ID
+        bool getTypeAndIDParameters();
+    #endif
+
+        void publishSetpoint(float x, float y, float z, float yaw);
+
+        void publishGain(float new_gain);
+
 };
 
 #endif // TUNINGCONTROLLERTAB_H
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index 801865dd..7fa20851 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -6,6 +6,80 @@ TuningControllerTab::TuningControllerTab(QWidget *parent) :
     ui(new Ui::TuningControllerTab)
 {
     ui->setupUi(this);
+
+    // Set the gain field
+    int starting_slider_value = ui->slider_gain_P->value();
+    float slider_ratio = float(starting_slider_value) / 1000.0;
+
+    m_gain_P = P_GAIN_MIN_GUI + slider_ratio * (P_GAIN_MAX_GUI-P_GAIN_MIN_GUI);
+    m_gain_D = m_gain_P * P_TO_D_GAIN_RATIO_GUI;
+
+    ui->lineEdit_gain_P->setText( QString::number( m_gain_P, 'f', DECIMAL_PLACES_GAIN) );
+    ui->lineEdit_gain_D->setText( QString::number( m_gain_D, 'f', DECIMAL_PLACES_GAIN) );
+
+    ui->lineEdit_setpoint->setText( QString::number( m_current_setpoint, 'f', DECIMAL_PLACES_SETPOINT) );
+
+
+#ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[TUNING CONTROLLER TAB GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[TUNING CONTROLLER TAB GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("TuningControllerService/RequestSetpointChange", 1);
+
+    // SUBSCRIBE TO SETPOINT CHANGES
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("TuningControllerService/SetpointChanged", 1, &TuningControllerTab::setpointChangedCallback, this);
+    }
+
+
+    // CREATE THE NEW GAIN PUBLISHER
+    requestNewGainChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::FloatWithHeader>("TuningControllerService/RequestGainChange", 1);
+
+    // CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
+    //customButtonPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::CustomButtonWithHeader>("TuningControllerService/CustomButtonPressed", 1);
+
+    // GET THE CURRENT SETPOINT
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+//        // > Request the current setpoint
+//        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
+//        d_fall_pps::GetSetpointService getSetpointCall;
+//        getSetpointCall.request.data = 0;
+//        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+//        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+//        {
+//            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+//        }
+//        else
+//        {
+//            // Inform the user
+//            ROS_INFO("[TUNING CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+//        }
+    }
+
+#endif
 }
 
 TuningControllerTab::~TuningControllerTab()
@@ -13,17 +87,587 @@ TuningControllerTab::~TuningControllerTab()
     delete ui;
 }
 
+
+
+//    ----------------------------------------------------------------------------------
+//    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
+//    P   P  O   O  S      E         D   D   A A     T     A A
+//    PPPP   O   O   SSS   EEE       D   D  A   A    T    A   A
+//    P      O   O      S  E         D   D  AAAAA    T    AAAAA
+//    P       OOO   SSSS   EEEEE     DDDD   A   A    T    A   A
+//    ----------------------------------------------------------------------------------
+
+
+void TuningControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+{
+    if (!occluded)
+    {
+        m_gain_setpoint_mutex.lock();
+
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+        QString qstr = "";
+
+        // PUT IN THE POSITION ERROR
+        float error_x = x - m_current_setpoint;
+        ui->lineEdit_error_P->setText( QString::number( error_x, 'f', DECIMAL_PLACES_POSITION_MEASURED) );
+
+        // COMPUTE AND PUT IN THE VELOCITY
+        float velocity_x = (x - m_x_previous) * MEASUREMENT_FRQUENCY;
+        m_x_previous = x;
+        ui->lineEdit_error_D->setText( QString::number( velocity_x, 'f', DECIMAL_PLACES_VELOCITY) );
+
+        // COMPUTE AND PUT IN THE ANGLE
+        float angle = (m_gain_P * error_x + m_gain_D * velocity_x) * RAD2DEG;
+        ui->lineEdit_angle->setText( QString::number( angle, 'f', DECIMAL_PLACES_ANGLE_DEGREES) );
+
+        m_gain_setpoint_mutex.unlock();
+
+//        // UPDATE THE MEASUREMENT COLUMN
+//        if (x < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', 3));
+//        if (y < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', 3));
+//        if (z < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
+
+//        if (roll < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+//        if (pitch < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
+//        if (yaw < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
+
+//        // GET THE CURRENT SETPOINT
+//        float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
+//        float error_y   = y   - (ui->lineEdit_setpoint_current_y->text()  ).toFloat();
+//        float error_z   = z   - (ui->lineEdit_setpoint_current_z->text()  ).toFloat();
+//        float error_yaw = yaw - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+//        // UPDATE THE ERROR COLUMN
+//        if (error_x < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_error_x->setText(qstr + QString::number( error_x, 'f', 3));
+//        if (error_y < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_error_y->setText(qstr + QString::number( error_y, 'f', 3));
+//        if (error_z < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', 3));
+
+//        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
+//        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+
+//        // Ensure the red frames are not visible
+//        if ( ui->red_frame_position_left->isVisible() )
+//            ui->red_frame_position_left->setVisible(false);
+//        if ( ui->red_frame_position_right->isVisible() )
+//            ui->red_frame_position_right->setVisible(false);
+    }
+    else
+    {
+//        // Make visible the red frames to indicate occluded
+//        if ( !(ui->red_frame_position_left->isVisible()) )
+//            ui->red_frame_position_left->setVisible(true);
+//        if ( !(ui->red_frame_position_right->isVisible()) )
+//            ui->red_frame_position_right->setVisible(true);
+    }
+}
+
+
+void TuningControllerTab::poseDataUnavailableSlot()
+{
+    ui->lineEdit_angle->setText("xx.xx");
+    ui->lineEdit_error_P->setText("xx.xx");
+    ui->lineEdit_error_D->setText("xx.xx");
+}
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC  H   H    A    N   N   GGGG  EEEEE  DDDD
+//    C      H   H   A A   NN  N  G      E      D   D
+//    C      HHHHH  A   A  N N N  G      EEE    D   D
+//    C      H   H  AAAAA  N  NN  G   G  E      D   D
+//     CCCC  H   H  A   A  N   N   GGGG  EEEEE  DDDD
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void TuningControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+{
+//    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+//    QString qstr = "";
+
+//    // EXTRACT THE SETPOINT
+//    float x = newSetpoint.x;
+//    float y = newSetpoint.y;
+//    float z = newSetpoint.z;
+//    float yaw = newSetpoint.yaw;
+
+//    // UPDATE THE SETPOINT COLUMN
+//    if (x < 0.0f) qstr = ""; else qstr = "+";
+//    ui->lineEdit_setpoint_current_x->setText(qstr + QString::number( x, 'f', 3));
+//    if (y < 0.0f) qstr = ""; else qstr = "+";
+//    ui->lineEdit_setpoint_current_y->setText(qstr + QString::number( y, 'f', 3));
+//    if (z < 0.0f) qstr = ""; else qstr = "+";
+//    ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3));
+
+//    if (yaw < 0.0f) qstr = ""; else qstr = "+";
+//    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 3));
+}
+#endif
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    RRRR   EEEEE   QQQ   U   U  EEEEE   SSSS  TTTTT     N   N  EEEEE  W     W
+//    R   R  E      Q   Q  U   U  E      S        T       NN  N  E      W     W
+//    RRRR   EEE    Q   Q  U   U  EEE     SSS     T       N N N  EEE    W     W
+//    R   R  E      Q  Q   U   U  E          S    T       N  NN  E       W W W
+//    R   R  EEEEE   QQ Q   UUU   EEEEE  SSSS     T       N   N  EEEEE    W W
+//
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//    ----------------------------------------------------------------------------------
+
+
+void TuningControllerTab::publishSetpoint(float x, float y, float z, float yaw)
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    d_fall_pps::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.x   = x;
+    msg.y   = y;
+    msg.z   = z;
+    msg.yaw = yaw * DEG2RAD;
+
+    // Publish the setpoint
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[TUNING CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[TUNING CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]";
+#endif
+}
+
+
+
+
+
 void TuningControllerTab::on_button_setpoint_toggle_clicked()
 {
 
+    m_gain_setpoint_mutex.lock();
+
+    float setpoint_copy = m_current_setpoint;
+    float new_setpoint = 0.0;
+
+    if (setpoint_copy < SETPOINT_X_MINUS)
+        new_setpoint = SETPOINT_X_MINUS;
+    else if (setpoint_copy < 0.0)
+        new_setpoint = SETPOINT_X_PLUS;
+    else if (setpoint_copy > SETPOINT_X_PLUS)
+        new_setpoint = SETPOINT_X_PLUS;
+    else
+        new_setpoint = SETPOINT_X_MINUS;
+
+    ui->lineEdit_setpoint->setText( QString::number( new_setpoint, 'f', DECIMAL_PLACES_SETPOINT) );
+    float lineEdit_as_float_rounded = (ui->lineEdit_setpoint->text()).toFloat();
+    m_current_setpoint = lineEdit_as_float_rounded;
+    publishSetpoint( m_current_setpoint, SETPOINT_Y, SETPOINT_Z, SETPOINT_YAW_DEGREES);
+
+    m_gain_setpoint_mutex.unlock();
+
 }
 
 void TuningControllerTab::on_lineEdit_setpoint_editingFinished()
 {
+    m_gain_setpoint_mutex.lock();
+
+
+    // Get the line edit data, as a float if possible
+    bool isValidFloat = false;
+    float lineEdit_as_float = (ui->lineEdit_setpoint->text()).toFloat(&isValidFloat);
+
+    // Fill in the data
+    if (isValidFloat)
+    {
+        ui->lineEdit_setpoint->setText( QString::number( lineEdit_as_float, 'f', DECIMAL_PLACES_SETPOINT) );
+        float lineEdit_as_float_rounded = (ui->lineEdit_setpoint->text()).toFloat();
+        m_current_setpoint = lineEdit_as_float_rounded;
+        publishSetpoint( m_current_setpoint, SETPOINT_Y, SETPOINT_Z, SETPOINT_YAW_DEGREES);
+    }
+    else
+    {
+        ui->lineEdit_setpoint->setText( QString::number( m_current_setpoint, 'f', DECIMAL_PLACES_SETPOINT) );
+    }
+    m_gain_setpoint_mutex.unlock();
+}
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+void TuningControllerTab::publishGain(float new_gain)
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    d_fall_pps::FloatWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
 
+    // Fill in the gain value
+    msg.data = new_gain;
+
+    // Publish the setpoint
+    this->requestNewGainChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[TUNING CONTROLLER GUI] Published request for gain change to: " << new_gain );
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[TUNING CONTROLLER GUI] would publish gain value: " << new_gain;
+#endif
 }
 
+
 void TuningControllerTab::on_slider_gain_P_valueChanged(int value)
 {
 
+    m_gain_setpoint_mutex.lock();
+
+    float slider_ratio = float(value) / 1000.0;
+
+    float new_gain_P = P_GAIN_MIN_GUI + slider_ratio * (P_GAIN_MAX_GUI-P_GAIN_MIN_GUI);
+    float new_gain_D = new_gain_P * P_TO_D_GAIN_RATIO_GUI;
+
+    ui->lineEdit_gain_P->setText( QString::number( new_gain_P, 'f', DECIMAL_PLACES_GAIN) );
+    ui->lineEdit_gain_D->setText( QString::number( new_gain_D, 'f', DECIMAL_PLACES_GAIN) );
+
+    float gain_P_rounded = (ui->lineEdit_gain_P->text()).toFloat();
+    float gain_D_rounded = (ui->lineEdit_gain_D->text()).toFloat();
+
+    m_gain_P = gain_P_rounded;
+    m_gain_D = gain_D_rounded;
+
+    publishGain(m_gain_P);
+
+    m_gain_setpoint_mutex.unlock();
+
+}
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void TuningControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+//        // // > Create the appropriate node handle
+//        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+//        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+//        // // > Request the current setpoint
+//        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
+//        d_fall_pps::GetSetpointService getSetpointCall;
+//        getSetpointCall.request.data = 0;
+//        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+//        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+//        {
+//            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+//        }
+//        else
+//        {
+//            // Inform the user
+//            ROS_INFO("[TUNING CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+//        }
+
+//        // SUBSCRIBERS
+//        // > For receiving message that the setpoint was changed
+//        setpointChangedSubscriber = agent_base_nodeHandle.subscribe("TuningControllerService/SetpointChanged", 1, &TuningControllerTab::setpointChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        setpointChangedSubscriber.shutdown();
+
+        // Set information back to the default
+        ui->lineEdit_setpoint_current_x->setText("xx.xx");
+        ui->lineEdit_setpoint_current_y->setText("xx.xx");
+        ui->lineEdit_setpoint_current_z->setText("xx.xx");
+        ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
+
+    }
+#endif
+}
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void TuningControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+}
+#endif
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void TuningControllerTab::fillFloatMessageHeader( d_fall_pps::FloatWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool TuningControllerTab::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[TUNING CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[TUNING CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[TUNING CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[TUNING CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[TUNING CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
 }
+#endif
-- 
GitLab


From da24b1c171cf2ee8fb3679c2035faf3bea61123f Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 09:58:21 +0100
Subject: [PATCH 47/87] Adapted the Tuning Contorller Service ROS node to be
 integrated with the current standard and with its new GUI

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |   3 +-
 .../include/tuningcontrollertab.h             |   6 +-
 .../include/nodes/TuningControllerService.h   |  99 ++-
 .../d_fall_pps/param/TuningController.yaml    |   2 +-
 .../src/nodes/StudentControllerService.cpp    |   2 +-
 .../src/nodes/TuningControllerService.cpp     | 600 +++++++++---------
 6 files changed, 402 insertions(+), 310 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index 1748c5e2..fd145d0a 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -338,7 +338,8 @@ add_executable(StudentControllerService  src/nodes/StudentControllerService.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(MpcControllerService      src/nodes/MpcControllerService.cpp)
 add_executable(RemoteControllerService   src/nodes/RemoteControllerService.cpp)
-add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp)
+add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(PickerControllerService   src/nodes/PickerControllerService.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(CentralManagerService     src/nodes/CentralManagerService.cpp src/CrazyflieIO.cpp)
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index 77738088..e26851eb 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -39,9 +39,9 @@
 #endif
 
 
-#define P_GAIN_MIN_GUI  1
-#define P_GAIN_MAX_GUI  10
-#define P_TO_D_GAIN_RATIO_GUI 0.4
+#define P_GAIN_MIN_GUI  0.10
+#define P_GAIN_MAX_GUI  1.00
+#define P_TO_D_GAIN_RATIO_GUI 0.6
 
 #define DECIMAL_PLACES_POSITION_MEASURED 3
 #define DECIMAL_PLACES_ANGLE_DEGREES 1
diff --git a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
index 8701bc89..f6ec1a02 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
@@ -55,19 +55,49 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
-//the generated structs from the msg-files have to be included
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "d_fall_pps/IntWithHeader.h"
+#include "d_fall_pps/FloatWithHeader.h"
+//#include "d_fall_pps/StringWithHeader.h"
+#include "d_fall_pps/SetpointWithHeader.h"
+//#include "d_fall_pps/CustomButtonWithHeader.h"
 #include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
+//#include "d_fall_pps/Setpoint.h"
 #include "d_fall_pps/ControlCommand.h"
 #include "d_fall_pps/Controller.h"
 #include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
-#include "d_fall_pps/ViconSubscribeObjectName.h"
 
-// Include the Parameter Service shared definitions
+// Include the DFALL service types
+#include "d_fall_pps/LoadYamlFromFilename.h"
+#include "d_fall_pps/GetSetpointService.h"
+
+// Include the shared definitions
 #include "nodes/Constants.h"
 
-#include <std_msgs/Int32.h>
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+
+
+
+// //the generated structs from the msg-files have to be included
+// #include "d_fall_pps/ViconData.h"
+// #include "d_fall_pps/Setpoint.h"
+// #include "d_fall_pps/ControlCommand.h"
+// #include "d_fall_pps/Controller.h"
+// #include "d_fall_pps/DebugMsg.h"
+// #include "d_fall_pps/CustomButton.h"
+// #include "d_fall_pps/ViconSubscribeObjectName.h"
+
+// // Include the Parameter Service shared definitions
+// #include "nodes/Constants.h"
+
+// #include <std_msgs/Int32.h>
 
 
 
@@ -175,6 +205,16 @@ using namespace d_fall_pps;
 //    ----------------------------------------------------------------------------------
 
 
+
+
+float m_gain_P = 0.31;
+float m_gain_P_to_D_ratio = 0.6;
+
+
+
+
+
+
 // ******************************************************************************* //
 // VARIABLES SPECIFIC TO THE TUNING CONTROL FEATURE
 
@@ -259,7 +299,7 @@ float setpoint[4] = {0.0,0.0,0.4,0.0};
 
 
 // The controller type to run in the "calculateControlOutput" function
-int controller_mode = CONTROLLER_MODE_LQR_RATE;
+int controller_mode = CONTROLLER_MODE_LQR_ANGLE_RATE_NESTED;
 
 // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
 std::vector<float> gainMatrixThrust_NineStateVector (9,0.0);
@@ -461,24 +501,45 @@ void convertIntoBodyFrame(float stateInertial[12], float (&stateBody)[12], float
 // CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
 float computeMotorPolyBackward(float thrust);
 
+
+
+
 // SETPOINT CHANGE CALLBACK
-void setpointCallback(const Setpoint& newSetpoint);
+//void setpointCallback(const Setpoint& newSetpoint);
+
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
+
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw);
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+//bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
+
+
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestGainChangeCallback(const FloatWithHeader& newGain);
 
 
 
 // LOAD PARAMETERS
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-std::string getParameterString(ros::NodeHandle& nodeHandle, std::string name);
-
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-void processFetchedParameters();
+// float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
+// void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
+// int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
+// void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
+// int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
+// bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
+// std::string getParameterString(ros::NodeHandle& nodeHandle, std::string name);
+
+
+
+//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
+//void fetchYamlParameters(ros::NodeHandle& nodeHandle);
+//void processFetchedParameters();
+
 
+void isReadyTuningControllerYamlCallback(const IntWithHeader & msg);
+void fetchTuningControllerYamlParameters(ros::NodeHandle& nodeHandle);
 
 
 // ******************************************************************************* //
diff --git a/pps_ws/src/d_fall_pps/param/TuningController.yaml b/pps_ws/src/d_fall_pps/param/TuningController.yaml
index 0bf1cb89..f427a45d 100644
--- a/pps_ws/src/d_fall_pps/param/TuningController.yaml
+++ b/pps_ws/src/d_fall_pps/param/TuningController.yaml
@@ -76,7 +76,7 @@ shouldDisplayDebugInfo : false
 #    -  Swaps between pitch set-points to test angle set-point response time
 #       i.e., this controller test the assumption that "the inner loop is infinitely fast"
 #
-controller_mode : 3
+controller_mode : 5
 
 
 # A flag for which estimator to use, defined as:
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 426be3b4..4df4b3d6 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -848,7 +848,7 @@ int main(int argc, char* argv[]) {
 	//   <param name="agentID" value="$(optenv ROS_NAMESPACE)" />
 	//   This line of code adds a parameter named "agentID" to the
 	//   "PPSClient" node.
-	// > Thus, to get access to this "studentID" paremeter, we first
+	// > Thus, to get access to this "agentID" paremeter, we first
 	//   need to get a handle to the "PPSClient" node within which this
 	//   controller service is nested.
 
diff --git a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
index 09bf7db1..c96fca2d 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
@@ -25,7 +25,7 @@
 //
 //
 //    DESCRIPTION:
-//    Place for students to implement their controller
+//    Allows for simple tuning of a P(I)D controller
 //
 //    ----------------------------------------------------------------------------------
 
@@ -914,13 +914,16 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 		for(int i = 0; i < 6; ++i)
 		{
 			// BODY FRAME Y CONTROLLER
-			lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
+			//lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// BODY FRAME X CONTROLLER
-			lqr_angleRateNested_prev_pitchAngle       -= gainMatrixPitchAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
+			//lqr_angleRateNested_prev_pitchAngle       -= gainMatrixPitchAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// > ALITUDE CONTROLLER (i.e., z-controller):
 			lqr_angleRateNested_prev_thrustAdjustment -= gainMatrixThrust_SixStateVector_50Hz[i] * stateErrorBody[i] * multiplier_vertical;
 		}
 
+		lqr_angleRateNested_prev_rollAngle  -= ( -1 * m_gain_P[i] * stateErrorBody[1] - m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[4] );
+		lqr_angleRateNested_prev_pitchAngle -= (      m_gain_P[i] * stateErrorBody[0] + m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[3] );
+
 		// BODY FRAME Z CONTROLLER
 		//lqr_angleRateNested_prev_yawAngle = setpoint[3];
 		lqr_angleRateNested_prev_yawAngle = stateErrorBody[8];
@@ -1237,45 +1240,79 @@ float computeMotorPolyBackward(float thrust)
 //    ----------------------------------------------------------------------------------
 
 // This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void setpointCallback(const Setpoint& newSetpoint)
-{
-    setpoint[0] = newSetpoint.x;
-    setpoint[1] = newSetpoint.y;
-    setpoint[2] = newSetpoint.z;
-    setpoint[3] = newSetpoint.yaw;
-}
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+// void setpointCallback(const Setpoint& newSetpoint)
+// {
+//     setpoint[0] = newSetpoint.x;
+//     setpoint[1] = newSetpoint.y;
+//     setpoint[2] = newSetpoint.z;
+//     setpoint[3] = newSetpoint.yaw;
+// }
 
 
 
 
+// REQUEST SETPOINT CHANGE CALLBACK
+// This function does NOT need to be edited 
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newSetpoint.shouldCheckForAgentID , newSetpoint.agentIDs );
 
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Call the function for actually setting the setpoint
+		setNewSetpoint(
+				newSetpoint.x,
+				newSetpoint.y,
+				newSetpoint.z,
+				newSetpoint.yaw
+			);
+	}
+}
 
 
+// CHANGE SETPOINT FUNCTION
+// This function does NOT need to be edited 
+void setNewSetpoint(float x, float y, float z, float yaw)
+{
+	// Put the new setpoint into the class variable
+	setpoint[0] = x;
+	setpoint[1] = y;
+	setpoint[2] = z;
+	setpoint[3] = yaw;
+
+	// Publish the change so that the network is updated
+	// (mainly the "flying agent GUI" is interested in
+	// displaying this change to the user)
+
+	// // Instantiate a local variable of type "SetpointWithHeader"
+	// SetpointWithHeader msg;
+	// // Fill in the setpoint
+	// msg.x   = x;
+	// msg.y   = y;
+	// msg.z   = z;
+	// msg.yaw = yaw;
+	// // Publish the message
+	// m_setpointChangedPublisher.publish(msg);
+}
 
 
 
 
+// REQUEST SETPOINT CHANGE CALLBACK
+// This function does NOT need to be edited 
+void requestGainChangeCallback(const FloatWithHeader& newGain)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForAgentID , newGain.agentIDs );
 
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		m_gain_P = newGain.data;
+	}
+}
 
 
 
@@ -1301,48 +1338,49 @@ void setpointCallback(const Setpoint& newSetpoint)
 //    ----------------------------------------------------------------------------------
 
 
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
+// LOADING OF YAML PARAMETERS
+// This function does NOT need to be edited 
+void isReadyTuningControllerYamlCallback(const IntWithHeader & msg)
 {
-	// Extract from the "msg" for which controller the and from where to fetch the YAML
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
 
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
+	// Continue if the message is relevant
+	if (isRevelant)
 	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[TUNING CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR:
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
 		{
-			// Let the user know that this message was received
-			ROS_INFO("[TUNING CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[TUNING CONTROLLER] Now fetching the TuningController 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("[TUNING CONTROLLER] Now fetching the TuningController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
 
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
+			default:
+			{
+				ROS_ERROR("[TUNING CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
 		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchTuningControllerYamlParameters(nodeHandle_to_use);
 	}
 }
 
@@ -1350,49 +1388,49 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 // This function CAN BE edited for successful completion of the PPS 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)
+void fetchTuningControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
 	// Here we load the parameters that are specified in the CustomController.yaml file
 
-	// Add the "CustomController" namespace to the "nodeHandle"
-	ros::NodeHandle nodeHandle_for_TuningController(nodeHandle, "TuningController");
+	// Add the "TuningController" namespace to the "nodeHandle"
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "TuningController");
 
 
 	// ******************************************************************************* //
 	// PARAMETERS SPECIFIC TO THE TUNING CONTROL FEATURE
 
 	/// Setpoint for the HORIZONTAL test
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_horizontal_setpoint1", test_horizontal_setpoint1, 4);
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_horizontal_setpoint2", test_horizontal_setpoint2, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_horizontal_setpoint1", test_horizontal_setpoint1, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_horizontal_setpoint2", test_horizontal_setpoint2, 4);
 
 	// Setpoint for the VERTICAL test
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_vertical_setpoint1", test_vertical_setpoint1, 4);
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_vertical_setpoint2", test_vertical_setpoint2, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_vertical_setpoint1", test_vertical_setpoint1, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_vertical_setpoint2", test_vertical_setpoint2, 4);
 
 	// Setpoint for the HEADING test
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_heading_setpoint1", test_heading_setpoint1, 4);
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_heading_setpoint2", test_heading_setpoint2, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_heading_setpoint1", test_heading_setpoint1, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_heading_setpoint2", test_heading_setpoint2, 4);
 
 	// Setpoint for the ALL test
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_all_setpoint1", test_all_setpoint1, 4);
-	getParameterFloatVector(nodeHandle_for_TuningController, "test_all_setpoint2", test_all_setpoint2, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_all_setpoint1", test_all_setpoint1, 4);
+	getParameterFloatVector(nodeHandle_for_paramaters, "test_all_setpoint2", test_all_setpoint2, 4);
 
 	// Parameters for flying in a circle
-	test_circle_radius = getParameterFloat(nodeHandle_for_TuningController, "test_circle_radius");
-	test_circle_seconds_per_rev = getParameterFloat(nodeHandle_for_TuningController, "test_circle_seconds_per_rev");
-	test_circle_height = getParameterFloat(nodeHandle_for_TuningController, "test_circle_height");
-	test_circle_time_to_reach_start = getParameterFloat(nodeHandle_for_TuningController, "test_circle_time_to_reach_start");
-	test_circle_pirouette_per_rev = getParameterFloat(nodeHandle_for_TuningController, "test_circle_pirouette_per_rev");
+	test_circle_radius = getParameterFloat(nodeHandle_for_paramaters, "test_circle_radius");
+	test_circle_seconds_per_rev = getParameterFloat(nodeHandle_for_paramaters, "test_circle_seconds_per_rev");
+	test_circle_height = getParameterFloat(nodeHandle_for_paramaters, "test_circle_height");
+	test_circle_time_to_reach_start = getParameterFloat(nodeHandle_for_paramaters, "test_circle_time_to_reach_start");
+	test_circle_pirouette_per_rev = getParameterFloat(nodeHandle_for_paramaters, "test_circle_pirouette_per_rev");
 
 	// Multipliers for the HORIZONTAL contorller
-	multiplier_horizontal_min = getParameterFloat(nodeHandle_for_TuningController, "multiplier_horizontal_min");
-	multiplier_horizontal_max = getParameterFloat(nodeHandle_for_TuningController, "multiplier_horizontal_max");
+	multiplier_horizontal_min = getParameterFloat(nodeHandle_for_paramaters, "multiplier_horizontal_min");
+	multiplier_horizontal_max = getParameterFloat(nodeHandle_for_paramaters, "multiplier_horizontal_max");
 	// Multipliers for the VERTICAL contorller
-	multiplier_vertical_min = getParameterFloat(nodeHandle_for_TuningController, "multiplier_vertical_min");
-	multiplier_vertical_max = getParameterFloat(nodeHandle_for_TuningController, "multiplier_vertical_max");
+	multiplier_vertical_min = getParameterFloat(nodeHandle_for_paramaters, "multiplier_vertical_min");
+	multiplier_vertical_max = getParameterFloat(nodeHandle_for_paramaters, "multiplier_vertical_max");
 	// Multipliers for the HEADING contorller
-	multiplier_heading_min = getParameterFloat(nodeHandle_for_TuningController, "multiplier_heading_min");
-	multiplier_heading_max = getParameterFloat(nodeHandle_for_TuningController, "multiplier_heading_max");
+	multiplier_heading_min = getParameterFloat(nodeHandle_for_paramaters, "multiplier_heading_min");
+	multiplier_heading_max = getParameterFloat(nodeHandle_for_paramaters, "multiplier_heading_max");
 
 	// // DEBUGGING: Print out one of the parameters that was loaded
 	ROS_INFO_STREAM("[TUNING CONTROLLER] DEBUGGING: the fetched TuningController/multiplier_horizontal_min = " << multiplier_horizontal_min);
@@ -1402,76 +1440,76 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 
 
 	// > The mass of the crazyflie
-	cf_mass = getParameterFloat(nodeHandle_for_TuningController , "mass");
+	cf_mass = getParameterFloat(nodeHandle_for_paramaters , "mass");
 
 	// Display one of the YAML parameters to debug if it is working correctly
 	//ROS_INFO_STREAM("DEBUGGING: mass leaded from loacl file = " << cf_mass );
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	vicon_frequency = getParameterFloat(nodeHandle_for_TuningController, "vicon_frequency");
+	vicon_frequency = getParameterFloat(nodeHandle_for_paramaters, "vicon_frequency");
 
 	// > The frequency at which the "computeControlOutput" is being called, as determined
 	//   by the frequency at which the Vicon system provides position and attitude data
-	control_frequency = getParameterFloat(nodeHandle_for_TuningController, "control_frequency");
+	control_frequency = getParameterFloat(nodeHandle_for_paramaters, "control_frequency");
 
 	// > The co-efficients of the quadratic conversation from 16-bit motor command to
 	//   thrust force in Newtons
-	getParameterFloatVector(nodeHandle_for_TuningController, "motorPoly", motorPoly, 3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", motorPoly, 3);
 
 	// > The boolean for whether to execute the convert into body frame function
-	shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_TuningController, "shouldPerformConvertIntoBodyFrame");
+	shouldPerformConvertIntoBodyFrame = getParameterBool(nodeHandle_for_paramaters, "shouldPerformConvertIntoBodyFrame");
 
 	// Boolean indiciating whether the "Debug Message" of this agent should be published or not
-	shouldPublishDebugMessage = getParameterBool(nodeHandle_for_TuningController, "shouldPublishDebugMessage");
+	shouldPublishDebugMessage = getParameterBool(nodeHandle_for_paramaters, "shouldPublishDebugMessage");
 
 	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-	shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_TuningController, "shouldDisplayDebugInfo");
+	shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paramaters, "shouldDisplayDebugInfo");
 
 
 	// THE CONTROLLER GAINS:
 
 	// A flag for which controller to use:
-	controller_mode = getParameterInt( nodeHandle_for_TuningController , "controller_mode" );
+	controller_mode = getParameterInt( nodeHandle_for_paramaters , "controller_mode" );
 
 	// A flag for which estimator to use:
-	estimator_method = getParameterInt( nodeHandle_for_TuningController , "estimator_method" );
+	estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );
 
 	// The LQR Controller parameters for "LQR_MODE_RATE"
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixThrust_NineStateVector", gainMatrixThrust_NineStateVector, 9);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixRollRate",               gainMatrixRollRate,               9);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixPitchRate",              gainMatrixPitchRate,              9);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixYawRate",                gainMatrixYawRate,                9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_NineStateVector", gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate",               gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate",              gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate",                gainMatrixYawRate,                9);
 	
 	// The LQR Controller parameters for "LQR_MODE_ANGLE"
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixThrust_SixStateVector",  gainMatrixThrust_SixStateVector,  6);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixRollAngle",              gainMatrixRollAngle,              6);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixPitchAngle",             gainMatrixPitchAngle,             6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_SixStateVector",  gainMatrixThrust_SixStateVector,  6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollAngle",              gainMatrixRollAngle,              6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchAngle",             gainMatrixPitchAngle,             6);
 	
 	// The LQR Controller parameters for "LQR_MODE_ANGLE_RATE_NESTED"
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixThrust_SixStateVector_50Hz",  gainMatrixThrust_SixStateVector_50Hz,  6);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixRollAngle_50Hz",              gainMatrixRollAngle_50Hz,              6);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixPitchAngle_50Hz",             gainMatrixPitchAngle_50Hz,             6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_SixStateVector_50Hz",  gainMatrixThrust_SixStateVector_50Hz,  6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollAngle_50Hz",              gainMatrixRollAngle_50Hz,              6);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchAngle_50Hz",             gainMatrixPitchAngle_50Hz,             6);
 
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixRollRate_Nested",             gainMatrixRollRate_Nested,             3);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixPitchRate_Nested",            gainMatrixPitchRate_Nested,            3);
-	getParameterFloatVector(nodeHandle_for_TuningController, "gainMatrixYawRate_Nested",              gainMatrixYawRate_Nested,              3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate_Nested",             gainMatrixRollRate_Nested,             3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate_Nested",            gainMatrixPitchRate_Nested,            3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate_Nested",              gainMatrixYawRate_Nested,              3);
 
 	
 	// 16-BIT COMMAND LIMITS
-	cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_TuningController, "command_sixteenbit_min");
-	cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_TuningController, "command_sixteenbit_max");
+	cmd_sixteenbit_min = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_min");
+	cmd_sixteenbit_max = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_max");
 
 
 	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 	// > For the (x,y,z) position
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_positions",  PMKF_Ahat_row1_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_positions",  PMKF_Ahat_row2_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_positions"     ,  PMKF_Kinf_for_positions     ,  2);
 	// > For the (roll,pitch,yaw) angles
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_TuningController, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_angles",  PMKF_Ahat_row1_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_angles",  PMKF_Ahat_row2_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_angles"     ,  PMKF_Kinf_for_angles     ,  2);
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
@@ -1480,15 +1518,8 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
 
 	// Call the function that computes details an values that are needed from these
 	// parameters loaded above
-	processFetchedParameters();
-}
+	//processFetchedParameters();
 
-
-// This function CAN BE edited for successful completion of the PPS 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()
-{
 	// Compute the feed-forward force that we need to counteract gravity (i.e., mg)
 	// > in units of [Newtons]
 	gravity_force         = cf_mass * 9.81/(1000);
@@ -1503,82 +1534,6 @@ void processFetchedParameters()
 
 
 
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
-//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
-//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
-//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
-//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
-//    ----------------------------------------------------------------------------------
-
-
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        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 getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val.size();
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
-{
-    bool val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-// This function DOES NOT NEED TO BE edited for successful completion of the PPS exercise
-std::string getParameterString(ros::NodeHandle& nodeHandle, std::string name)
-{
-	std::string val;
-	if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}    
 
 
 
@@ -1598,117 +1553,188 @@ int main(int argc, char* argv[]) {
     // Starting the ROS-node
     ros::init(argc, argv, "TuningControllerService");
 
-    // 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 "StudentControllerService" node
-    // > This should be something like: "/dfall/agentXXX"
-    std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[TUNING CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
-
-    // Get the agent ID as the "ROS_NAMESPACE" this computer.
-    // NOTES:
-    // > 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"
-    // > 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");
-    // Get the value of the "studentID" parameter into the instance variable "my_agentID"
-    if(!PPSClient_nodeHandle.getParam("agentID", my_agentID))
-    {
-    	// Throw an error if the student ID parameter could not be obtained
-		ROS_ERROR("[TUNING CONTROLLER] Failed to get agentID from PPSClient");
-	}
+    // 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("~");
 
+    // AGENT ID AND COORDINATOR ID
 
-	// *********************************************************************************
-	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
+	// 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
+	//   "PPSClient" node.
+	// > Thus, to get access to this "agentID" paremeter, we first
+	//   need to get a handle to the "PPSClient" node within which this
+	//   controller service is nested.
 
 
-	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+	// Get the ID of the agent and its coordinator
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/PPSClient" , &m_agentID , &m_coordID);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[TUNING CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[TUNING CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+	}
+
 
-	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
-    // namespace string for the parameter service that is running on the machine of this
-    // agent
-    namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService";
+	
 
-    // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+	// 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";
+
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[TUNING CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[TUNING CONTROLLER] 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+
+
+
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber safeContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "TuningController", 1, isReadyTuningControllerYamlCallback);
+	ros::Subscriber safeContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("TuningController", 1, isReadyTuningControllerYamlCallback);
+
+
+
+	// GIVE YAML VARIABLES AN INITIAL VALUE
+	// This can be done either here or as part of declaring the
+	// variables in the header file
+
+	// // > the mass of the crazyflie, in [grams]
+	// yaml_cf_mass_in_grams = 25.0;
+	// // > the coefficients of the 16-bit command to thrust conversion
+	// yaml_motorPoly[0] = 5.484560e-4;
+	// yaml_motorPoly[1] = 1.032633e-6;
+	// yaml_motorPoly[2] = 2.130295e-11;
+	// // > the frequency at which the controller is running
+	// yaml_control_frequency = 200.0;
+	// // > the default setpoint, the ordering is (x,y,z,yaw),
+	// //   with units [meters,meters,meters,radians]
+	// yaml_default_setpoint[0] = 0.0;
+	// yaml_default_setpoint[1] = 0.0;
+	// yaml_default_setpoint[2] = 0.4;
+	// yaml_default_setpoint[3] = 0.0;
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// The yaml files for the controllers are not added to
+	// "Parameter Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// service call containing the filename of the *.yaml file,
+	// and then a message will be received on the above subscribers
+	// when the paramters are ready.
+	// > NOTE IMPORTANTLY that by using a serice client
+	//   we stall the availability of this node until the
+	//   paramter service is ready
+
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "TuningController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyTuningControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+		// Inform the user
+		ROS_ERROR("[TUNING CONTROLLER] The request load yaml file service call failed.");
+	}
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
 
-    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService")
-    //       is very important because it specifies that the name is global
-    namespace_to_coordinator_parameter_service = "/ParameterService";
 
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
-    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-    
 
-    // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
-    // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
-    // and calls the class function "yamlReadyForFetchCallback" each time a message is
-    // received on this topic and the message is passed as an input argument to the
-    // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
-    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
 
-    // PRINT OUT SOME INFORMATION
+	// // Subscribe to the message that activates the tests
+	// ros::Subscriber tuningActivateTestSubscriber = nodeHandle.subscribe("ActivateTest", 1, activateTestCallback);
 
-    // Let the user know what namespaces are being used for linking to the parameter service
-    ROS_INFO_STREAM("[TUNING CONTROLLER] The namespace string for accessing the Paramter Services are:");
-    ROS_INFO_STREAM("[TUNING CONTROLLER] namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
-    ROS_INFO_STREAM("[TUNING CONTROLLER] namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
+	// // Subscribe to the message that changes the gains
+	// ros::Subscriber tuningHorizontalGainSubscriber = nodeHandle.subscribe("HorizontalGain", 1, horizontalGainCallback);
+	// ros::Subscriber tuningVerticalGainSubscriber   = nodeHandle.subscribe("VerticalGain",   1, verticalGainCallback);
+	// ros::Subscriber tuningHeadingGainSubscriber    = nodeHandle.subscribe("HeadingGain",    1, headingGainCallback);
 
 
-    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
 
-	// Call the class function that loads the parameters for this class.
-    fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
-    // *********************************************************************************
 
 
+    // Instantiate the class variable "m_debugPublisher" to be a
+    // "ros::Publisher". This variable advertises under the name
+    // "DebugTopic" and is a message with the structure defined
+    //  in the file "DebugMsg.msg" (located in the "msg" folder).
+    m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-    // Subscribe to the message that activates the tests
-	ros::Subscriber tuningActivateTestSubscriber = nodeHandle.subscribe("ActivateTest", 1, activateTestCallback);
+    // Instantiate the local variable "requestSetpointChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestSetpointChange" topic and calls the class function
+	// "requestSetpointChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the setpoint is changed
+	// by the user.
+	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
 
-	// Subscribe to the message that changes the gains
-	ros::Subscriber tuningHorizontalGainSubscriber = nodeHandle.subscribe("HorizontalGain", 1, horizontalGainCallback);
-	ros::Subscriber tuningVerticalGainSubscriber   = nodeHandle.subscribe("VerticalGain",   1, verticalGainCallback);
-	ros::Subscriber tuningHeadingGainSubscriber    = nodeHandle.subscribe("HeadingGain",    1, headingGainCallback);
+	// Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("TuningControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
 
 
 
-    // Instantiate the instance variable "debugPublisher" to be a "ros::Publisher" that
-    // advertises under the name "DebugTopic" and is a message with the structure
-    // defined in the file "DebugMsg.msg" (located in the "msg" folder).
-    debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
 
-    // Instantiate the local variable "setpointSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "Setpoint" topic and calls the class function
-    // "setpointCallback" each time a messaged is received on this topic and the message
-    // is passed as an input argument to the "setpointCallback" class function.
-    //ros::Subscriber setpointSubscriber = nodeHandle.subscribe("Setpoint", 1, setpointCallback);
 
     // Instantiate the local variable "service" to be a "ros::ServiceServer" type
-    // variable that advertises the service called "CustomController". This service has
+    // variable that advertises the service called "TuningController". This service has
     // the input-output behaviour defined in the "Controller.srv" file (located in the
     // "srv" folder). This service, when called, is provided with the most recent
     // measurement of the Crazyflie and is expected to respond with the control action
@@ -1717,11 +1743,15 @@ int main(int argc, char* argv[]) {
     // of this service the "calculateControlOutput" function is called.
     ros::ServiceServer service = nodeHandle.advertiseService("TuningController", calculateControlOutput);
 
+
+
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
     // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
     //     "using namespace d_fall_pps;"
     // in the "DEFINES" section at the top of this file.
-    ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
+
 
     // Print out some information to the user.
     ROS_INFO("[TUNING CONTROLLER] Service ready :-)");
-- 
GitLab


From bbe5f8418fba690ccc24d13b05a459808f082b1e Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 10:57:28 +0100
Subject: [PATCH 48/87] Tuning Controller Service now tested and working
 (although the z-controller is a bit sloppy)

---
 pps_ws/src/d_fall_pps/CMakeLists.txt          |  3 ++
 .../include/tuningcontrollertab.h             |  4 +-
 .../flyingAgentGUI/src/controllertabs.cpp     | 15 +++++++
 .../src/tuningcontrollertab.cpp               | 16 ++++----
 .../include/nodes/TuningControllerService.h   | 15 ++++---
 .../d_fall_pps/param/TuningController.yaml    |  4 +-
 pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp |  1 +
 .../src/nodes/TuningControllerService.cpp     | 39 +++++++++++++++----
 8 files changed, 73 insertions(+), 24 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/pps_ws/src/d_fall_pps/CMakeLists.txt
index fd145d0a..77da3b66 100755
--- a/pps_ws/src/d_fall_pps/CMakeLists.txt
+++ b/pps_ws/src/d_fall_pps/CMakeLists.txt
@@ -136,6 +136,7 @@ set(SRC_HDRS_QOBJECT_FLYING_AGENT_GUI
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/safecontrollertab.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/studentcontrollertab.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/topbanner.h
+  ${FLYING_AGENT_GUI_LIB_PATH_INC}/tuningcontrollertab.h
   )
 # Flying Agent GUI -- wrap UI file and QOBJECT files
 qt5_wrap_ui(UIS_HDRS_FLYING_AGENT_GUI
@@ -150,6 +151,7 @@ qt5_wrap_ui(UIS_HDRS_FLYING_AGENT_GUI
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/safecontrollertab.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/studentcontrollertab.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/topbanner.ui
+  ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/tuningcontrollertab.ui
   )
 qt5_wrap_cpp(SRC_MOC_HDRS_FLYING_AGENT_GUI ${SRC_HDRS_QOBJECT_FLYING_AGENT_GUI})
 # Flying Agent GUI -- wrap resource file qrc->rcc
@@ -392,6 +394,7 @@ set(MY_CPP_SOURCES_FLYING_AGENT_GUI         # compilation of sources
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/safecontrollertab.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/studentcontrollertab.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/topbanner.cpp
+    ${FLYING_AGENT_GUI_LIB_PATH_SRC}/tuningcontrollertab.cpp
     )
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index e26851eb..a5fa7abc 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -39,8 +39,8 @@
 #endif
 
 
-#define P_GAIN_MIN_GUI  0.10
-#define P_GAIN_MAX_GUI  1.00
+#define P_GAIN_MIN_GUI  0.05
+#define P_GAIN_MAX_GUI  1.60
 #define P_TO_D_GAIN_RATIO_GUI 0.6
 
 #define DECIMAL_PLACES_POSITION_MEASURED 3
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 9b112789..7d9880e7 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -36,6 +36,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->picker_controller_tab_widget , &PickerControllerTab::setMeasuredPose
         );
 
+    QObject::connect(
+            this , &ControllerTabs::measuredPoseValueChanged ,
+            ui->tuning_controller_tab_widget , &TuningControllerTab::setMeasuredPose
+        );
+
 
 
     // CONNECT THE "MEASUREMENTS UNAVAILABLE" SIGNAL TO
@@ -55,6 +60,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->picker_controller_tab_widget , &PickerControllerTab::poseDataUnavailableSlot
         );
 
+    QObject::connect(
+            this , &ControllerTabs::poseDataUnavailableSignal ,
+            ui->tuning_controller_tab_widget , &TuningControllerTab::poseDataUnavailableSlot
+        );
+
 
     // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
     // WITH THE LIST OF AGENT IDs TO COORDINATE
@@ -76,6 +86,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->picker_controller_tab_widget , &PickerControllerTab::setAgentIDsToCoordinate
         );
 
+    QObject::connect(
+            this , &ControllerTabs::agentIDsToCoordinateChanged ,
+            ui->tuning_controller_tab_widget , &TuningControllerTab::setAgentIDsToCoordinate
+        );
+
     
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index 7fa20851..24ea87a3 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -350,7 +350,7 @@ void TuningControllerTab::publishGain(float new_gain)
     d_fall_pps::FloatWithHeader msg;
 
     // Fill the header of the message
-    fillSetpointMessageHeader( msg );
+    fillFloatMessageHeader( msg );
 
     // Fill in the gain value
     msg.data = new_gain;
@@ -463,10 +463,10 @@ void TuningControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
         setpointChangedSubscriber.shutdown();
 
         // Set information back to the default
-        ui->lineEdit_setpoint_current_x->setText("xx.xx");
-        ui->lineEdit_setpoint_current_y->setText("xx.xx");
-        ui->lineEdit_setpoint_current_z->setText("xx.xx");
-        ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
+        ui->lineEdit_setpoint->setText("xx.xx");
+        //ui->lineEdit_setpoint_current_y->setText("xx.xx");
+        //ui->lineEdit_setpoint_current_z->setText("xx.xx");
+        //ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
 
     }
 #endif
@@ -537,7 +537,7 @@ void TuningControllerTab::fillFloatMessageHeader( d_fall_pps::FloatWithHeader &
     {
         case TYPE_AGENT:
         {
-            msg.shouldCheckForAgentID = false;
+            msg.shouldCheckForID = false;
             break;
         }
         case TYPE_COORDINATOR:
@@ -545,7 +545,7 @@ void TuningControllerTab::fillFloatMessageHeader( d_fall_pps::FloatWithHeader &
             // Lock the mutex
             m_agentIDs_toCoordinate_mutex.lock();
             // Add the "coordinate all" flag
-            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            msg.shouldCheckForID = !(m_shouldCoordinateAll);
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
@@ -561,7 +561,7 @@ void TuningControllerTab::fillFloatMessageHeader( d_fall_pps::FloatWithHeader &
 
         default:
         {
-            msg.shouldCheckForAgentID = true;
+            msg.shouldCheckForID = true;
             ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
             break;
         }
diff --git a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
index f6ec1a02..7184651d 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
@@ -215,6 +215,8 @@ float m_gain_P_to_D_ratio = 0.6;
 
 
 
+
+
 // ******************************************************************************* //
 // VARIABLES SPECIFIC TO THE TUNING CONTROL FEATURE
 
@@ -398,13 +400,13 @@ std::vector<float> PMKF_Kinf_for_angles         (2,0.0);
 
 // VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
 // > For the paramter service of this agent
-std::string namespace_to_own_agent_parameter_service;
+std::string m_namespace_to_own_agent_parameter_service;
 // > For the parameter service of the coordinator
-std::string namespace_to_coordinator_parameter_service;
+std::string m_namespace_to_coordinator_parameter_service;
 
 
 // ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
-ros::Publisher debugPublisher;
+ros::Publisher m_debugPublisher;
 
 
 // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
@@ -425,8 +427,11 @@ bool shouldDisplayDebugInfo = false;
 // VARIABLES RELATING TO PUBLISHING CURRENT POSITION AND FOLLOWING ANOTHER AGENT'S
 // POSITION
 
-// The ID of this agent, i.e., the ID of this compute
-int my_agentID = 0;
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// The ID of the agent that can coordinate this node
+int m_coordID;
 
 
 
diff --git a/pps_ws/src/d_fall_pps/param/TuningController.yaml b/pps_ws/src/d_fall_pps/param/TuningController.yaml
index f427a45d..0baaf04e 100644
--- a/pps_ws/src/d_fall_pps/param/TuningController.yaml
+++ b/pps_ws/src/d_fall_pps/param/TuningController.yaml
@@ -40,7 +40,7 @@ multiplier_heading_max : 3.0
 
 
 # Mass of the crazyflie
-mass : 29
+mass : 30
 
 # Frequency of the controller, in hertz
 vicon_frequency : 200
@@ -93,7 +93,7 @@ estimator_method : 1
 
 
 # The LQR Controller parameters for "mode = 3"
-gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00]
+gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.76, 0.00, 0.00, 0.32, 0.00, 0.00, 0.00]
 gainMatrixRollRate                  :  [ 0.00,-1.80, 0.00, 0.00,-1.38, 0.00, 5.20, 0.00, 0.00]
 gainMatrixPitchRate                 :  [ 1.80, 0.00, 0.00, 1.38, 0.00, 0.00, 0.00, 5.20, 0.00]
 gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30]
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index 90d259e0..a92c51dd 100755
--- a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -739,6 +739,7 @@ void setInstantController(int controller) //for right now, temporal use
             break;
         case TUNING_CONTROLLER:
             loadTuningController();
+            break;
         case PICKER_CONTROLLER:
             loadPickerController();
             break;
diff --git a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
index c96fca2d..289e3adb 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
@@ -914,15 +914,15 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 		for(int i = 0; i < 6; ++i)
 		{
 			// BODY FRAME Y CONTROLLER
-			//lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
+			lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// BODY FRAME X CONTROLLER
 			//lqr_angleRateNested_prev_pitchAngle       -= gainMatrixPitchAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// > ALITUDE CONTROLLER (i.e., z-controller):
 			lqr_angleRateNested_prev_thrustAdjustment -= gainMatrixThrust_SixStateVector_50Hz[i] * stateErrorBody[i] * multiplier_vertical;
 		}
 
-		lqr_angleRateNested_prev_rollAngle  -= ( -1 * m_gain_P[i] * stateErrorBody[1] - m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[4] );
-		lqr_angleRateNested_prev_pitchAngle -= (      m_gain_P[i] * stateErrorBody[0] + m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[3] );
+		//lqr_angleRateNested_prev_rollAngle  -= ( -1 * m_gain_P * stateErrorBody[1] - m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[4] );
+		lqr_angleRateNested_prev_pitchAngle -= (      m_gain_P * stateErrorBody[0] + m_gain_P * m_gain_P_to_D_ratio * stateErrorBody[3] );
 
 		// BODY FRAME Z CONTROLLER
 		//lqr_angleRateNested_prev_yawAngle = setpoint[3];
@@ -962,6 +962,17 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 	}
 
 
+
+	float thrustAdjustment_200Hz = 0.0;
+	// Perform the "-Kx" LQR computation for the rates and thrust:
+	for(int i = 0; i < 9; ++i)
+	{
+		// > ALITUDE CONTROLLER (i.e., z-controller):
+		thrustAdjustment_200Hz  -= gainMatrixThrust_NineStateVector[i] * stateErrorBody[i] * multiplier_vertical;
+	}
+
+
+
 	// UPDATE THE "RETURN" THE VARIABLE NAMED "response"
 
 	// Put the computed rates and thrust into the "response" variable
@@ -973,7 +984,7 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 	// > NOTE: remember that the thrust is commanded per motor, so you sohuld
 	//         consider whether the "thrustAdjustment" computed by your
 	//         controller needed to be divided by 4 or not.
-	float thrustAdjustment = lqr_angleRateNested_prev_thrustAdjustment / 4.0;
+	float thrustAdjustment = thrustAdjustment_200Hz / 4.0;
 	// > NOTE: the "gravity_force_quarter" value was already divided by 4 when
 	//         it was loaded/processes from the .yaml file.
 	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + gravity_force_quarter);
@@ -1049,7 +1060,7 @@ void construct_and_publish_debug_message(Controller::Request &request, Controlle
 	// debugMsg.value_10 = your_variable_name;
 
 	// Publish the "debugMsg"
-	debugPublisher.publish(debugMsg);
+	m_debugPublisher.publish(debugMsg);
 }
 
 
@@ -1305,12 +1316,14 @@ void setNewSetpoint(float x, float y, float z, float yaw)
 void requestGainChangeCallback(const FloatWithHeader& newGain)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForAgentID , newGain.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForID , newGain.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
 	{
 		m_gain_P = newGain.data;
+
+		ROS_INFO_STREAM("[TUNING CONTROLLER] proportional gain changed to " << m_gain_P );
 	}
 }
 
@@ -1558,6 +1571,10 @@ int main(int argc, char* argv[]) {
 	// node handle assigned to this variable.
 	ros::NodeHandle nodeHandle("~");
 
+	// Get the namespace of this "TuningControllerService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[TUNING CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
+
     // AGENT ID AND COORDINATOR ID
 
 	// NOTES:
@@ -1729,7 +1746,15 @@ int main(int argc, char* argv[]) {
 	// And now we can instantiate the subscriber:
 	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("TuningControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
 
-
+	// Instantiate the local variable "requestGainChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestGainChange" topic and calls the class function
+	// "requestGainChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the gain is changed
+	// by the user.
+	ros::Subscriber requestGainChangeSubscriber = nodeHandle.subscribe("RequestGainChange", 1, requestGainChangeCallback);
 
 
 
-- 
GitLab


From 52134eb8f5f842822fb38ff162cfe34b5d28c9a2 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 11:26:21 +0100
Subject: [PATCH 49/87] Adjust Controller Tabs GUI so that the Mocap data is
 converted to the local frame

---
 .../flyingAgentGUI/include/controllertabs.h   | 11 ++++
 .../flyingAgentGUI/src/controllertabs.cpp     | 53 ++++++++++++++++++-
 2 files changed, 63 insertions(+), 1 deletion(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index c159378e..b77c7ff4 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -20,6 +20,9 @@
 //#include "d_fall_pps/SetpointWithHeader.h"
 #include "d_fall_pps/CrazyflieData.h"
 #include "d_fall_pps/ViconData.h"
+#include "d_fall_pps/AreaBounds.h"
+#include "d_fall_pps/CrazyflieContext.h"
+#include "d_fall_pps/CMQuery.h"
 
 // Include the shared definitions
 //#include "nodes/Constants.h"
@@ -102,11 +105,19 @@ private:
     // --------------------------------------------------- //
     // PRIVATE VARIABLES FOR ROS
 
+    // > For the "context" of this agent
+    d_fall_pps::CrazyflieContext m_context;
+    d_fall_pps::AreaBounds m_area;
+
     // SUBSRIBER
     // > For the pose data from a motion capture system
     ros::Subscriber m_poseDataSubscriber;
     // > For the controller that is currently operating
     ros::Subscriber controllerUsedSubscriber;
+
+    // > For changes in the database that defines {agentID,cfID,flying zone} links
+    //ros::Subscriber databaseChangedSubscriber;
+    ros::ServiceClient centralManagerDatabaseService;
 #endif
 
 
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 7d9880e7..8be696ac 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -132,6 +132,18 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     }
 
 
+
+    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+    ros::NodeHandle dfall_root_nodeHandle("/dfall");
+
+    // > Publisher for the emergency stop button
+    //emergencyStopPublisher = dfall_root_nodeHandle.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
+
+    // > For changes in the database that defines {agentID,cfID,flying zone} links
+    //databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
+    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+
+
 #endif
 
 }
@@ -218,8 +230,34 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
         m_should_search_pose_data_for_object_name = true;
         // Inform the user
         #ifdef CATKIN_MAKE
-            ROS_INFO_STREAM("[CONTROLLER TABS GUI] now emitting data for object named: " << m_object_name_for_emitting_pose_data );
+            ROS_INFO_STREAM("[CONTROLLER TABS GUI] now emitting data for object named: " << m_object_name_for_emitting_pose_data << ", with ID = " << m_ID );
+        #endif
+
+
+        #ifdef CATKIN_MAKE
+        // Get also the context
+        d_fall_pps::CMQuery contextCall;
+        contextCall.request.studentID = m_ID;
+
+        centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
+
+        if(centralManagerDatabaseService.call(contextCall))
+        {
+            m_context = contextCall.response.crazyflieContext;
+            m_area = m_context.localArea;
+            ROS_INFO_STREAM("[CONTROLLER TABS GUI] AreaBounds:\n" << m_area);
+
+            //qstr_crazyflie_name.append(QString::fromStdString(m_context.crazyflieName));
+
+            //m_object_name_for_emitting_pose_data = QString::fromStdString(my_context.crazyflieName);
+
+        }
+        else
+        {
+            ROS_ERROR_STREAM("[CONTROLLER TABS GUI] Failed to load context for agentID = " << m_ID);
+        }
         #endif
+
     }
     m_should_search_pose_data_for_object_name_mutex.unlock();
 }
@@ -239,6 +277,19 @@ void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& vicon
 
             if(pose_in_global_frame.crazyflieName == m_object_name_for_emitting_pose_data)
             {
+
+                // Convert it into the local frame
+                float originX = (m_area.xmin + m_area.xmax) / 2.0;
+                float originY = (m_area.ymin + m_area.ymax) / 2.0;
+                
+                pose_in_global_frame.x -= originX;
+                pose_in_global_frame.y -= originY;
+
+                // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
+                //float originZ = 0.0;
+                // float originZ = (area.zmin + area.zmax) / 2.0;
+                //pose_in_global_frame.z -= originZ;
+
                 emit measuredPoseValueChanged(
                         pose_in_global_frame.x,
                         pose_in_global_frame.y,
-- 
GitLab


From 91a11def6badf2bab80293b7579d7469c5fe5954 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Feb 2019 11:33:53 +0100
Subject: [PATCH 50/87] Fixed small error in Tuning Controller relating to gain
 multipliers

---
 .../src/nodes/TuningControllerService.cpp          | 14 +++++++++-----
 1 file changed, 9 insertions(+), 5 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
index 289e3adb..05ff0300 100644
--- a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
@@ -914,7 +914,7 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 		for(int i = 0; i < 6; ++i)
 		{
 			// BODY FRAME Y CONTROLLER
-			lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
+			//lqr_angleRateNested_prev_rollAngle        -= gainMatrixRollAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// BODY FRAME X CONTROLLER
 			//lqr_angleRateNested_prev_pitchAngle       -= gainMatrixPitchAngle_50Hz[i] * stateErrorBody[i] * multiplier_horizontal;
 			// > ALITUDE CONTROLLER (i.e., z-controller):
@@ -926,7 +926,7 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 
 		// BODY FRAME Z CONTROLLER
 		//lqr_angleRateNested_prev_yawAngle = setpoint[3];
-		lqr_angleRateNested_prev_yawAngle = stateErrorBody[8];
+		//lqr_angleRateNested_prev_yawAngle = stateErrorBody[8];
 
 
 	}
@@ -954,11 +954,11 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 	for(int i = 0; i < 4; ++i)
 	{
 		// BODY FRAME Y CONTROLLER
-		rollRate_forResponse  -= gainMatrixRollRate_Nested[i]  * temp_stateAngleError[i];
+		//rollRate_forResponse  -= gainMatrixRollRate_Nested[i]  * temp_stateAngleError[i];
 		// BODY FRAME X CONTROLLER
 		pitchRate_forResponse -= gainMatrixPitchRate_Nested[i] * temp_stateAngleError[i];
 		// BODY FRAME Z CONTROLLER
-		yawRate_forResponse   -= gainMatrixYawRate_Nested[i]   * temp_stateAngleError[i] * multiplier_heading;
+		//yawRate_forResponse   -= gainMatrixYawRate_Nested[i]   * temp_stateAngleError[i] * multiplier_heading;
 	}
 
 
@@ -967,8 +967,12 @@ void calculateControlOutput_viaLQRforAnglesRatesNested( float stateErrorBody[12]
 	// Perform the "-Kx" LQR computation for the rates and thrust:
 	for(int i = 0; i < 9; ++i)
 	{
+		// BODY FRAME Y CONTROLLER
+		rollRate_forResponse    -= gainMatrixRollRate[i] * stateErrorBody[i];
 		// > ALITUDE CONTROLLER (i.e., z-controller):
-		thrustAdjustment_200Hz  -= gainMatrixThrust_NineStateVector[i] * stateErrorBody[i] * multiplier_vertical;
+		thrustAdjustment_200Hz  -= gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
+		// BODY FRAME YAW CONTROLLER
+		yawRate_forResponse   -= gainMatrixYawRate[i] * stateErrorBody[i];
 	}
 
 
-- 
GitLab


From 35fdab8fadf35e262f72fc228a05da6e0e6f1ca4 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 7 Feb 2019 22:03:37 +0100
Subject: [PATCH 51/87] Changed workspace directory name from pps_ws to
 dfall_ws

---
 .gitignore                                    |  15 +-
 {pps_ws => dfall_ws}/.catkin_workspace        |   0
 {pps_ws => dfall_ws}/src/CMakeLists.txt       |   0
 .../src/d_fall_pps/CMakeLists.txt             |   0
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro        |   0
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc        |   0
 .../GUI_Qt/CrazyFlyGUI/images/center_rect.svg |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone.png       | Bin
 .../GUI_Qt/CrazyFlyGUI/images/drone.svg       |   0
 .../CrazyFlyGUI/images/drone_fixed_01.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_02.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_03.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_04.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_05.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_06.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_07.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_08.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_09.svg     |   0
 .../CrazyFlyGUI/images/drone_fixed_unk.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/include/CFLinker.h     |   0
 .../GUI_Qt/CrazyFlyGUI/include/centerMarker.h |   0
 .../GUI_Qt/CrazyFlyGUI/include/channelLUT.h   |   0
 .../CrazyFlyGUI/include/cornergrabber.h       |   0
 .../GUI_Qt/CrazyFlyGUI/include/crazyFly.h     |   0
 .../GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h |   0
 .../CrazyFlyGUI/include/crazyFlyZoneTab.h     |   0
 .../CrazyFlyGUI/include/globalDefinitions.h   |   0
 .../CrazyFlyGUI/include/mainguiwindow.h       |   0
 .../GUI_Qt/CrazyFlyGUI/include/marker.h       |   0
 .../CrazyFlyGUI/include/myGraphicsRectItem.h  |   0
 .../CrazyFlyGUI/include/myGraphicsScene.h     |   0
 .../CrazyFlyGUI/include/myGraphicsView.h      |   0
 .../include/rosNodeThread_for_managerGUI.h    |   0
 .../GUI_Qt/CrazyFlyGUI/include/tablePiece.h   |   0
 .../GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp       |   0
 .../GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp   |   0
 .../GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp     |   0
 .../GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp  |   0
 .../GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp       |   0
 .../GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp   |   0
 .../CrazyFlyGUI/src/crazyFlyZoneTab.cpp       |   0
 .../GUI_Qt/CrazyFlyGUI/src/main.cpp           |   0
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  |   0
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui   |   0
 .../GUI_Qt/CrazyFlyGUI/src/marker.cpp         |   0
 .../CrazyFlyGUI/src/myGraphicsRectItem.cpp    |   0
 .../CrazyFlyGUI/src/myGraphicsScene.cpp       |   0
 .../GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp |   0
 .../src/rosNodeThread_for_managerGUI.cpp      |   0
 .../GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp     |   0
 .../GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro  |   0
 .../GUI_Qt/flyingAgentGUI/flyingagentgui.qrc  |   0
 .../forms/connectstartstopbar.ui              |   0
 .../flyingAgentGUI/forms/controllertabs.ui    |   0
 .../flyingAgentGUI/forms/coordinator.ui       |   0
 .../flyingAgentGUI/forms/coordinatorrow.ui    |   0
 .../forms/defaultcontrollertab.ui             |   0
 .../forms/enablecontrollerloadyamlbar.ui      |   0
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |   0
 .../forms/pickercontrollertab.ui              |   0
 .../flyingAgentGUI/forms/safecontrollertab.ui |   0
 .../forms/studentcontrollertab.ui             |   0
 .../GUI_Qt/flyingAgentGUI/forms/topbanner.ui  |   0
 .../forms/tuningcontrollertab.ui              |   0
 .../flyingAgentGUI/images/battery_20.png      | Bin
 .../flyingAgentGUI/images/battery_40.png      | Bin
 .../flyingAgentGUI/images/battery_60.png      | Bin
 .../flyingAgentGUI/images/battery_80.png      | Bin
 .../flyingAgentGUI/images/battery_empty.png   | Bin
 .../flyingAgentGUI/images/battery_full.png    | Bin
 .../images/battery_unavailable.png            | Bin
 .../flyingAgentGUI/images/battery_unknown.png | Bin
 .../flyingAgentGUI/images/emergency_stop.png  | Bin
 .../images/flying_state_disabling.png         | Bin
 .../images/flying_state_enabling.png          | Bin
 .../images/flying_state_flying.png            | Bin
 .../images/flying_state_off.png               | Bin
 .../images/flying_state_unavailable.png       | Bin
 .../images/flying_state_unknown.png           | Bin
 .../flyingAgentGUI/images/rf_connected.png    | Bin
 .../flyingAgentGUI/images/rf_connecting.png   | Bin
 .../flyingAgentGUI/images/rf_disconnected.png | Bin
 .../include/Constants_for_Qt_compile.h        |   0
 ...PickerControllerConstants_for_Qt_compile.h |   0
 .../include/connectstartstopbar.h             |   0
 .../flyingAgentGUI/include/controllertabs.h   |   0
 .../flyingAgentGUI/include/coordinator.h      |   0
 .../flyingAgentGUI/include/coordinatorrow.h   |   0
 .../include/defaultcontrollertab.h            |   0
 .../include/enablecontrollerloadyamlbar.h     |   0
 .../flyingAgentGUI/include/mainwindow.h       |   0
 .../include/pickercontrollertab.h             |   0
 .../rosNodeThread_for_flyingAgentGUI.h        |   0
 .../include/safecontrollertab.h               |   0
 .../include/studentcontrollertab.h            |   0
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h |   0
 .../include/tuningcontrollertab.h             |   0
 .../src/connectstartstopbar.cpp               |   0
 .../flyingAgentGUI/src/controllertabs.cpp     |   0
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp |   0
 .../flyingAgentGUI/src/coordinatorrow.cpp     |   0
 .../src/defaultcontrollertab.cpp              |   0
 .../src/enablecontrollerloadyamlbar.cpp       |   0
 .../GUI_Qt/flyingAgentGUI/src/main.cpp        |   0
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |   0
 .../src/pickercontrollertab.cpp               |   0
 .../src/rosNodeThread_for_flyingAgentGUI.cpp  |   0
 .../flyingAgentGUI/src/safecontrollertab.cpp  |   0
 .../src/studentcontrollertab.cpp              |   0
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |   0
 .../src/tuningcontrollertab.cpp               |   0
 .../GUI_Qt/studentGUI/images/battery_20.png   | Bin
 .../GUI_Qt/studentGUI/images/battery_40.png   | Bin
 .../GUI_Qt/studentGUI/images/battery_60.png   | Bin
 .../GUI_Qt/studentGUI/images/battery_80.png   | Bin
 .../studentGUI/images/battery_empty.png       | Bin
 .../GUI_Qt/studentGUI/images/battery_full.png | Bin
 .../studentGUI/images/battery_unknown.png     | Bin
 .../images/flying_state_disabling.png         | Bin
 .../images/flying_state_enabling.png          | Bin
 .../studentGUI/images/flying_state_flying.png | Bin
 .../studentGUI/images/flying_state_off.png    | Bin
 .../images/flying_state_unknown.png           | Bin
 .../GUI_Qt/studentGUI/images/rf_connected.png | Bin
 .../studentGUI/images/rf_connecting.png       | Bin
 .../studentGUI/images/rf_disconnected.png     | Bin
 .../GUI_Qt/studentGUI/include/MainWindow.h    |   0
 .../include/rosNodeThread_for_studentGUI.h    |   0
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      |   0
 .../GUI_Qt/studentGUI/src/MainWindow.ui       |   0
 .../d_fall_pps/GUI_Qt/studentGUI/src/main.cpp |   0
 .../src/rosNodeThread_for_studentGUI.cpp      |   0
 .../GUI_Qt/studentGUI/studentGUI.pro          |   0
 .../GUI_Qt/studentGUI/studentgui.qrc          |   0
 .../src/d_fall_pps/PPS.perspective            |   0
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   |   0
 .../src/d_fall_pps/crazyradio/LICENSE.txt     |   0
 .../src/d_fall_pps/crazyradio/Makefile        |   0
 .../src/d_fall_pps/crazyradio/README.md       |   0
 .../src/d_fall_pps/crazyradio/TestCF.py       |   0
 .../crazyradio/build/lib/cflib/__init__.py    |   0
 .../build/lib/cflib/bootloader/__init__.py    |   0
 .../build/lib/cflib/bootloader/boottypes.py   |   0
 .../build/lib/cflib/bootloader/cloader.py     |   0
 .../build/lib/cflib/crazyflie/__init__.py     |   0
 .../build/lib/cflib/crazyflie/commander.py    |   0
 .../build/lib/cflib/crazyflie/console.py      |   0
 .../build/lib/cflib/crazyflie/extpos.py       |   0
 .../build/lib/cflib/crazyflie/localization.py |   0
 .../build/lib/cflib/crazyflie/log.py          |   0
 .../build/lib/cflib/crazyflie/mem.py          |   0
 .../build/lib/cflib/crazyflie/param.py        |   0
 .../lib/cflib/crazyflie/platformservice.py    |   0
 .../build/lib/cflib/crazyflie/swarm.py        |   0
 .../lib/cflib/crazyflie/syncCrazyflie.py      |   0
 .../build/lib/cflib/crazyflie/syncLogger.py   |   0
 .../build/lib/cflib/crazyflie/toc.py          |   0
 .../build/lib/cflib/crazyflie/toccache.py     |   0
 .../build/lib/cflib/crtp/__init__.py          |   0
 .../build/lib/cflib/crtp/crtpdriver.py        |   0
 .../build/lib/cflib/crtp/crtpstack.py         |   0
 .../build/lib/cflib/crtp/debugdriver.py       |   0
 .../build/lib/cflib/crtp/exceptions.py        |   0
 .../build/lib/cflib/crtp/radiodriver.py       |   0
 .../build/lib/cflib/crtp/serialdriver.py      |   0
 .../build/lib/cflib/crtp/udpdriver.py         |   0
 .../build/lib/cflib/crtp/usbdriver.py         |   0
 .../build/lib/cflib/drivers/__init__.py       |   0
 .../build/lib/cflib/drivers/cfusb.py          |   0
 .../build/lib/cflib/drivers/crazyradio.py     |   0
 .../build/lib/cflib/utils/__init__.py         |   0
 .../build/lib/cflib/utils/callbacks.py        |   0
 .../crazyradio/build/lib/lpslib/__init__.py   |   0
 .../crazyradio/build/lib/lpslib/lopoanchor.py |   0
 .../crazyradio/build/lib/test/__init__.py     |   0
 .../build/lib/test/crazyflie/__init__.py      |   0
 .../build/lib/test/crazyflie/test_swarm.py    |   0
 .../lib/test/crazyflie/test_syncCrazyflie.py  |   0
 .../lib/test/crazyflie/test_syncLogger.py     |   0
 .../build/lib/test/crtp/__init__.py           |   0
 .../build/lib/test/crtp/test_crtpstack.py     |   0
 .../build/lib/test/support/__init__.py        |   0
 .../lib/test/support/asyncCallbackCaller.py   |   0
 .../build/lib/test/utils/__init__.py          |   0
 .../build/lib/test/utils/test_callbacks.py    |   0
 .../crazyradio/cflib.egg-info/PKG-INFO        |   0
 .../crazyradio/cflib.egg-info/SOURCES.txt     |   0
 .../cflib.egg-info/dependency_links.txt       |   0
 .../crazyradio/cflib.egg-info/requires.txt    |   0
 .../crazyradio/cflib.egg-info/top_level.txt   |   0
 .../d_fall_pps/crazyradio/cflib/__init__.py   |   0
 .../crazyradio/cflib/bootloader/__init__.py   |   0
 .../crazyradio/cflib/bootloader/boottypes.py  |   0
 .../crazyradio/cflib/bootloader/cloader.py    |   0
 .../crazyradio/cflib/crazyflie/__init__.py    |   0
 .../crazyradio/cflib/crazyflie/commander.py   |   0
 .../crazyradio/cflib/crazyflie/console.py     |   0
 .../crazyradio/cflib/crazyflie/extpos.py      |   0
 .../cflib/crazyflie/localization.py           |   0
 .../crazyradio/cflib/crazyflie/log.py         |   0
 .../crazyradio/cflib/crazyflie/mem.py         |   0
 .../crazyradio/cflib/crazyflie/param.py       |   0
 .../cflib/crazyflie/platformservice.py        |   0
 .../crazyradio/cflib/crazyflie/swarm.py       |   0
 .../cflib/crazyflie/syncCrazyflie.py          |   0
 .../crazyradio/cflib/crazyflie/syncLogger.py  |   0
 .../crazyradio/cflib/crazyflie/toc.py         |   0
 .../crazyradio/cflib/crazyflie/toccache.py    |   0
 .../crazyradio/cflib/crtp/__init__.py         |   0
 .../crazyradio/cflib/crtp/crtpdriver.py       |   0
 .../crazyradio/cflib/crtp/crtpstack.py        |   0
 .../crazyradio/cflib/crtp/debugdriver.py      |   0
 .../crazyradio/cflib/crtp/exceptions.py       |   0
 .../crazyradio/cflib/crtp/radiodriver.py      |   0
 .../crazyradio/cflib/crtp/serialdriver.py     |   0
 .../crazyradio/cflib/crtp/udpdriver.py        |   0
 .../crazyradio/cflib/crtp/usbdriver.py        |   0
 .../crazyradio/cflib/drivers/__init__.py      |   0
 .../crazyradio/cflib/drivers/cfusb.py         |   0
 .../crazyradio/cflib/drivers/crazyradio.py    |   0
 .../crazyradio/cflib/utils/__init__.py        |   0
 .../crazyradio/cflib/utils/callbacks.py       |   0
 .../crazyradio/dist/cflib-0.1.3-py3.5.egg     | Bin
 .../crazyradio/examples/autonomousSequence.py |   0
 .../crazyradio/examples/basiclog.py           |   0
 .../crazyradio/examples/basiclogSync.py       |   0
 .../crazyradio/examples/basicparam.py         |   0
 .../crazyradio/examples/erase-ow.py           |   0
 .../crazyradio/examples/flash-memory.py       |   0
 .../crazyradio/examples/flowsequenceSync.py   |   0
 .../examples/lps_reboot_to_bootloader.py      |   0
 .../crazyradio/examples/multiramp.py          |   0
 .../crazyradio/examples/radio-test.py         |   0
 .../d_fall_pps/crazyradio/examples/ramp.py    |   0
 .../crazyradio/examples/read-eeprom.py        |   0
 .../d_fall_pps/crazyradio/examples/read-ow.py |   0
 .../d_fall_pps/crazyradio/examples/scan.py    |   0
 .../crazyradio/examples/swarmSequence.py      |   0
 .../examples/swarmSequenceCircle.py           |   0
 .../crazyradio/examples/write-eeprom.py       |   0
 .../crazyradio/examples/write-ow.py           |   0
 .../d_fall_pps/crazyradio/lpslib/__init__.py  |   0
 .../crazyradio/lpslib/lopoanchor.py           |   0
 .../src/d_fall_pps/crazyradio/module.json     |   0
 .../crazyradio/requirements-dev.txt           |   0
 .../d_fall_pps/crazyradio/requirements.txt    |   0
 .../src/d_fall_pps/crazyradio/setup.cfg       |   0
 .../src/d_fall_pps/crazyradio/setup.py        |   0
 .../src/d_fall_pps/crazyradio/setup_linux.sh  |   0
 .../d_fall_pps/crazyradio/test/__init__.py    |   0
 .../crazyradio/test/crazyflie/__init__.py     |   0
 .../crazyradio/test/crazyflie/test_swarm.py   |   0
 .../test/crazyflie/test_syncCrazyflie.py      |   0
 .../test/crazyflie/test_syncLogger.py         |   0
 .../crazyradio/test/crtp/__init__.py          |   0
 .../crazyradio/test/crtp/test_crtpstack.py    |   0
 .../crazyradio/test/support/__init__.py       |   0
 .../test/support/asyncCallbackCaller.py       |   0
 .../crazyradio/test/utils/__init__.py         |   0
 .../crazyradio/test/utils/test_callbacks.py   |   0
 .../d_fall_pps/crazyradio/tools/build/bdist   |   0
 .../d_fall_pps/crazyradio/tools/build/build   |   0
 .../d_fall_pps/crazyradio/tools/build/test    |   0
 .../d_fall_pps/crazyradio/tools/build/verify  |   0
 .../src/d_fall_pps/crazyradio/tox.ini         |   0
 .../classes/GetParamtersAndNamespaces.h       |   0
 .../d_fall_pps/include/nodes/BatteryMonitor.h |   0
 .../include/nodes/CentralManagerService.h     |   0
 .../src/d_fall_pps/include/nodes/Constants.h  |   0
 .../d_fall_pps/include/nodes/CrazyflieIO.h    |   0
 .../include/nodes/DefaultControllerService.h  |   0
 .../include/nodes/DemoControllerService.h     |   0
 .../src/d_fall_pps/include/nodes/PPSClient.h  |   0
 .../include/nodes/ParameterService.h          |   0
 .../include/nodes/PickerControllerConstants.h |   0
 .../include/nodes/PickerControllerService.h   |   0
 .../include/nodes/RemoteControllerService.h   |   0
 .../include/nodes/SafeControllerService.h     |   0
 .../include/nodes/StudentControllerService.h  |   0
 .../include/nodes/TuningControllerService.h   |   0
 .../src/d_fall_pps/launch/Agent.launch        |   0
 .../src/d_fall_pps/launch/Config.sh           |   0
 .../src/d_fall_pps/launch/Coordinator.launch  |   0
 .../src/d_fall_pps/launch/Teacher.launch      |   0
 .../src/d_fall_pps/msg/AreaBounds.msg         |   0
 .../src/d_fall_pps/msg/ControlCommand.msg     |   0
 .../src/d_fall_pps/msg/CrazyflieContext.msg   |   0
 .../src/d_fall_pps/msg/CrazyflieDB.msg        |   0
 .../src/d_fall_pps/msg/CrazyflieData.msg      |   0
 .../src/d_fall_pps/msg/CrazyflieEntry.msg     |   0
 .../src/d_fall_pps/msg/CustomButton.msg       |   0
 .../d_fall_pps/msg/CustomButtonWithHeader.msg |   0
 .../src/d_fall_pps/msg/DebugMsg.msg           |   0
 .../src/d_fall_pps/msg/FloatWithHeader.msg    |   0
 .../src/d_fall_pps/msg/IntWithHeader.msg      |   0
 .../src/d_fall_pps/msg/Setpoint.msg           |   0
 .../src/d_fall_pps/msg/SetpointV2.msg         |   0
 .../src/d_fall_pps/msg/SetpointWithHeader.msg |   0
 .../src/d_fall_pps/msg/StringWithHeader.msg   |   0
 .../src/d_fall_pps/msg/UnlabeledMarker.msg    |   0
 .../src/d_fall_pps/msg/ViconData.msg          |   0
 .../msg/ViconSubscribeObjectName.msg          |   0
 .../src/d_fall_pps/package.xml                |   0
 .../src/d_fall_pps/param/BatteryMonitor.yaml  |   0
 .../src/d_fall_pps/param/ClientConfig.yaml    |   0
 .../d_fall_pps/param/DefaultController.yaml   |   0
 .../src/d_fall_pps/param/DemoController.yaml  |   0
 .../src/d_fall_pps/param/MpcController.yaml   |   0
 .../d_fall_pps/param/PickerController.yaml    |   0
 .../d_fall_pps/param/RemoteController.yaml    |   0
 .../src/d_fall_pps/param/SafeController.yaml  |   0
 .../d_fall_pps/param/StudentController.yaml   |   0
 .../d_fall_pps/param/TuningController.yaml    |   0
 .../src/d_fall_pps/param/ViconConfig.yaml     |   0
 .../src/d_fall_pps/param/YamlFileNames.yaml   |   0
 .../src/d_fall_pps/scripts/land_crazyflie     |   0
 .../d_fall_pps/scripts/load_custom_controller |   0
 .../d_fall_pps/scripts/load_safe_controller   |   0
 .../d_fall_pps/scripts/motors_off_crazyflie   |   0
 .../scripts/safe_controller_setpoint          |   0
 .../src/d_fall_pps/scripts/take_off_crazyflie |   0
 .../src/d_fall_pps/src/CrazyflieIO.cpp        |   0
 .../src/classes/GetParamtersAndNamespaces.cpp |   0
 .../d_fall_pps/src/nodes/BatteryMonitor.cpp   |   0
 .../src/nodes/CentralManagerService.cpp       |   0
 .../src/nodes/DefaultControllerService.cpp    |   0
 .../src/nodes/DemoControllerService.cpp       |   0
 .../src/nodes/MpcControllerService.cpp        |   0
 .../src/d_fall_pps/src/nodes/PPSClient.cpp    |   0
 .../d_fall_pps/src/nodes/ParameterService.cpp |   0
 .../src/nodes/PickerControllerService.cpp     |   0
 .../src/nodes/RemoteControllerService.cpp     |   0
 .../src/nodes/SafeControllerService.cpp       |   0
 .../src/nodes/StudentControllerService.cpp    |   0
 .../src/nodes/TuningControllerService.cpp     |   0
 .../src/nodes/ViconDataPublisher.cpp          |   0
 .../src/d_fall_pps/srv/CMCommand.srv          |   0
 .../src/d_fall_pps/srv/CMQuery.srv            |   0
 .../src/d_fall_pps/srv/CMRead.srv             |   0
 .../src/d_fall_pps/srv/CMUpdate.srv           |   0
 .../src/d_fall_pps/srv/Controller.srv         |   0
 .../src/d_fall_pps/srv/GetSetpointService.srv |   0
 .../src/d_fall_pps/srv/IntIntService.srv      |   0
 .../d_fall_pps/srv/LoadYamlFromFilename.srv   |   0
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user   | 271 --------------
 .../CrazyFlyGUI/CrazyFlyGUI.pro.user.7257614  | 336 ------------------
 .../studentGUI/studentGUI.pro.user.1400dcd    | 271 --------------
 .../studentGUI/studentGUI.pro.user.7257614    | 336 ------------------
 pps_ws/src/d_fall_pps/param/Crazyflie.db      |   8 -
 349 files changed, 7 insertions(+), 1230 deletions(-)
 rename {pps_ws => dfall_ws}/.catkin_workspace (100%)
 rename {pps_ws => dfall_ws}/src/CMakeLists.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/CMakeLists.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/PPS.perspective (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/CrazyRadio.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/LICENSE.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/Makefile (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/README.md (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/TestCF.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/utils/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/autonomousSequence.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/basiclog.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/basiclogSync.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/basicparam.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/erase-ow.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/flash-memory.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/multiramp.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/radio-test.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/ramp.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/read-eeprom.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/read-ow.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/scan.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/swarmSequence.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/write-eeprom.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/examples/write-ow.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/lpslib/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/module.json (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/requirements-dev.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/requirements.txt (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/setup.cfg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/setup.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/setup_linux.sh (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crtp/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/support/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/utils/__init__.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/tools/build/bdist (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/tools/build/build (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/tools/build/test (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/tools/build/verify (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/crazyradio/tox.ini (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/BatteryMonitor.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/CentralManagerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/Constants.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/CrazyflieIO.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/DefaultControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/DemoControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/PPSClient.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/ParameterService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/PickerControllerConstants.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/PickerControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/RemoteControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/SafeControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/StudentControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/include/nodes/TuningControllerService.h (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/launch/Agent.launch (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/launch/Config.sh (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/launch/Coordinator.launch (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/launch/Teacher.launch (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/AreaBounds.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/ControlCommand.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CrazyflieContext.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CrazyflieDB.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CrazyflieData.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CrazyflieEntry.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CustomButton.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/CustomButtonWithHeader.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/DebugMsg.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/FloatWithHeader.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/IntWithHeader.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/Setpoint.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/SetpointV2.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/SetpointWithHeader.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/StringWithHeader.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/UnlabeledMarker.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/ViconData.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/msg/ViconSubscribeObjectName.msg (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/package.xml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/BatteryMonitor.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/ClientConfig.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/DefaultController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/DemoController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/MpcController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/PickerController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/RemoteController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/SafeController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/StudentController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/TuningController.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/ViconConfig.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/param/YamlFileNames.yaml (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/land_crazyflie (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/load_custom_controller (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/load_safe_controller (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/motors_off_crazyflie (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/safe_controller_setpoint (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/scripts/take_off_crazyflie (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/CrazyflieIO.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/BatteryMonitor.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/CentralManagerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/DefaultControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/DemoControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/MpcControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/PPSClient.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/ParameterService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/PickerControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/RemoteControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/SafeControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/StudentControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/TuningControllerService.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/CMCommand.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/CMQuery.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/CMRead.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/CMUpdate.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/Controller.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/GetSetpointService.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/IntIntService.srv (100%)
 rename {pps_ws => dfall_ws}/src/d_fall_pps/srv/LoadYamlFromFilename.srv (100%)
 delete mode 100755 pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user
 delete mode 100755 pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user.7257614
 delete mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.1400dcd
 delete mode 100644 pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.7257614
 delete mode 100644 pps_ws/src/d_fall_pps/param/Crazyflie.db

diff --git a/.gitignore b/.gitignore
index d35aaa9e..26806938 100755
--- a/.gitignore
+++ b/.gitignore
@@ -1,13 +1,12 @@
-pps_ws/build/
-pps_ws/devel/
+dfall_ws/build/
+dfall_ws/devel/
 
-pps_ws/src/d_fall_pps/lib/vicon/
-pps_ws/src/d_fall_pps/include/DataStreamClient.h
+dfall_ws/src/d_fall_pps/lib/vicon/
+dfall_ws/src/d_fall_pps/include/DataStreamClient.h
 
-pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/*.pro.user
-
-pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/*.pro.user
-pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/*.pro.user.*
+# Qt Project files with user preferences
+*.pro.user
+*.pro.user.*
 
 *.pyc
 *.orig
diff --git a/pps_ws/.catkin_workspace b/dfall_ws/.catkin_workspace
similarity index 100%
rename from pps_ws/.catkin_workspace
rename to dfall_ws/.catkin_workspace
diff --git a/pps_ws/src/CMakeLists.txt b/dfall_ws/src/CMakeLists.txt
similarity index 100%
rename from pps_ws/src/CMakeLists.txt
rename to dfall_ws/src/CMakeLists.txt
diff --git a/pps_ws/src/d_fall_pps/CMakeLists.txt b/dfall_ws/src/d_fall_pps/CMakeLists.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/CMakeLists.txt
rename to dfall_ws/src/d_fall_pps/CMakeLists.txt
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc
similarity index 100%
rename from pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc
rename to dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc
diff --git a/pps_ws/src/d_fall_pps/PPS.perspective b/dfall_ws/src/d_fall_pps/PPS.perspective
similarity index 100%
rename from pps_ws/src/d_fall_pps/PPS.perspective
rename to dfall_ws/src/d_fall_pps/PPS.perspective
diff --git a/pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
rename to dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/LICENSE.txt b/dfall_ws/src/d_fall_pps/crazyradio/LICENSE.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/LICENSE.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/LICENSE.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/Makefile b/dfall_ws/src/d_fall_pps/crazyradio/Makefile
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/Makefile
rename to dfall_ws/src/d_fall_pps/crazyradio/Makefile
diff --git a/pps_ws/src/d_fall_pps/crazyradio/README.md b/dfall_ws/src/d_fall_pps/crazyradio/README.md
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/README.md
rename to dfall_ws/src/d_fall_pps/crazyradio/README.md
diff --git a/pps_ws/src/d_fall_pps/crazyradio/TestCF.py b/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/TestCF.py
rename to dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py b/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py
rename to dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO b/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt b/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt b/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt b/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt b/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py b/dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py
rename to dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg b/dfall_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg
rename to dfall_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/basiclog.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/basiclog.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/basiclog.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/basiclog.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/basicparam.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/basicparam.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/basicparam.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/basicparam.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/multiramp.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/multiramp.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/multiramp.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/multiramp.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/radio-test.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/radio-test.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/radio-test.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/radio-test.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/ramp.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/ramp.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/ramp.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/ramp.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/read-ow.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/read-ow.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/read-ow.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/read-ow.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/scan.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/scan.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/scan.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/scan.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/examples/write-ow.py b/dfall_ws/src/d_fall_pps/crazyradio/examples/write-ow.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/examples/write-ow.py
rename to dfall_ws/src/d_fall_pps/crazyradio/examples/write-ow.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py b/dfall_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py
rename to dfall_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/module.json b/dfall_ws/src/d_fall_pps/crazyradio/module.json
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/module.json
rename to dfall_ws/src/d_fall_pps/crazyradio/module.json
diff --git a/pps_ws/src/d_fall_pps/crazyradio/requirements-dev.txt b/dfall_ws/src/d_fall_pps/crazyradio/requirements-dev.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/requirements-dev.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/requirements-dev.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/requirements.txt b/dfall_ws/src/d_fall_pps/crazyradio/requirements.txt
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/requirements.txt
rename to dfall_ws/src/d_fall_pps/crazyradio/requirements.txt
diff --git a/pps_ws/src/d_fall_pps/crazyradio/setup.cfg b/dfall_ws/src/d_fall_pps/crazyradio/setup.cfg
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/setup.cfg
rename to dfall_ws/src/d_fall_pps/crazyradio/setup.cfg
diff --git a/pps_ws/src/d_fall_pps/crazyradio/setup.py b/dfall_ws/src/d_fall_pps/crazyradio/setup.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/setup.py
rename to dfall_ws/src/d_fall_pps/crazyradio/setup.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/setup_linux.sh b/dfall_ws/src/d_fall_pps/crazyradio/setup_linux.sh
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/setup_linux.sh
rename to dfall_ws/src/d_fall_pps/crazyradio/setup_linux.sh
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/test/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py b/dfall_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/support/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/test/support/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/support/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/support/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py b/dfall_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py b/dfall_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py b/dfall_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py
rename to dfall_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py
diff --git a/pps_ws/src/d_fall_pps/crazyradio/tools/build/bdist b/dfall_ws/src/d_fall_pps/crazyradio/tools/build/bdist
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/tools/build/bdist
rename to dfall_ws/src/d_fall_pps/crazyradio/tools/build/bdist
diff --git a/pps_ws/src/d_fall_pps/crazyradio/tools/build/build b/dfall_ws/src/d_fall_pps/crazyradio/tools/build/build
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/tools/build/build
rename to dfall_ws/src/d_fall_pps/crazyradio/tools/build/build
diff --git a/pps_ws/src/d_fall_pps/crazyradio/tools/build/test b/dfall_ws/src/d_fall_pps/crazyradio/tools/build/test
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/tools/build/test
rename to dfall_ws/src/d_fall_pps/crazyradio/tools/build/test
diff --git a/pps_ws/src/d_fall_pps/crazyradio/tools/build/verify b/dfall_ws/src/d_fall_pps/crazyradio/tools/build/verify
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/tools/build/verify
rename to dfall_ws/src/d_fall_pps/crazyradio/tools/build/verify
diff --git a/pps_ws/src/d_fall_pps/crazyradio/tox.ini b/dfall_ws/src/d_fall_pps/crazyradio/tox.ini
similarity index 100%
rename from pps_ws/src/d_fall_pps/crazyradio/tox.ini
rename to dfall_ws/src/d_fall_pps/crazyradio/tox.ini
diff --git a/pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
rename to dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
rename to dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h b/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/Constants.h b/dfall_ws/src/d_fall_pps/include/nodes/Constants.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/Constants.h
rename to dfall_ws/src/d_fall_pps/include/nodes/Constants.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h b/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
rename to dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h b/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
rename to dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/ParameterService.h b/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/ParameterService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h b/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
rename to dfall_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
diff --git a/pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
similarity index 100%
rename from pps_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
rename to dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
diff --git a/pps_ws/src/d_fall_pps/launch/Agent.launch b/dfall_ws/src/d_fall_pps/launch/Agent.launch
similarity index 100%
rename from pps_ws/src/d_fall_pps/launch/Agent.launch
rename to dfall_ws/src/d_fall_pps/launch/Agent.launch
diff --git a/pps_ws/src/d_fall_pps/launch/Config.sh b/dfall_ws/src/d_fall_pps/launch/Config.sh
similarity index 100%
rename from pps_ws/src/d_fall_pps/launch/Config.sh
rename to dfall_ws/src/d_fall_pps/launch/Config.sh
diff --git a/pps_ws/src/d_fall_pps/launch/Coordinator.launch b/dfall_ws/src/d_fall_pps/launch/Coordinator.launch
similarity index 100%
rename from pps_ws/src/d_fall_pps/launch/Coordinator.launch
rename to dfall_ws/src/d_fall_pps/launch/Coordinator.launch
diff --git a/pps_ws/src/d_fall_pps/launch/Teacher.launch b/dfall_ws/src/d_fall_pps/launch/Teacher.launch
similarity index 100%
rename from pps_ws/src/d_fall_pps/launch/Teacher.launch
rename to dfall_ws/src/d_fall_pps/launch/Teacher.launch
diff --git a/pps_ws/src/d_fall_pps/msg/AreaBounds.msg b/dfall_ws/src/d_fall_pps/msg/AreaBounds.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/AreaBounds.msg
rename to dfall_ws/src/d_fall_pps/msg/AreaBounds.msg
diff --git a/pps_ws/src/d_fall_pps/msg/ControlCommand.msg b/dfall_ws/src/d_fall_pps/msg/ControlCommand.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/ControlCommand.msg
rename to dfall_ws/src/d_fall_pps/msg/ControlCommand.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CrazyflieContext.msg b/dfall_ws/src/d_fall_pps/msg/CrazyflieContext.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CrazyflieContext.msg
rename to dfall_ws/src/d_fall_pps/msg/CrazyflieContext.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CrazyflieDB.msg b/dfall_ws/src/d_fall_pps/msg/CrazyflieDB.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CrazyflieDB.msg
rename to dfall_ws/src/d_fall_pps/msg/CrazyflieDB.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CrazyflieData.msg b/dfall_ws/src/d_fall_pps/msg/CrazyflieData.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CrazyflieData.msg
rename to dfall_ws/src/d_fall_pps/msg/CrazyflieData.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CrazyflieEntry.msg b/dfall_ws/src/d_fall_pps/msg/CrazyflieEntry.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CrazyflieEntry.msg
rename to dfall_ws/src/d_fall_pps/msg/CrazyflieEntry.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CustomButton.msg b/dfall_ws/src/d_fall_pps/msg/CustomButton.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CustomButton.msg
rename to dfall_ws/src/d_fall_pps/msg/CustomButton.msg
diff --git a/pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg b/dfall_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
rename to dfall_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
diff --git a/pps_ws/src/d_fall_pps/msg/DebugMsg.msg b/dfall_ws/src/d_fall_pps/msg/DebugMsg.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/DebugMsg.msg
rename to dfall_ws/src/d_fall_pps/msg/DebugMsg.msg
diff --git a/pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg b/dfall_ws/src/d_fall_pps/msg/FloatWithHeader.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/FloatWithHeader.msg
rename to dfall_ws/src/d_fall_pps/msg/FloatWithHeader.msg
diff --git a/pps_ws/src/d_fall_pps/msg/IntWithHeader.msg b/dfall_ws/src/d_fall_pps/msg/IntWithHeader.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/IntWithHeader.msg
rename to dfall_ws/src/d_fall_pps/msg/IntWithHeader.msg
diff --git a/pps_ws/src/d_fall_pps/msg/Setpoint.msg b/dfall_ws/src/d_fall_pps/msg/Setpoint.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/Setpoint.msg
rename to dfall_ws/src/d_fall_pps/msg/Setpoint.msg
diff --git a/pps_ws/src/d_fall_pps/msg/SetpointV2.msg b/dfall_ws/src/d_fall_pps/msg/SetpointV2.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/SetpointV2.msg
rename to dfall_ws/src/d_fall_pps/msg/SetpointV2.msg
diff --git a/pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg b/dfall_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
rename to dfall_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
diff --git a/pps_ws/src/d_fall_pps/msg/StringWithHeader.msg b/dfall_ws/src/d_fall_pps/msg/StringWithHeader.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/StringWithHeader.msg
rename to dfall_ws/src/d_fall_pps/msg/StringWithHeader.msg
diff --git a/pps_ws/src/d_fall_pps/msg/UnlabeledMarker.msg b/dfall_ws/src/d_fall_pps/msg/UnlabeledMarker.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/UnlabeledMarker.msg
rename to dfall_ws/src/d_fall_pps/msg/UnlabeledMarker.msg
diff --git a/pps_ws/src/d_fall_pps/msg/ViconData.msg b/dfall_ws/src/d_fall_pps/msg/ViconData.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/ViconData.msg
rename to dfall_ws/src/d_fall_pps/msg/ViconData.msg
diff --git a/pps_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg b/dfall_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg
similarity index 100%
rename from pps_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg
rename to dfall_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg
diff --git a/pps_ws/src/d_fall_pps/package.xml b/dfall_ws/src/d_fall_pps/package.xml
similarity index 100%
rename from pps_ws/src/d_fall_pps/package.xml
rename to dfall_ws/src/d_fall_pps/package.xml
diff --git a/pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml b/dfall_ws/src/d_fall_pps/param/BatteryMonitor.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/BatteryMonitor.yaml
rename to dfall_ws/src/d_fall_pps/param/BatteryMonitor.yaml
diff --git a/pps_ws/src/d_fall_pps/param/ClientConfig.yaml b/dfall_ws/src/d_fall_pps/param/ClientConfig.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/ClientConfig.yaml
rename to dfall_ws/src/d_fall_pps/param/ClientConfig.yaml
diff --git a/pps_ws/src/d_fall_pps/param/DefaultController.yaml b/dfall_ws/src/d_fall_pps/param/DefaultController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/DefaultController.yaml
rename to dfall_ws/src/d_fall_pps/param/DefaultController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/DemoController.yaml b/dfall_ws/src/d_fall_pps/param/DemoController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/DemoController.yaml
rename to dfall_ws/src/d_fall_pps/param/DemoController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/MpcController.yaml b/dfall_ws/src/d_fall_pps/param/MpcController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/MpcController.yaml
rename to dfall_ws/src/d_fall_pps/param/MpcController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/PickerController.yaml b/dfall_ws/src/d_fall_pps/param/PickerController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/PickerController.yaml
rename to dfall_ws/src/d_fall_pps/param/PickerController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/RemoteController.yaml b/dfall_ws/src/d_fall_pps/param/RemoteController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/RemoteController.yaml
rename to dfall_ws/src/d_fall_pps/param/RemoteController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/SafeController.yaml b/dfall_ws/src/d_fall_pps/param/SafeController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/SafeController.yaml
rename to dfall_ws/src/d_fall_pps/param/SafeController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/StudentController.yaml b/dfall_ws/src/d_fall_pps/param/StudentController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/StudentController.yaml
rename to dfall_ws/src/d_fall_pps/param/StudentController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/TuningController.yaml b/dfall_ws/src/d_fall_pps/param/TuningController.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/TuningController.yaml
rename to dfall_ws/src/d_fall_pps/param/TuningController.yaml
diff --git a/pps_ws/src/d_fall_pps/param/ViconConfig.yaml b/dfall_ws/src/d_fall_pps/param/ViconConfig.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/ViconConfig.yaml
rename to dfall_ws/src/d_fall_pps/param/ViconConfig.yaml
diff --git a/pps_ws/src/d_fall_pps/param/YamlFileNames.yaml b/dfall_ws/src/d_fall_pps/param/YamlFileNames.yaml
similarity index 100%
rename from pps_ws/src/d_fall_pps/param/YamlFileNames.yaml
rename to dfall_ws/src/d_fall_pps/param/YamlFileNames.yaml
diff --git a/pps_ws/src/d_fall_pps/scripts/land_crazyflie b/dfall_ws/src/d_fall_pps/scripts/land_crazyflie
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/land_crazyflie
rename to dfall_ws/src/d_fall_pps/scripts/land_crazyflie
diff --git a/pps_ws/src/d_fall_pps/scripts/load_custom_controller b/dfall_ws/src/d_fall_pps/scripts/load_custom_controller
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/load_custom_controller
rename to dfall_ws/src/d_fall_pps/scripts/load_custom_controller
diff --git a/pps_ws/src/d_fall_pps/scripts/load_safe_controller b/dfall_ws/src/d_fall_pps/scripts/load_safe_controller
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/load_safe_controller
rename to dfall_ws/src/d_fall_pps/scripts/load_safe_controller
diff --git a/pps_ws/src/d_fall_pps/scripts/motors_off_crazyflie b/dfall_ws/src/d_fall_pps/scripts/motors_off_crazyflie
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/motors_off_crazyflie
rename to dfall_ws/src/d_fall_pps/scripts/motors_off_crazyflie
diff --git a/pps_ws/src/d_fall_pps/scripts/safe_controller_setpoint b/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/safe_controller_setpoint
rename to dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
diff --git a/pps_ws/src/d_fall_pps/scripts/take_off_crazyflie b/dfall_ws/src/d_fall_pps/scripts/take_off_crazyflie
similarity index 100%
rename from pps_ws/src/d_fall_pps/scripts/take_off_crazyflie
rename to dfall_ws/src/d_fall_pps/scripts/take_off_crazyflie
diff --git a/pps_ws/src/d_fall_pps/src/CrazyflieIO.cpp b/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/CrazyflieIO.cpp
rename to dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
diff --git a/pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
rename to dfall_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
diff --git a/pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp b/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
similarity index 100%
rename from pps_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
rename to dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
diff --git a/pps_ws/src/d_fall_pps/srv/CMCommand.srv b/dfall_ws/src/d_fall_pps/srv/CMCommand.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/CMCommand.srv
rename to dfall_ws/src/d_fall_pps/srv/CMCommand.srv
diff --git a/pps_ws/src/d_fall_pps/srv/CMQuery.srv b/dfall_ws/src/d_fall_pps/srv/CMQuery.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/CMQuery.srv
rename to dfall_ws/src/d_fall_pps/srv/CMQuery.srv
diff --git a/pps_ws/src/d_fall_pps/srv/CMRead.srv b/dfall_ws/src/d_fall_pps/srv/CMRead.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/CMRead.srv
rename to dfall_ws/src/d_fall_pps/srv/CMRead.srv
diff --git a/pps_ws/src/d_fall_pps/srv/CMUpdate.srv b/dfall_ws/src/d_fall_pps/srv/CMUpdate.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/CMUpdate.srv
rename to dfall_ws/src/d_fall_pps/srv/CMUpdate.srv
diff --git a/pps_ws/src/d_fall_pps/srv/Controller.srv b/dfall_ws/src/d_fall_pps/srv/Controller.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/Controller.srv
rename to dfall_ws/src/d_fall_pps/srv/Controller.srv
diff --git a/pps_ws/src/d_fall_pps/srv/GetSetpointService.srv b/dfall_ws/src/d_fall_pps/srv/GetSetpointService.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/GetSetpointService.srv
rename to dfall_ws/src/d_fall_pps/srv/GetSetpointService.srv
diff --git a/pps_ws/src/d_fall_pps/srv/IntIntService.srv b/dfall_ws/src/d_fall_pps/srv/IntIntService.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/IntIntService.srv
rename to dfall_ws/src/d_fall_pps/srv/IntIntService.srv
diff --git a/pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv b/dfall_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
similarity index 100%
rename from pps_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
rename to dfall_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user
deleted file mode 100755
index c3bd5196..00000000
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user
+++ /dev/null
@@ -1,271 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<!DOCTYPE QtCreatorProject>
-<!-- Written by QtCreator 3.5.1, 2017-12-05T07:54:15. -->
-<qtcreator>
- <data>
-  <variable>EnvironmentId</variable>
-  <value type="QByteArray">{1400dcd4-82c6-466c-a808-34f7a3d4fe21}</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.ActiveTarget</variable>
-  <value type="int">0</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.EditorSettings</variable>
-  <valuemap type="QVariantMap">
-   <value type="bool" key="EditorConfiguration.AutoIndent">true</value>
-   <value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
-   <value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
-    <value type="QString" key="language">Cpp</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
-    </valuemap>
-   </valuemap>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
-    <value type="QString" key="language">QmlJS</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
-    </valuemap>
-   </valuemap>
-   <value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
-   <value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
-   <value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
-   <value type="int" key="EditorConfiguration.IndentSize">4</value>
-   <value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
-   <value type="int" key="EditorConfiguration.MarginColumn">80</value>
-   <value type="bool" key="EditorConfiguration.MouseHiding">true</value>
-   <value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
-   <value type="int" key="EditorConfiguration.PaddingMode">1</value>
-   <value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
-   <value type="bool" key="EditorConfiguration.ShowMargin">false</value>
-   <value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
-   <value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
-   <value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
-   <value type="int" key="EditorConfiguration.TabSize">8</value>
-   <value type="bool" key="EditorConfiguration.UseGlobal">true</value>
-   <value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
-   <value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
-   <value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
-   <value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
-   <value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.PluginSettings</variable>
-  <valuemap type="QVariantMap"/>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Target.0</variable>
-  <valuemap type="QVariantMap">
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{051621a5-413a-4a38-907c-a6d036ac454e}</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-CrazyFlyGUI-Desktop-Debug</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibraryAuto">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-CrazyFlyGUI-Desktop-Release</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibraryAuto">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Release</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">2</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy locally</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
-    <value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
-    <value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
-    <value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
-    <value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
-    <value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
-    <value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
-    <value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
-    <value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
-     <value type="int">0</value>
-     <value type="int">1</value>
-     <value type="int">2</value>
-     <value type="int">3</value>
-     <value type="int">4</value>
-     <value type="int">5</value>
-     <value type="int">6</value>
-     <value type="int">7</value>
-     <value type="int">8</value>
-     <value type="int">9</value>
-     <value type="int">10</value>
-     <value type="int">11</value>
-     <value type="int">12</value>
-     <value type="int">13</value>
-     <value type="int">14</value>
-    </valuelist>
-    <value type="int" key="PE.EnvironmentAspect.Base">2</value>
-    <valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">CrazyFlyGUI</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">CrazyFlyGUI.pro</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseTerminal">false</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value>
-    <value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
-    <value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
-    <value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.TargetCount</variable>
-  <value type="int">1</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Updater.FileVersion</variable>
-  <value type="int">18</value>
- </data>
- <data>
-  <variable>Version</variable>
-  <value type="int">18</value>
- </data>
-</qtcreator>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user.7257614 b/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user.7257614
deleted file mode 100755
index ebe2fd31..00000000
--- a/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro.user.7257614
+++ /dev/null
@@ -1,336 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<!DOCTYPE QtCreatorProject>
-<!-- Written by QtCreator 4.0.2, 2017-08-15T15:30:19. -->
-<qtcreator>
- <data>
-  <variable>EnvironmentId</variable>
-  <value type="QByteArray">{72576140-2426-4e8d-b4f8-00ed8021ee7f}</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.ActiveTarget</variable>
-  <value type="int">0</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.EditorSettings</variable>
-  <valuemap type="QVariantMap">
-   <value type="bool" key="EditorConfiguration.AutoIndent">true</value>
-   <value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
-   <value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
-    <value type="QString" key="language">Cpp</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
-    </valuemap>
-   </valuemap>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
-    <value type="QString" key="language">QmlJS</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
-    </valuemap>
-   </valuemap>
-   <value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
-   <value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
-   <value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
-   <value type="int" key="EditorConfiguration.IndentSize">4</value>
-   <value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
-   <value type="int" key="EditorConfiguration.MarginColumn">80</value>
-   <value type="bool" key="EditorConfiguration.MouseHiding">true</value>
-   <value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
-   <value type="int" key="EditorConfiguration.PaddingMode">1</value>
-   <value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
-   <value type="bool" key="EditorConfiguration.ShowMargin">false</value>
-   <value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
-   <value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
-   <value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
-   <value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
-   <value type="int" key="EditorConfiguration.TabSize">8</value>
-   <value type="bool" key="EditorConfiguration.UseGlobal">true</value>
-   <value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
-   <value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
-   <value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
-   <value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
-   <value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.PluginSettings</variable>
-  <valuemap type="QVariantMap"/>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Target.0</variable>
-  <valuemap type="QVariantMap">
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">qt.57.gcc_64_kit</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-CrazyFlyGUI-Desktop_Qt_5_7_0_GCC_64bit-Debug</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_gui/GUI_Qt/build-CrazyFlyGUI-Desktop_Qt_5_7_0_GCC_64bit-Release</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Release</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.2">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_gui/GUI_Qt/build-CrazyFlyGUI-Desktop_Qt_5_7_0_GCC_64bit-Profile</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">true</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Profile</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">3</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy locally</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
-    <value type="bool" key="Analyzer.QmlProfiler.AggregateTraces">false</value>
-    <value type="bool" key="Analyzer.QmlProfiler.FlushEnabled">false</value>
-    <value type="uint" key="Analyzer.QmlProfiler.FlushInterval">1000</value>
-    <value type="QString" key="Analyzer.QmlProfiler.LastTraceFile"></value>
-    <value type="bool" key="Analyzer.QmlProfiler.Settings.UseGlobalSettings">true</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
-    <value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
-    <value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
-    <value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
-    <value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
-    <value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
-    <value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
-    <value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
-    <value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
-     <value type="int">0</value>
-     <value type="int">1</value>
-     <value type="int">2</value>
-     <value type="int">3</value>
-     <value type="int">4</value>
-     <value type="int">5</value>
-     <value type="int">6</value>
-     <value type="int">7</value>
-     <value type="int">8</value>
-     <value type="int">9</value>
-     <value type="int">10</value>
-     <value type="int">11</value>
-     <value type="int">12</value>
-     <value type="int">13</value>
-     <value type="int">14</value>
-    </valuelist>
-    <value type="int" key="PE.EnvironmentAspect.Base">2</value>
-    <valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">CrazyFlyGUI</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">CrazyFlyGUI2</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro</value>
-    <value type="bool" key="QmakeProjectManager.QmakeRunConfiguration.UseLibrarySearchPath">true</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">CrazyFlyGUI.pro</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory.default">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-CrazyFlyGUI-Desktop_Qt_5_7_0_GCC_64bit-Debug</value>
-    <value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
-    <value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
-    <value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.TargetCount</variable>
-  <value type="int">1</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Updater.FileVersion</variable>
-  <value type="int">18</value>
- </data>
- <data>
-  <variable>Version</variable>
-  <value type="int">18</value>
- </data>
-</qtcreator>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.1400dcd b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.1400dcd
deleted file mode 100644
index 8e1edbbf..00000000
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.1400dcd
+++ /dev/null
@@ -1,271 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<!DOCTYPE QtCreatorProject>
-<!-- Written by QtCreator 3.5.1, 2017-10-18T15:20:06. -->
-<qtcreator>
- <data>
-  <variable>EnvironmentId</variable>
-  <value type="QByteArray">{1400dcd4-82c6-466c-a808-34f7a3d4fe21}</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.ActiveTarget</variable>
-  <value type="int">0</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.EditorSettings</variable>
-  <valuemap type="QVariantMap">
-   <value type="bool" key="EditorConfiguration.AutoIndent">true</value>
-   <value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
-   <value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
-    <value type="QString" key="language">Cpp</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
-    </valuemap>
-   </valuemap>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
-    <value type="QString" key="language">QmlJS</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
-    </valuemap>
-   </valuemap>
-   <value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
-   <value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
-   <value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
-   <value type="int" key="EditorConfiguration.IndentSize">4</value>
-   <value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
-   <value type="int" key="EditorConfiguration.MarginColumn">80</value>
-   <value type="bool" key="EditorConfiguration.MouseHiding">true</value>
-   <value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
-   <value type="int" key="EditorConfiguration.PaddingMode">1</value>
-   <value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
-   <value type="bool" key="EditorConfiguration.ShowMargin">false</value>
-   <value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
-   <value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
-   <value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
-   <value type="int" key="EditorConfiguration.TabSize">8</value>
-   <value type="bool" key="EditorConfiguration.UseGlobal">true</value>
-   <value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
-   <value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
-   <value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
-   <value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
-   <value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.PluginSettings</variable>
-  <valuemap type="QVariantMap"/>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Target.0</variable>
-  <valuemap type="QVariantMap">
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{051621a5-413a-4a38-907c-a6d036ac454e}</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop-Debug</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibraryAuto">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop-Release</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibraryAuto">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Release</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">2</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy locally</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
-    <value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
-    <value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
-    <value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
-    <value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
-    <value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
-    <value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
-    <value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
-    <value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
-     <value type="int">0</value>
-     <value type="int">1</value>
-     <value type="int">2</value>
-     <value type="int">3</value>
-     <value type="int">4</value>
-     <value type="int">5</value>
-     <value type="int">6</value>
-     <value type="int">7</value>
-     <value type="int">8</value>
-     <value type="int">9</value>
-     <value type="int">10</value>
-     <value type="int">11</value>
-     <value type="int">12</value>
-     <value type="int">13</value>
-     <value type="int">14</value>
-    </valuelist>
-    <value type="int" key="PE.EnvironmentAspect.Base">2</value>
-    <valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">studentGUI</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/ppsteacher/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">studentGUI.pro</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseTerminal">false</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value>
-    <value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
-    <value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
-    <value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.TargetCount</variable>
-  <value type="int">1</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Updater.FileVersion</variable>
-  <value type="int">18</value>
- </data>
- <data>
-  <variable>Version</variable>
-  <value type="int">18</value>
- </data>
-</qtcreator>
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.7257614 b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.7257614
deleted file mode 100644
index 3b064d23..00000000
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro.user.7257614
+++ /dev/null
@@ -1,336 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<!DOCTYPE QtCreatorProject>
-<!-- Written by QtCreator 4.0.2, 2017-09-05T11:57:14. -->
-<qtcreator>
- <data>
-  <variable>EnvironmentId</variable>
-  <value type="QByteArray">{72576140-2426-4e8d-b4f8-00ed8021ee7f}</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.ActiveTarget</variable>
-  <value type="int">0</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.EditorSettings</variable>
-  <valuemap type="QVariantMap">
-   <value type="bool" key="EditorConfiguration.AutoIndent">true</value>
-   <value type="bool" key="EditorConfiguration.AutoSpacesForTabs">false</value>
-   <value type="bool" key="EditorConfiguration.CamelCaseNavigation">true</value>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.0">
-    <value type="QString" key="language">Cpp</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">CppGlobal</value>
-    </valuemap>
-   </valuemap>
-   <valuemap type="QVariantMap" key="EditorConfiguration.CodeStyle.1">
-    <value type="QString" key="language">QmlJS</value>
-    <valuemap type="QVariantMap" key="value">
-     <value type="QByteArray" key="CurrentPreferences">QmlJSGlobal</value>
-    </valuemap>
-   </valuemap>
-   <value type="int" key="EditorConfiguration.CodeStyle.Count">2</value>
-   <value type="QByteArray" key="EditorConfiguration.Codec">UTF-8</value>
-   <value type="bool" key="EditorConfiguration.ConstrainTooltips">false</value>
-   <value type="int" key="EditorConfiguration.IndentSize">4</value>
-   <value type="bool" key="EditorConfiguration.KeyboardTooltips">false</value>
-   <value type="int" key="EditorConfiguration.MarginColumn">80</value>
-   <value type="bool" key="EditorConfiguration.MouseHiding">true</value>
-   <value type="bool" key="EditorConfiguration.MouseNavigation">true</value>
-   <value type="int" key="EditorConfiguration.PaddingMode">1</value>
-   <value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
-   <value type="bool" key="EditorConfiguration.ShowMargin">false</value>
-   <value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
-   <value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
-   <value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
-   <value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
-   <value type="int" key="EditorConfiguration.TabSize">8</value>
-   <value type="bool" key="EditorConfiguration.UseGlobal">true</value>
-   <value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
-   <value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
-   <value type="bool" key="EditorConfiguration.cleanIndentation">true</value>
-   <value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
-   <value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.PluginSettings</variable>
-  <valuemap type="QVariantMap"/>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Target.0</variable>
-  <valuemap type="QVariantMap">
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop Qt 5.7.0 GCC 64bit</value>
-   <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">qt.57.gcc_64_kit</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
-   <value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop_Qt_5_7_0_GCC_64bit-Debug</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Debug</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">2</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.1">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop_Qt_5_7_0_GCC_64bit-Release</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">false</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Release</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.2">
-    <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop_Qt_5_7_0_GCC_64bit-Profile</value>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">qmake</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">QtProjectManager.QMakeBuildStep</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.LinkQmlDebuggingLibrary">true</value>
-      <value type="QString" key="QtProjectManager.QMakeBuildStep.QMakeArguments"></value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.QMakeForced">false</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.SeparateDebugInfo">true</value>
-      <value type="bool" key="QtProjectManager.QMakeBuildStep.UseQtQuickCompiler">false</value>
-     </valuemap>
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.1">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">false</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments"></value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">2</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
-    </valuemap>
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
-     <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
-      <value type="bool" key="ProjectExplorer.BuildStep.Enabled">true</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Make</value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-      <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.MakeStep</value>
-      <valuelist type="QVariantList" key="Qt4ProjectManager.MakeStep.AutomaticallyAddedMakeArguments">
-       <value type="QString">-w</value>
-       <value type="QString">-r</value>
-      </valuelist>
-      <value type="bool" key="Qt4ProjectManager.MakeStep.Clean">true</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeArguments">clean</value>
-      <value type="QString" key="Qt4ProjectManager.MakeStep.MakeCommand"></value>
-     </valuemap>
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
-    <value type="bool" key="ProjectExplorer.BuildConfiguration.ClearSystemEnvironment">false</value>
-    <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Profile</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4BuildConfiguration</value>
-    <value type="int" key="Qt4ProjectManager.Qt4BuildConfiguration.BuildConfiguration">0</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4BuildConfiguration.UseShadowBuild">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.BuildConfigurationCount">3</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
-    <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
-     <value type="int" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-     <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
-    </valuemap>
-    <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy locally</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.DefaultDeployConfiguration</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.DeployConfigurationCount">1</value>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.PluginSettings"/>
-   <valuemap type="QVariantMap" key="ProjectExplorer.Target.RunConfiguration.0">
-    <value type="bool" key="Analyzer.QmlProfiler.AggregateTraces">false</value>
-    <value type="bool" key="Analyzer.QmlProfiler.FlushEnabled">false</value>
-    <value type="uint" key="Analyzer.QmlProfiler.FlushInterval">1000</value>
-    <value type="QString" key="Analyzer.QmlProfiler.LastTraceFile"></value>
-    <value type="bool" key="Analyzer.QmlProfiler.Settings.UseGlobalSettings">true</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.AddedSuppressionFiles"/>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectBusEvents">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.CollectSystime">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableBranchSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableCacheSim">false</value>
-    <value type="bool" key="Analyzer.Valgrind.Callgrind.EnableEventToolTips">true</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.MinimumCostRatio">0.01</value>
-    <value type="double" key="Analyzer.Valgrind.Callgrind.VisualisationMinimumCostRatio">10</value>
-    <value type="bool" key="Analyzer.Valgrind.FilterExternalIssues">true</value>
-    <value type="int" key="Analyzer.Valgrind.LeakCheckOnFinish">1</value>
-    <value type="int" key="Analyzer.Valgrind.NumCallers">25</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.RemovedSuppressionFiles"/>
-    <value type="int" key="Analyzer.Valgrind.SelfModifyingCodeDetection">1</value>
-    <value type="bool" key="Analyzer.Valgrind.Settings.UseGlobalSettings">true</value>
-    <value type="bool" key="Analyzer.Valgrind.ShowReachable">false</value>
-    <value type="bool" key="Analyzer.Valgrind.TrackOrigins">true</value>
-    <value type="QString" key="Analyzer.Valgrind.ValgrindExecutable">valgrind</value>
-    <valuelist type="QVariantList" key="Analyzer.Valgrind.VisibleErrorKinds">
-     <value type="int">0</value>
-     <value type="int">1</value>
-     <value type="int">2</value>
-     <value type="int">3</value>
-     <value type="int">4</value>
-     <value type="int">5</value>
-     <value type="int">6</value>
-     <value type="int">7</value>
-     <value type="int">8</value>
-     <value type="int">9</value>
-     <value type="int">10</value>
-     <value type="int">11</value>
-     <value type="int">12</value>
-     <value type="int">13</value>
-     <value type="int">14</value>
-    </valuelist>
-    <value type="int" key="PE.EnvironmentAspect.Base">2</value>
-    <valuelist type="QVariantList" key="PE.EnvironmentAspect.Changes"/>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">studentGUI</value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName"></value>
-    <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">Qt4ProjectManager.Qt4RunConfiguration:/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro</value>
-    <value type="bool" key="QmakeProjectManager.QmakeRunConfiguration.UseLibrarySearchPath">true</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.CommandLineArguments"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.ProFile">studentGUI.pro</value>
-    <value type="bool" key="Qt4ProjectManager.Qt4RunConfiguration.UseDyldImageSuffix">false</value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory"></value>
-    <value type="QString" key="Qt4ProjectManager.Qt4RunConfiguration.UserWorkingDirectory.default">/home/gazebo-cf/work/D-FaLL-System/pps_ws/src/d_fall_pps/GUI_Qt/build-studentGUI-Desktop_Qt_5_7_0_GCC_64bit-Debug</value>
-    <value type="uint" key="RunConfiguration.QmlDebugServerPort">3768</value>
-    <value type="bool" key="RunConfiguration.UseCppDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
-    <value type="bool" key="RunConfiguration.UseMultiProcess">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebugger">false</value>
-    <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
-   </valuemap>
-   <value type="int" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
-  </valuemap>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.TargetCount</variable>
-  <value type="int">1</value>
- </data>
- <data>
-  <variable>ProjectExplorer.Project.Updater.FileVersion</variable>
-  <value type="int">18</value>
- </data>
- <data>
-  <variable>Version</variable>
-  <value type="int">18</value>
- </data>
-</qtcreator>
diff --git a/pps_ws/src/d_fall_pps/param/Crazyflie.db b/pps_ws/src/d_fall_pps/param/Crazyflie.db
deleted file mode 100644
index a9616e9d..00000000
--- a/pps_ws/src/d_fall_pps/param/Crazyflie.db
+++ /dev/null
@@ -1,8 +0,0 @@
-1,CF01,0/0/2M/E7E7E7E701,0,-1.95374,-0.0143279,-0.2,-1.01034,0.774692,1.2
-2,CF02,0/8/2M/E7E7E7E702,1,-0.844536,-0.025763,-0.2,0.0759869,0.751821,1.2
-3,CF03,0/16/2M/E7E7E7E703,2,0.213208,0.00282468,-0.2,1.18519,0.757539,1.2
-4,CF04,0/24/2M/E7E7E7E704,3,1.34528,-0.0143279,-0.2,2.31154,0.723234,1.2
-5,CF05,0/32/2M/E7E7E7E705,4,1.351,0.791844,-0.2,2.31154,1.54084,1.2
-6,CF06,0/40/2M/E7E7E7E706,5,0.20749,0.843302,-0.2,1.18519,1.55799,1.2
-7,CF07,0/48/2M/E7E7E7E707,6,-0.867406,0.843302,-0.2,0.0702693,1.54656,1.2
-8,CF08,0/56/2M/E7E7E7E708,7,-1.95374,0.854737,-0.2,-0.987474,1.54656,1.2
-- 
GitLab


From 041762224abc3273919135fbd24c7dcb80f74f3c Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 7 Feb 2019 22:14:55 +0100
Subject: [PATCH 52/87] Renamed all instances of d_fall_pps to dfall_pkg

---
 dfall_ws/src/d_fall_pps/CMakeLists.txt        | 38 +++++++++---------
 .../GUI_Qt/CrazyFlyGUI/include/crazyFly.h     |  4 +-
 .../CrazyFlyGUI/include/mainguiwindow.h       |  8 ++--
 .../GUI_Qt/CrazyFlyGUI/include/marker.h       |  4 +-
 .../include/rosNodeThread_for_managerGUI.h    |  8 ++--
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  | 16 ++++----
 .../src/rosNodeThread_for_managerGUI.cpp      |  6 +--
 .../include/connectstartstopbar.h             | 14 +++----
 .../flyingAgentGUI/include/controllertabs.h   | 22 +++++-----
 .../flyingAgentGUI/include/coordinatorrow.h   | 14 +++----
 .../include/defaultcontrollertab.h            | 12 +++---
 .../include/enablecontrollerloadyamlbar.h     | 16 ++++----
 .../flyingAgentGUI/include/mainwindow.h       |  4 +-
 .../include/pickercontrollertab.h             | 14 +++----
 .../rosNodeThread_for_flyingAgentGUI.h        | 14 +++----
 .../include/studentcontrollertab.h            | 16 ++++----
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h | 12 +++---
 .../include/tuningcontrollertab.h             | 18 ++++-----
 .../src/connectstartstopbar.cpp               | 24 +++++------
 .../flyingAgentGUI/src/controllertabs.cpp     | 12 +++---
 .../flyingAgentGUI/src/coordinatorrow.cpp     | 26 ++++++------
 .../src/defaultcontrollertab.cpp              | 18 ++++-----
 .../src/enablecontrollerloadyamlbar.cpp       | 26 ++++++------
 .../src/pickercontrollertab.cpp               | 16 ++++----
 .../src/rosNodeThread_for_flyingAgentGUI.cpp  |  8 ++--
 .../src/studentcontrollertab.cpp              | 24 +++++------
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |  8 ++--
 .../src/tuningcontrollertab.cpp               | 24 +++++------
 .../GUI_Qt/studentGUI/include/MainWindow.h    | 10 ++---
 .../include/rosNodeThread_for_studentGUI.h    |  8 ++--
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      |  6 +--
 .../src/rosNodeThread_for_studentGUI.cpp      |  6 +--
 .../src/d_fall_pps/crazyradio/CrazyRadio.py   | 10 ++---
 dfall_ws/src/d_fall_pps/crazyradio/TestCF.py  |  6 +--
 .../classes/GetParamtersAndNamespaces.h       |  4 +-
 .../d_fall_pps/include/nodes/BatteryMonitor.h |  4 +-
 .../include/nodes/CentralManagerService.h     | 14 +++----
 .../d_fall_pps/include/nodes/CrazyflieIO.h    |  4 +-
 .../include/nodes/DefaultControllerService.h  | 24 +++++------
 .../include/nodes/DemoControllerService.h     | 18 ++++-----
 .../src/d_fall_pps/include/nodes/PPSClient.h  | 20 +++++-----
 .../include/nodes/ParameterService.h          | 10 ++---
 .../include/nodes/PickerControllerService.h   | 30 +++++++-------
 .../include/nodes/RemoteControllerService.h   | 16 ++++----
 .../include/nodes/SafeControllerService.h     | 12 +++---
 .../include/nodes/StudentControllerService.h  | 24 +++++------
 .../include/nodes/TuningControllerService.h   | 40 +++++++++----------
 dfall_ws/src/d_fall_pps/launch/Agent.launch   | 40 +++++++++----------
 .../src/d_fall_pps/launch/Coordinator.launch  | 10 ++---
 dfall_ws/src/d_fall_pps/launch/Teacher.launch |  8 ++--
 dfall_ws/src/d_fall_pps/package.xml           |  6 +--
 .../scripts/safe_controller_setpoint          |  2 +-
 dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp   | 10 ++---
 .../src/nodes/DefaultControllerService.cpp    |  4 +-
 .../src/nodes/DemoControllerService.cpp       |  4 +-
 .../src/nodes/MpcControllerService.cpp        | 16 ++++----
 .../src/d_fall_pps/src/nodes/PPSClient.cpp    |  4 +-
 .../d_fall_pps/src/nodes/ParameterService.cpp |  8 ++--
 .../src/nodes/PickerControllerService.cpp     |  4 +-
 .../src/nodes/RemoteControllerService.cpp     |  4 +-
 .../src/nodes/SafeControllerService.cpp       |  2 +-
 .../src/nodes/StudentControllerService.cpp    |  4 +-
 .../src/nodes/TuningControllerService.cpp     |  4 +-
 .../src/nodes/ViconDataPublisher.cpp          |  6 +--
 64 files changed, 414 insertions(+), 414 deletions(-)

diff --git a/dfall_ws/src/d_fall_pps/CMakeLists.txt b/dfall_ws/src/d_fall_pps/CMakeLists.txt
index 77da3b66..3fb5b938 100755
--- a/dfall_ws/src/d_fall_pps/CMakeLists.txt
+++ b/dfall_ws/src/d_fall_pps/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 3.0)
-project(d_fall_pps)
+project(dfall_pkg)
 
 ## Add support for C++11, supported in ROS Kinetic and newer
 # add_definitions(-std=c++11)
@@ -321,7 +321,7 @@ include_directories(
 ## Declare a C++ executable
 ## With catkin_make all packages are built within a single CMake context
 ## The recommended prefix ensures that target names across packages don't collide
-# add_executable(${PROJECT_NAME}_node src/d_fall_pps_node.cpp)
+# add_executable(${PROJECT_NAME}_node src/dfall_pkg_node.cpp)
 
 if(VICON_LIBRARY)
 	add_executable(ViconDataPublisher       src/nodes/ViconDataPublisher.cpp)
@@ -417,36 +417,36 @@ qt5_use_modules(flyingAgentGUI Widgets)
 
 
 if(VICON_LIBRARY)
-	add_dependencies(ViconDataPublisher       d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+	add_dependencies(ViconDataPublisher       dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 endif()
 
-add_dependencies(PPSClient                 d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(BatteryMonitor            d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(DefaultControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(SafeControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(DemoControllerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(StudentControllerService  d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(MpcControllerService      d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(RemoteControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(TuningControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(PickerControllerService   d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(CentralManagerService     d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(ParameterService          d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(PPSClient                 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})
+add_dependencies(DemoControllerService     dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(StudentControllerService  dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(MpcControllerService      dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(RemoteControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(TuningControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(PickerControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(CentralManagerService     dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(ParameterService          dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
 # GUI-- dependencies
-add_dependencies(my_GUI d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(my_GUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
 # StudentGUI-- dependencies
-add_dependencies(student_GUI d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(student_GUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
 # FLYING AGENT GUI-- dependencies
-add_dependencies(flyingAgentGUI d_fall_pps_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(flyingAgentGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
@@ -553,7 +553,7 @@ target_link_libraries(flyingAgentGUI ${catkin_LIBRARIES})
 #############
 
 ## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_d_fall_pps.cpp)
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_dfall_pkg.cpp)
 # if(TARGET ${PROJECT_NAME}-test)
 #   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
 # endif()
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
index dc818987..679f7303 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
@@ -39,11 +39,11 @@
 #include <QSvgRenderer>
 
 #ifdef CATKIN_MAKE
-#include "d_fall_pps/CrazyflieData.h"
+#include "dfall_pkg/CrazyflieData.h"
 #endif
 
 #ifdef CATKIN_MAKE
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 #endif
 
 #define DRONE_HEIGHT         100 * FROM_MILIMETERS_TO_UNITS * 1.2
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
index ef7d7920..d5aceaf6 100755
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
@@ -49,14 +49,14 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
+#include "dfall_pkg/IntWithHeader.h"
 #include "marker.h"
 #include "crazyFly.h"
 #include "CFLinker.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/CrazyflieDB.h"
-#include "d_fall_pps/CrazyflieEntry.h"
+#include "dfall_pkg/CrazyflieDB.h"
+#include "dfall_pkg/CrazyflieEntry.h"
 
 
 // The constants that are sent to the agents in order to
@@ -79,7 +79,7 @@
 #define LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR  4
 
 
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 #endif
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
index 1a7a4ae0..8aa71328 100755
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
@@ -38,12 +38,12 @@
 #include <QGraphicsEllipseItem>
 
 #ifdef CATKIN_MAKE
-#include "d_fall_pps/UnlabeledMarker.h"
+#include "dfall_pkg/UnlabeledMarker.h"
 #endif
 
 
 #ifdef CATKIN_MAKE
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 #endif
 
 #define MARKER_DIAMETER        20 * FROM_MILIMETERS_TO_UNITS
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
index e07356ee..65c516e2 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
@@ -43,11 +43,11 @@
 
 #include <ros/ros.h>
 #include <ros/network.h>
-#include "d_fall_pps/UnlabeledMarker.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/ViconData.h"
+#include "dfall_pkg/UnlabeledMarker.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/ViconData.h"
 
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 typedef ViconData::ConstPtr ptrToMessage;
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
index 32e7dc02..49dac78b 100755
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
@@ -47,11 +47,11 @@
 #include <QShortcut>
 
 #ifdef CATKIN_MAKE
-#include "d_fall_pps/UnlabeledMarker.h"
-#include "d_fall_pps/CMRead.h"
-#include "d_fall_pps/CrazyflieEntry.h"
-#include "d_fall_pps/CMUpdate.h"
-#include "d_fall_pps/CMCommand.h"
+#include "dfall_pkg/UnlabeledMarker.h"
+#include "dfall_pkg/CMRead.h"
+#include "dfall_pkg/CrazyflieEntry.h"
+#include "dfall_pkg/CMUpdate.h"
+#include "dfall_pkg/CMCommand.h"
 #include "nodes/CentralManagerService.h"
 
 #include <ros/ros.h>
@@ -65,7 +65,7 @@
 #define N_MAX_CRAZYFLIES           20 // protection number
 
 #ifdef CATKIN_MAKE
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 #endif
 
 MainGUIWindow::MainGUIWindow(int argc, char **argv, QWidget *parent) :
@@ -279,7 +279,7 @@ void MainGUIWindow::_init()
 
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle nodeHandle_dfall_root("/dfall");
-    emergencyStopPublisher = nodeHandle_dfall_root.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
+    emergencyStopPublisher = nodeHandle_dfall_root.advertise<dfall_pkg::IntWithHeader>("emergencyStop", 1);
 
     // Initialise the publisher for sending "commands" from here (the master)
     // to all of the agent nodes
@@ -1108,7 +1108,7 @@ void MainGUIWindow::on_all_land_button_clicked()
 // > MOTORS OFF
 void MainGUIWindow::on_all_motors_off_button_clicked()
 {
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     msg.shouldCheckForID = false;
     //commandAllAgentsPublisher.publish(msg);
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
index ab9fd2c5..bbb3f6c1 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
@@ -32,9 +32,9 @@
 
 #include "rosNodeThread_for_managerGUI.h"
 
-#include "d_fall_pps/CMRead.h"
-#include "d_fall_pps/CMUpdate.h"
-#include "d_fall_pps/CMCommand.h"
+#include "dfall_pkg/CMRead.h"
+#include "dfall_pkg/CMUpdate.h"
+#include "dfall_pkg/CMCommand.h"
 
 
 rosNodeThread::rosNodeThread(int argc, char** pArgv, const char * node_name,  QObject* parent)
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 6bf867c8..71d42945 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -50,17 +50,17 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/AreaBounds.h"
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/IntIntService.h"
-#include "d_fall_pps/CMQuery.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/AreaBounds.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/IntIntService.h"
+#include "dfall_pkg/CMQuery.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -187,7 +187,7 @@ private:
     // Get the type and ID of this node
     bool getTypeAndIDParameters();
 	// Fill the head for a message
-    void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
+    void fillIntMessageHeader( dfall_pkg::IntWithHeader & msg );
 
     // > For the CrazyRadio status, received on the
     //   "crazyRadioStatusSubscriber"
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index b77c7ff4..8cf19970 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -16,19 +16,19 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
-//#include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/AreaBounds.h"
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CMQuery.h"
+//#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/AreaBounds.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CMQuery.h"
 
 // Include the shared definitions
 //#include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -106,8 +106,8 @@ private:
     // PRIVATE VARIABLES FOR ROS
 
     // > For the "context" of this agent
-    d_fall_pps::CrazyflieContext m_context;
-    d_fall_pps::AreaBounds m_area;
+    dfall_pkg::CrazyflieContext m_context;
+    dfall_pkg::AreaBounds m_area;
 
     // SUBSRIBER
     // > For the pose data from a motion capture system
@@ -127,7 +127,7 @@ private:
 
     // > For the controller currently operating, received on
     //   "controllerUsedSubscriber"
-    void poseDataReceivedCallback(const d_fall_pps::ViconData& viconData);
+    void poseDataReceivedCallback(const dfall_pkg::ViconData& viconData);
 
     void controllerUsedChangedCallback(const std_msgs::Int32& msg);
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
index 854b26d6..6a0734db 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
@@ -48,17 +48,17 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/AreaBounds.h"
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CMQuery.h"
-#include "d_fall_pps/IntIntService.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/AreaBounds.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CMQuery.h"
+#include "dfall_pkg/IntIntService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -175,7 +175,7 @@ private:
     // PRIVATE VARIABLES FOR ROS
 
     // > For the "context" of this agent
-    d_fall_pps::CrazyflieContext my_context;
+    dfall_pkg::CrazyflieContext my_context;
 
     // PUBLISHERS AND SUBSRIBERS
     // > For Crazyradio commands based on button clicks
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 68763c1d..1e6ed40c 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -17,17 +17,17 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
+//#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -117,10 +117,10 @@ private:
 
 #ifdef CATKIN_MAKE
     // For receiving message that the setpoint was changed
-    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+    void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint);
 
     // Fill the header for a message
-    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+    void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
index 1f81bf8e..6095810a 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
@@ -15,18 +15,18 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/StringWithHeader.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/StringWithHeader.h"
 
 // Include the DFALL service types
-// #include "d_fall_pps/AreaBounds.h"
-// #include "d_fall_pps/CrazyflieContext.h"
-// #include "d_fall_pps/CMQuery.h"
+// #include "dfall_pkg/AreaBounds.h"
+// #include "dfall_pkg/CrazyflieContext.h"
+// #include "dfall_pkg/CMQuery.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
-// using namespace d_fall_pps;
+// using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -122,8 +122,8 @@ private:
 
 #ifdef CATKIN_MAKE
     // Fill the header for a message
-    void fillIntMessageHeader( d_fall_pps::IntWithHeader & msg );
-    void fillStringMessageHeader( d_fall_pps::StringWithHeader & msg );
+    void fillIntMessageHeader( dfall_pkg::IntWithHeader & msg );
+    void fillStringMessageHeader( dfall_pkg::StringWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 91e68c96..2f929f1d 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -51,12 +51,12 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/StringWithHeader.h"
+#include "dfall_pkg/StringWithHeader.h"
 
 #include "nodes/Constants.h"
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 //using namespace std;
 
 #else
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 08769c25..54585fbf 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -43,19 +43,19 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-//#include "d_fall_pps/CustomButtonWithHeader.h"
+//#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+//#include "dfall_pkg/CustomButtonWithHeader.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 #include "nodes/PickerControllerConstants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -282,10 +282,10 @@ private:
 
 #ifdef CATKIN_MAKE
     // For receiving message that the setpoint was changed
-    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+    void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint);
 
     // Fill the header for a message
-    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
+    void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
index 0d881f18..fc331115 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
@@ -44,15 +44,15 @@
 #include <ros/ros.h>
 #include <ros/network.h>
 
-#include "d_fall_pps/CMRead.h"
-#include "d_fall_pps/CMUpdate.h"
-#include "d_fall_pps/CMCommand.h"
+#include "dfall_pkg/CMRead.h"
+#include "dfall_pkg/CMUpdate.h"
+#include "dfall_pkg/CMCommand.h"
 
-//#include "d_fall_pps/UnlabeledMarker.h"
-//#include "d_fall_pps/CrazyflieData.h"
-//#include "d_fall_pps/ViconData.h"
+//#include "dfall_pkg/UnlabeledMarker.h"
+//#include "dfall_pkg/CrazyflieData.h"
+//#include "dfall_pkg/ViconData.h"
 
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 //typedef ViconData::ConstPtr ptrToMessage;
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 32825c7e..01376a3c 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -18,18 +18,18 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CustomButtonWithHeader.h"
+//#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -129,14 +129,14 @@ private:
 
 #ifdef CATKIN_MAKE
     // For receiving message that the setpoint was changed
-    void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+    void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint);
 
     // Publish a message when a custom button is pressed
     void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer);
 
     // Fill the header for a message
-    void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
-    void fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg );
+    void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg );
+    void fillCustomButtonMessageHeader( dfall_pkg::CustomButtonWithHeader & msg );
 
     // Get the paramters that specify the type and ID
     bool getTypeAndIDParameters();
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
index a3cd555c..b3ff17a9 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -51,16 +51,16 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/AreaBounds.h"
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CMQuery.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/AreaBounds.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CMQuery.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #endif
 
@@ -127,7 +127,7 @@ private:
     // PRIVATE VARIABLES FOR ROS
 
     // > For the "context" of this agent
-    d_fall_pps::CrazyflieContext my_context;
+    dfall_pkg::CrazyflieContext my_context;
 
     // PUBLISHERS AND SUBSRIBERS
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index a5fa7abc..2e763165 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -18,19 +18,19 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-//#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/FloatWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CustomButtonWithHeader.h"
+//#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/FloatWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-//using namespace d_fall_pps;
+//using namespace dfall_pkg;
 
 #else
 // Include the shared definitions
@@ -146,14 +146,14 @@ private:
 
     #ifdef CATKIN_MAKE
         // For receiving message that the setpoint was changed
-        void setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint);
+        void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint);
 
         // Publish a message when a custom button is pressed
         //void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer);
 
         // Fill the header for a message
-        void fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg );
-        void fillFloatMessageHeader( d_fall_pps::FloatWithHeader & msg );
+        void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg );
+        void fillFloatMessageHeader( dfall_pkg::FloatWithHeader & msg );
 
         // Get the paramters that specify the type and ID
         bool getTypeAndIDParameters();
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
index 217d153c..36498a1f 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
+++ b/dfall_ws/src/d_fall_pps/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<d_fall_pps::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
 
     // > For Flying state commands based on button clicks
-    flyingStateCommandPublisher = base_nodeHandle.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
+    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
 
     if (m_type == TYPE_AGENT)
     {
@@ -518,7 +518,7 @@ void ConnectStartStopBar::setFlyingState(int new_flying_state)
 void ConnectStartStopBar::on_rf_connect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
@@ -529,7 +529,7 @@ void ConnectStartStopBar::on_rf_connect_button_clicked()
 void ConnectStartStopBar::on_rf_disconnect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
@@ -540,7 +540,7 @@ void ConnectStartStopBar::on_rf_disconnect_button_clicked()
 void ConnectStartStopBar::on_enable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
@@ -551,7 +551,7 @@ void ConnectStartStopBar::on_enable_flying_button_clicked()
 void ConnectStartStopBar::on_disable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
@@ -562,7 +562,7 @@ void ConnectStartStopBar::on_disable_flying_button_clicked()
 void ConnectStartStopBar::on_motors_off_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
@@ -614,8 +614,8 @@ 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<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
-        d_fall_pps::IntIntService getFlyingStateCall;
+        ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("PPSClient/getCurrentFlyingState", false);
+        dfall_pkg::IntIntService getFlyingStateCall;
         getFlyingStateCall.request.data = 0;
         getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
         if(getCurrentFlyingStateService.call(getFlyingStateCall))
@@ -628,8 +628,8 @@ void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
         }
 
         // > Request the current status of the crazy radio
-        ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
-        d_fall_pps::IntIntService getCrazyRadioCall;
+        ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
+        dfall_pkg::IntIntService getCrazyRadioCall;
         getCrazyRadioCall.request.data = 0;
         getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
         if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
@@ -703,7 +703,7 @@ void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
 
 #ifdef CATKIN_MAKE
 // Fill the head for a message
-void ConnectStartStopBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg )
+void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
index 8be696ac..ecbb608e 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
@@ -137,11 +137,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
     // > Publisher for the emergency stop button
-    //emergencyStopPublisher = dfall_root_nodeHandle.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
+    //emergencyStopPublisher = dfall_root_nodeHandle.advertise<dfall_pkg::IntWithHeader>("emergencyStop", 1);
 
     // > For changes in the database that defines {agentID,cfID,flying zone} links
     //databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
-    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+    centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<dfall_pkg::CMQuery>("CentralManagerService/Query", false);
 
 
 #endif
@@ -236,7 +236,7 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
 
         #ifdef CATKIN_MAKE
         // Get also the context
-        d_fall_pps::CMQuery contextCall;
+        dfall_pkg::CMQuery contextCall;
         contextCall.request.studentID = m_ID;
 
         centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
@@ -266,14 +266,14 @@ void ControllerTabs::setObjectNameForDisplayingPoseData( QString object_name )
 #ifdef CATKIN_MAKE
 // > For the controller currently operating, received on
 //   "controllerUsedSubscriber"
-void ControllerTabs::poseDataReceivedCallback(const d_fall_pps::ViconData& viconData)
+void ControllerTabs::poseDataReceivedCallback(const dfall_pkg::ViconData& viconData)
 {
     m_should_search_pose_data_for_object_name_mutex.lock();
     if (m_should_search_pose_data_for_object_name)
     {
-        for(std::vector<d_fall_pps::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
+        for(std::vector<dfall_pkg::CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it)
         {
-            d_fall_pps::CrazyflieData pose_in_global_frame = *it;
+            dfall_pkg::CrazyflieData pose_in_global_frame = *it;
 
             if(pose_in_global_frame.crazyflieName == m_object_name_for_emitting_pose_data)
             {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
index 3f9eb75c..8a1af80b 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
+++ b/dfall_ws/src/d_fall_pps/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<d_fall_pps::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
+    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/crazyRadioCommand", 1);
     // > For updating the "rf_status_label" picture
     crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &CoordinatorRow::crazyRadioStatusCallback, this);
 
@@ -119,24 +119,24 @@ 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<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
+    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
     // > For updating the "flying_state_label" picture
     flyingStateSubscriber = base_nodeHandle.subscribe("PPSClient/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<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+    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);
 
     // > For requesting the current flying state,
     //   this is used only for initialising the icon
-    getCurrentFlyingStateService = base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("PPSClient/getCurrentFlyingState", false);
+    getCurrentFlyingStateService = base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("PPSClient/getCurrentFlyingState", false);
 
     // > For requesting the current state of the Crazy Radio,
     //   this is used only for initialising the icon
-    getCurrentCrazyRadioStateService = base_nodeHandle.serviceClient<d_fall_pps::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
+    getCurrentCrazyRadioStateService = base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
 
 #endif
 
@@ -604,7 +604,7 @@ void CoordinatorRow::loadCrazyflieContext()
 {
     QString qstr_crazyflie_name = "";
 #ifdef CATKIN_MAKE
-    d_fall_pps::CMQuery contextCall;
+    dfall_pkg::CMQuery contextCall;
     contextCall.request.studentID = m_agentID;
     //ROS_INFO_STREAM("StudentID:" << m_agentID);
 
@@ -645,7 +645,7 @@ void CoordinatorRow::loadCrazyflieContext()
 void CoordinatorRow::getCurrentFlyingState()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntIntService getFlyingStateCall;
+    dfall_pkg::IntIntService getFlyingStateCall;
     getFlyingStateCall.request.data = 0;
     getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
     if(getCurrentFlyingStateService.call(getFlyingStateCall))
@@ -665,7 +665,7 @@ void CoordinatorRow::getCurrentFlyingState()
 void CoordinatorRow::getCurrentCrazyRadioState()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntIntService getCrazyRadioCall;
+    dfall_pkg::IntIntService getCrazyRadioCall;
     getCrazyRadioCall.request.data = 0;
     getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
     if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
@@ -761,7 +761,7 @@ void CoordinatorRow::setControllerEnabled(int new_controller)
 void CoordinatorRow::on_rf_connect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
@@ -772,7 +772,7 @@ void CoordinatorRow::on_rf_connect_button_clicked()
 void CoordinatorRow::on_rf_disconnect_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
@@ -783,7 +783,7 @@ void CoordinatorRow::on_rf_disconnect_button_clicked()
 void CoordinatorRow::on_enable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
@@ -794,7 +794,7 @@ void CoordinatorRow::on_enable_flying_button_clicked()
 void CoordinatorRow::on_disable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
@@ -805,7 +805,7 @@ void CoordinatorRow::on_disable_flying_button_clicked()
 void CoordinatorRow::on_motors_off_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 697a2fc5..f43d15fe 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -37,7 +37,7 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
-    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("DefaultControllerService/RequestSetpointChange", 1);
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("DefaultControllerService/RequestSetpointChange", 1);
 
     // SUBSCRIBE TO SETPOINT CHANGES
     // Only if this is an agent GUI
@@ -51,8 +51,8 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     if (m_type == TYPE_AGENT)
     {
         // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<dfall_pkg::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -192,7 +192,7 @@ void DefaultControllerTab::poseDataUnavailableSlot()
 
 
 #ifdef CATKIN_MAKE
-void DefaultControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+void DefaultControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
 {
     // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
     QString qstr = "";
@@ -244,7 +244,7 @@ void DefaultControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -338,7 +338,7 @@ void DefaultControllerTab::on_default_setpoint_button_clicked()
     // "buttonID" field set appropriately
 
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -576,8 +576,8 @@ void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<dfall_pkg::GetSetpointService>("DefaultControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -626,7 +626,7 @@ void DefaultControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
 
 #ifdef CATKIN_MAKE
 // Fill the head for a message
-void DefaultControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+void DefaultControllerTab::fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
index e3afc90f..fa8700c5 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
@@ -30,11 +30,11 @@ EnableControllerLoadYamlBar::EnableControllerLoadYamlBar(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE COMMAND PUBLISHER
-    commandPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::IntWithHeader>("PPSClient/Command", 1);
+    commandPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::IntWithHeader>("PPSClient/Command", 1);
 
     // CREATE THE REQUEST LOAD YAML FILE PUBLISHER
     // Get the node handle to this parameter service
-    m_requestLoadYamlFilenamePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::StringWithHeader>("ParameterService/requestLoadYamlFilename", 1);
+    m_requestLoadYamlFilenamePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::StringWithHeader>("ParameterService/requestLoadYamlFilename", 1);
 #endif
 
 }
@@ -87,7 +87,7 @@ void EnableControllerLoadYamlBar::showHideController_safe_changed()
 void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_SAFE_CONTROLLER;
     this->commandPublisher.publish(msg);
@@ -98,7 +98,7 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_tuning_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_TUNING_CONTROLLER;
     this->commandPublisher.publish(msg);
@@ -109,7 +109,7 @@ void EnableControllerLoadYamlBar::on_enable_tuning_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_PICKER_CONTROLLER;
     this->commandPublisher.publish(msg);
@@ -120,7 +120,7 @@ void EnableControllerLoadYamlBar::on_enable_picker_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_STUDENT_CONTROLLER;
     this->commandPublisher.publish(msg);
@@ -131,7 +131,7 @@ void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
     msg.data = CMD_USE_SAFE_CONTROLLER;
     this->commandPublisher.publish(msg);
@@ -153,7 +153,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_tuning_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
-    d_fall_pps::StringWithHeader yaml_filename_msg;
+    dfall_pkg::StringWithHeader yaml_filename_msg;
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
@@ -169,7 +169,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_picker_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
-    d_fall_pps::StringWithHeader yaml_filename_msg;
+    dfall_pkg::StringWithHeader yaml_filename_msg;
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
@@ -185,7 +185,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
-    d_fall_pps::StringWithHeader yaml_filename_msg;
+    dfall_pkg::StringWithHeader yaml_filename_msg;
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
@@ -201,7 +201,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 {
     #ifdef CATKIN_MAKE
     // Create a local variable for the message
-    d_fall_pps::StringWithHeader yaml_filename_msg;
+    dfall_pkg::StringWithHeader yaml_filename_msg;
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
@@ -263,7 +263,7 @@ void EnableControllerLoadYamlBar::setAgentIDsToCoordinate(QVector<int> agentIDs
 
 #ifdef CATKIN_MAKE
 // Fill the head for a message
-void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg )
+void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
 {
     switch (m_type)
     {
@@ -307,7 +307,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade
 
 #ifdef CATKIN_MAKE
 // Fill the head for a message
-void EnableControllerLoadYamlBar::fillStringMessageHeader( d_fall_pps::StringWithHeader & msg )
+void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index c59fed6f..455a77b4 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -112,7 +112,7 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
-    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("PickerControllerService/RequestSetpointChange", 1);
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("PickerControllerService/RequestSetpointChange", 1);
 
     // SUBSCRIBE TO SETPOINT CHANGES
     // Only if this is an agent GUI
@@ -126,8 +126,8 @@ PickerControllerTab::PickerControllerTab(QWidget *parent) :
     if (m_type == TYPE_AGENT)
     {
         // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<dfall_pkg::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -280,7 +280,7 @@ void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to
     // Publish a ROS message with the setpoint to be requested
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -335,7 +335,7 @@ void PickerControllerTab::publish_request_setpoint_change_for_state(int state_to
 
 
 #ifdef CATKIN_MAKE
-void PickerControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+void PickerControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
 {
     // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
     QString qstr = "";
@@ -1790,8 +1790,8 @@ void PickerControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<dfall_pkg::GetSetpointService>("PickerControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -1841,7 +1841,7 @@ void PickerControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void PickerControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+void PickerControllerTab::fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
index 63d73e66..5072e14e 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
@@ -32,11 +32,11 @@
 
 #include "rosNodeThread_for_flyingAgentGUI.h"
 
-// #include "d_fall_pps/CMRead.h"
-// #include "d_fall_pps/CMUpdate.h"
-// #include "d_fall_pps/CMCommand.h"
+// #include "dfall_pkg/CMRead.h"
+// #include "dfall_pkg/CMUpdate.h"
+// #include "dfall_pkg/CMCommand.h"
 
-// using namespace d_fall_pps;
+// using namespace dfall_pkg;
 
 
 rosNodeThread::rosNodeThread(int argc, char** pArgv, const char * node_name,  QObject* parent)
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index efc5d999..c7547f9d 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -37,7 +37,7 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
-    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("StudentControllerService/RequestSetpointChange", 1);
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("StudentControllerService/RequestSetpointChange", 1);
 
     // SUBSCRIBE TO SETPOINT CHANGES
     // Only if this is an agent GUI
@@ -47,15 +47,15 @@ StudentControllerTab::StudentControllerTab(QWidget *parent) :
     }
 
     // CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
-    customButtonPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::CustomButtonWithHeader>("StudentControllerService/CustomButtonPressed", 1);
+    customButtonPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::CustomButtonWithHeader>("StudentControllerService/CustomButtonPressed", 1);
 
     // GET THE CURRENT SETPOINT
     // Only if this is an agent GUI
     if (m_type == TYPE_AGENT)
     {
         // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<dfall_pkg::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -101,7 +101,7 @@ StudentControllerTab::~StudentControllerTab()
 void StudentControllerTab::publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer)
 {
     // Initialise the message as a local variable
-    d_fall_pps::CustomButtonWithHeader msg;
+    dfall_pkg::CustomButtonWithHeader msg;
     // Fill the header of the message
     fillCustomButtonMessageHeader( msg );
     // Fill in the button index
@@ -274,7 +274,7 @@ void StudentControllerTab::poseDataUnavailableSlot()
 
 
 #ifdef CATKIN_MAKE
-void StudentControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+void StudentControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
 {
     // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
     QString qstr = "";
@@ -326,7 +326,7 @@ void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -420,7 +420,7 @@ void StudentControllerTab::on_default_setpoint_button_clicked()
     // "buttonID" field set appropriately
 
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -685,8 +685,8 @@ void StudentControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
         // // > Request the current setpoint
-        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
-        d_fall_pps::GetSetpointService getSetpointCall;
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<dfall_pkg::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
         getSetpointCall.request.data = 0;
         getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
         if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -735,7 +735,7 @@ void StudentControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void StudentControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+void StudentControllerTab::fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg )
 {
     switch (m_type)
     {
@@ -777,7 +777,7 @@ void StudentControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHe
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void StudentControllerTab::fillCustomButtonMessageHeader( d_fall_pps::CustomButtonWithHeader & msg )
+void StudentControllerTab::fillCustomButtonMessageHeader( dfall_pkg::CustomButtonWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 1c8f5232..fb731181 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -93,11 +93,11 @@ TopBanner::TopBanner(QWidget *parent) :
     ros::NodeHandle dfall_root_nodeHandle("/dfall");
 
     // > Publisher for the emergency stop button
-    emergencyStopPublisher = dfall_root_nodeHandle.advertise<d_fall_pps::IntWithHeader>("emergencyStop", 1);
+    emergencyStopPublisher = dfall_root_nodeHandle.advertise<dfall_pkg::IntWithHeader>("emergencyStop", 1);
 
 	// > For changes in the database that defines {agentID,cfID,flying zone} links
 	databaseChangedSubscriber = dfall_root_nodeHandle.subscribe("CentralManagerService/DBChanged", 1, &TopBanner::databaseChangedCallback, this);;
-	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<d_fall_pps::CMQuery>("CentralManagerService/Query", false);
+	centralManagerDatabaseService = dfall_root_nodeHandle.serviceClient<dfall_pkg::CMQuery>("CentralManagerService/Query", false);
 #endif
 
 
@@ -170,7 +170,7 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
     QString qstr_crazyflie_name = "";
 
 #ifdef CATKIN_MAKE
-	d_fall_pps::CMQuery contextCall;
+	dfall_pkg::CMQuery contextCall;
 	contextCall.request.studentID = ID_to_request_from_database;
 	//ROS_INFO_STREAM("StudentID:" << m_agentID);
 
@@ -248,7 +248,7 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
 void TopBanner::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
-    d_fall_pps::IntWithHeader msg;
+    dfall_pkg::IntWithHeader msg;
     msg.shouldCheckForID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->emergencyStopPublisher.publish(msg);
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index 24ea87a3..afcfb970 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -43,7 +43,7 @@ TuningControllerTab::TuningControllerTab(QWidget *parent) :
     ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
 
     // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
-    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::SetpointWithHeader>("TuningControllerService/RequestSetpointChange", 1);
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("TuningControllerService/RequestSetpointChange", 1);
 
     // SUBSCRIBE TO SETPOINT CHANGES
     // Only if this is an agent GUI
@@ -54,18 +54,18 @@ TuningControllerTab::TuningControllerTab(QWidget *parent) :
 
 
     // CREATE THE NEW GAIN PUBLISHER
-    requestNewGainChangePublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::FloatWithHeader>("TuningControllerService/RequestGainChange", 1);
+    requestNewGainChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::FloatWithHeader>("TuningControllerService/RequestGainChange", 1);
 
     // CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
-    //customButtonPublisher = nodeHandle_for_this_gui.advertise<d_fall_pps::CustomButtonWithHeader>("TuningControllerService/CustomButtonPressed", 1);
+    //customButtonPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::CustomButtonWithHeader>("TuningControllerService/CustomButtonPressed", 1);
 
     // GET THE CURRENT SETPOINT
     // Only if this is an agent GUI
     if (m_type == TYPE_AGENT)
     {
 //        // > Request the current setpoint
-//        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<d_fall_pps::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
-//        d_fall_pps::GetSetpointService getSetpointCall;
+//        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<dfall_pkg::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
+//        dfall_pkg::GetSetpointService getSetpointCall;
 //        getSetpointCall.request.data = 0;
 //        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
 //        if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -202,7 +202,7 @@ void TuningControllerTab::poseDataUnavailableSlot()
 
 
 #ifdef CATKIN_MAKE
-void TuningControllerTab::setpointChangedCallback(const d_fall_pps::SetpointWithHeader& newSetpoint)
+void TuningControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
 {
 //    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
 //    QString qstr = "";
@@ -254,7 +254,7 @@ void TuningControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    d_fall_pps::SetpointWithHeader msg;
+    dfall_pkg::SetpointWithHeader msg;
 
     // Fill the header of the message
     fillSetpointMessageHeader( msg );
@@ -347,7 +347,7 @@ void TuningControllerTab::publishGain(float new_gain)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
-    d_fall_pps::FloatWithHeader msg;
+    dfall_pkg::FloatWithHeader msg;
 
     // Fill the header of the message
     fillFloatMessageHeader( msg );
@@ -439,8 +439,8 @@ void TuningControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
 //        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
 //        // // > Request the current setpoint
-//        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<d_fall_pps::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
-//        d_fall_pps::GetSetpointService getSetpointCall;
+//        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<dfall_pkg::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
+//        dfall_pkg::GetSetpointService getSetpointCall;
 //        getSetpointCall.request.data = 0;
 //        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
 //        if(getCurrentSetpointServiceClient.call(getSetpointCall))
@@ -489,7 +489,7 @@ void TuningControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool s
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void TuningControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHeader & msg )
+void TuningControllerTab::fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg )
 {
     switch (m_type)
     {
@@ -531,7 +531,7 @@ void TuningControllerTab::fillSetpointMessageHeader( d_fall_pps::SetpointWithHea
 
 #ifdef CATKIN_MAKE
 // Fill the header for a message
-void TuningControllerTab::fillFloatMessageHeader( d_fall_pps::FloatWithHeader & msg )
+void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & msg )
 {
     switch (m_type)
     {
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
index 48d6bda3..608102b2 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
@@ -41,11 +41,11 @@
 
 #include "rosNodeThread_for_studentGUI.h"
 
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/SetpointV2.h"
-#include "d_fall_pps/ViconSubscribeObjectName.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/SetpointV2.h"
+#include "dfall_pkg/ViconSubscribeObjectName.h"
 
 
 // Types of controllers being used:
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
index a7bb5874..823094a0 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
@@ -43,11 +43,11 @@
 
 #include <ros/ros.h>
 #include <ros/network.h>
-#include "d_fall_pps/UnlabeledMarker.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/ViconData.h"
+#include "dfall_pkg/UnlabeledMarker.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/ViconData.h"
 
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 typedef ViconData::ConstPtr ptrToMessage;
 
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
index ce661742..aed81191 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
@@ -38,11 +38,11 @@
 #include <ros/network.h>
 #include <ros/package.h>
 
-#include "d_fall_pps/CMQuery.h"
+#include "dfall_pkg/CMQuery.h"
 
-#include "d_fall_pps/ViconData.h"
+#include "dfall_pkg/ViconData.h"
 
-#include "d_fall_pps/CustomButton.h"
+#include "dfall_pkg/CustomButton.h"
 
 MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     QMainWindow(parent),
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
index ce716b2d..ed87c889 100644
--- a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
+++ b/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
@@ -32,9 +32,9 @@
 
 #include "rosNodeThread_for_studentGUI.h"
 
-#include "d_fall_pps/CMRead.h"
-#include "d_fall_pps/CMUpdate.h"
-#include "d_fall_pps/CMCommand.h"
+#include "dfall_pkg/CMRead.h"
+#include "dfall_pkg/CMUpdate.h"
+#include "dfall_pkg/CMCommand.h"
 
 
 rosNodeThread::rosNodeThread(int argc, char** pArgv, const char * node_name, QObject* parent)
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
index 2a66010a..3746f705 100755
--- a/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
+++ b/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
@@ -33,12 +33,12 @@
 #    ----------------------------------------------------------------------------------
 
 
-import roslib; roslib.load_manifest('d_fall_pps')
+import roslib; roslib.load_manifest('dfall_pkg')
 import rospy
 from std_msgs.msg import Int32
-from d_fall_pps.msg import ControlCommand
-from d_fall_pps.msg import IntWithHeader
-from d_fall_pps.srv import IntIntService
+from dfall_pkg.msg import ControlCommand
+from dfall_pkg.msg import IntWithHeader
+from dfall_pkg.srv import IntIntService
 
 
 # General import
@@ -101,7 +101,7 @@ CMD_CRAZYFLY_LAND =         12
 CMD_CRAZYFLY_MOTORS_OFF =   13
 
 rp = RosPack()
-record_file = rp.get_path('d_fall_pps') + '/LoggingOnboard.bag'
+record_file = rp.get_path('dfall_pkg') + '/LoggingOnboard.bag'
 rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf')
 rospy.loginfo(record_file)
 bag = rosbag.Bag(record_file, 'w')
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py b/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
index c5fa4f44..5cc25317 100755
--- a/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
+++ b/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
@@ -1,9 +1,9 @@
 #!/usr/bin/env python
 # -*- coding: utf-8 -*-
 
-# import roslib; roslib.load_manifest('d_fall_pps')
+# import roslib; roslib.load_manifest('dfall_pkg')
 # import rospy
-# from d_fall_pps.msg import ControlCommand
+# from dfall_pkg.msg import ControlCommand
 # from std_msgs.msg import Int32
 
 
@@ -62,7 +62,7 @@ CMD_CRAZYFLY_LAND =         4
 CMD_CRAZYFLY_MOTORS_OFF =   5
 
 # rp = RosPack()
-# record_file = rp.get_path('d_fall_pps') + '/LoggingOnboard.bag'
+# record_file = rp.get_path('dfall_pkg') + '/LoggingOnboard.bag'
 # rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf')
 # rospy.loginfo(record_file)
 # bag = rosbag.Bag(record_file, 'w')
diff --git a/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
index f92f393d..f61481cf 100644
--- a/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
+++ b/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
@@ -55,13 +55,13 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
+#include "dfall_pkg/IntWithHeader.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 //using namespace std;
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
index 9d576b5b..43f3740b 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
@@ -55,14 +55,14 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
+#include "dfall_pkg/IntWithHeader.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
 #include "classes/GetParamtersAndNamespaces.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 //using namespace std;
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h b/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
index db93514f..0c02248e 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
@@ -50,14 +50,14 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CrazyflieDB.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CrazyflieDB.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/CMRead.h"
-#include "d_fall_pps/CMQuery.h"
-#include "d_fall_pps/CMUpdate.h"
-#include "d_fall_pps/CMCommand.h"
+#include "dfall_pkg/CMRead.h"
+#include "dfall_pkg/CMQuery.h"
+#include "dfall_pkg/CMUpdate.h"
+#include "dfall_pkg/CMCommand.h"
 
 // Include other classes
 #include "CrazyflieIO.h"
@@ -95,7 +95,7 @@
 #define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR    4
 
 
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 using namespace std;
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h b/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
index fa4e2573..d28f5656 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
@@ -30,9 +30,9 @@
 //    ----------------------------------------------------------------------------------
 
 
-#include "d_fall_pps/CrazyflieDB.h"
+#include "dfall_pkg/CrazyflieDB.h"
 
-namespace d_fall_pps {
+namespace dfall_pkg {
 
 void readCrazyflieDB(CrazyflieDB& cfdb);
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
index 612f266d..23450feb 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
@@ -56,19 +56,19 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-//#include "d_fall_pps/StringWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CustomButtonWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
+#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/LoadYamlFromFilename.h"
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/LoadYamlFromFilename.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -84,7 +84,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
index e82252a9..111c7e47 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
@@ -56,14 +56,14 @@
 #include <std_msgs/String.h>
 
 //the generated structs from the msg-files have to be included
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/StringWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
+#include "dfall_pkg/CustomButton.h"
 
 // Include the Parameter Service shared definitions
 #include "nodes/Constants.h"
@@ -79,7 +79,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h b/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
index 7efa2a65..d39549bc 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -52,17 +52,17 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/Setpoint.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/Setpoint.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/CMQuery.h"
-#include "d_fall_pps/IntIntService.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/CMQuery.h"
+#include "dfall_pkg/IntIntService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -78,7 +78,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h b/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
index 75d51729..92dda4e3 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
@@ -54,12 +54,12 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-//#include "d_fall_pps/FloatWithHeader.h"
-#include "d_fall_pps/StringWithHeader.h"
+#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/FloatWithHeader.h"
+#include "dfall_pkg/StringWithHeader.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/LoadYamlFromFilename.h"
+#include "dfall_pkg/LoadYamlFromFilename.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -80,7 +80,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 //using namespace std;
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
index 67173f96..e7cfd58f 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
@@ -56,24 +56,24 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-//#include "d_fall_pps/StringWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-//#include "d_fall_pps/CustomButtonWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-//#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
+#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+//#include "dfall_pkg/CustomButtonWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+//#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
 
 //the generated structs from the msg-files have to be included
-// #include "d_fall_pps/Setpoint.h"
-// #include "d_fall_pps/SetpointV2.h"
-// #include "d_fall_pps/ControlCommand.h"
-// #include "d_fall_pps/CustomButton.h"
+// #include "dfall_pkg/Setpoint.h"
+// #include "dfall_pkg/SetpointV2.h"
+// #include "dfall_pkg/ControlCommand.h"
+// #include "dfall_pkg/CustomButton.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/LoadYamlFromFilename.h"
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/LoadYamlFromFilename.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -90,7 +90,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
index 8e9f783c..968f78ec 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
@@ -56,13 +56,13 @@
 #include <ros/package.h>
 
 //the generated structs from the msg-files have to be included
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
-#include "d_fall_pps/CustomButton.h"
-#include "d_fall_pps/ViconSubscribeObjectName.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
+#include "dfall_pkg/CustomButton.h"
+#include "dfall_pkg/ViconSubscribeObjectName.h"
 
 // Include the Parameter Service shared definitions
 #include "nodes/Constants.h"
@@ -163,7 +163,7 @@
 #define LQR_ANGLE_MODE  2
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 //    ----------------------------------------------------------------------------------
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
index 343141f7..3a540f29 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
@@ -55,11 +55,11 @@
 //#include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/CrazyflieData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/CrazyflieData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
 
 
 // Include the shared definitions
@@ -73,7 +73,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
index 7dccc05a..820cacfb 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
@@ -56,19 +56,19 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-//#include "d_fall_pps/StringWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-#include "d_fall_pps/CustomButtonWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
+#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/LoadYamlFromFilename.h"
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/LoadYamlFromFilename.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -84,7 +84,7 @@
 
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
index 7184651d..b7f2002e 100644
--- a/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
+++ b/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
@@ -61,20 +61,20 @@
 #include <std_msgs/String.h>
 
 // Include the DFALL message types
-#include "d_fall_pps/IntWithHeader.h"
-#include "d_fall_pps/FloatWithHeader.h"
-//#include "d_fall_pps/StringWithHeader.h"
-#include "d_fall_pps/SetpointWithHeader.h"
-//#include "d_fall_pps/CustomButtonWithHeader.h"
-#include "d_fall_pps/ViconData.h"
-//#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
+#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/FloatWithHeader.h"
+//#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+//#include "dfall_pkg/CustomButtonWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+//#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
 
 // Include the DFALL service types
-#include "d_fall_pps/LoadYamlFromFilename.h"
-#include "d_fall_pps/GetSetpointService.h"
+#include "dfall_pkg/LoadYamlFromFilename.h"
+#include "dfall_pkg/GetSetpointService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
@@ -86,13 +86,13 @@
 
 
 // //the generated structs from the msg-files have to be included
-// #include "d_fall_pps/ViconData.h"
-// #include "d_fall_pps/Setpoint.h"
-// #include "d_fall_pps/ControlCommand.h"
-// #include "d_fall_pps/Controller.h"
-// #include "d_fall_pps/DebugMsg.h"
-// #include "d_fall_pps/CustomButton.h"
-// #include "d_fall_pps/ViconSubscribeObjectName.h"
+// #include "dfall_pkg/ViconData.h"
+// #include "dfall_pkg/Setpoint.h"
+// #include "dfall_pkg/ControlCommand.h"
+// #include "dfall_pkg/Controller.h"
+// #include "dfall_pkg/DebugMsg.h"
+// #include "dfall_pkg/CustomButton.h"
+// #include "dfall_pkg/ViconSubscribeObjectName.h"
 
 // // Include the Parameter Service shared definitions
 // #include "nodes/Constants.h"
@@ -193,7 +193,7 @@
 #define LQR_ANGLE_MODE  2
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 //    ----------------------------------------------------------------------------------
diff --git a/dfall_ws/src/d_fall_pps/launch/Agent.launch b/dfall_ws/src/d_fall_pps/launch/Agent.launch
index 2c978143..24882047 100755
--- a/dfall_ws/src/d_fall_pps/launch/Agent.launch
+++ b/dfall_ws/src/d_fall_pps/launch/Agent.launch
@@ -13,23 +13,23 @@
     <!-- <param name="param" value="$(arg agentID)"/> -->
 
     <!-- Example of how to specify the agentID from command line -->
-    <!-- roslaunch d_fall_pps agentID:=1 -->
+    <!-- roslaunch dfall_pkg agentID:=1 -->
 
     <group ns="$(eval 'agent' + str(agentID).zfill(3))">
 
 		<!-- CRAZY RADIO -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "CrazyRadio"
 			output = "screen"
 			type   = "CrazyRadio.py"
 			>
-			<rosparam command="load" file="$(find d_fall_pps)/param/BatteryMonitor.yaml" />
+			<rosparam command="load" file="$(find dfall_pkg)/param/BatteryMonitor.yaml" />
 		</node>
 
 		<!-- PPS CLIENT -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "PPSClient"
 			output = "screen"
 			type   = "PPSClient"
@@ -40,7 +40,7 @@
 
 		<!-- BATTERY MONITOR -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "BatteryMonitor"
 			output = "screen"
 			type   = "BatteryMonitor"
@@ -49,7 +49,7 @@
 
 		<!-- DEFAULT CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "DefaultControllerService"
 			output = "screen"
 			type   = "DefaultControllerService"
@@ -58,7 +58,7 @@
 
 		<!-- SAFE CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "SafeControllerService"
 			output = "screen"
 			type   = "SafeControllerService"
@@ -67,7 +67,7 @@
 
 		<!-- DEMO CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "DemoControllerService"
 			output = "screen"
 			type   = "DemoControllerService"
@@ -76,7 +76,7 @@
 
 		<!-- STUDENT CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "StudentControllerService"
 			output = "screen"
 			type   = "StudentControllerService"
@@ -85,7 +85,7 @@
 
 		<!-- REMOTE CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "RemoteControllerService"
 			output = "screen"
 			type   = "RemoteControllerService"
@@ -94,7 +94,7 @@
 
 		<!-- TUNING CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "TuningControllerService"
 			output = "screen"
 			type   = "TuningControllerService"
@@ -103,7 +103,7 @@
 
 		<!-- PICKER CONTROLLER -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "PickerControllerService"
 			output = "screen"
 			type   = "PickerControllerService"
@@ -112,7 +112,7 @@
 
 		<!-- PARAMETER SERVICE -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "ParameterService"
 			output = "screen"
 			type   = "ParameterService"
@@ -121,32 +121,32 @@
 			<param name="agentID"  value="$(arg agentID)" />
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/ClientConfig.yaml"
+				file    = "$(find dfall_pkg)/param/ClientConfig.yaml"
 				ns      = "ClientConfig"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
+				file    = "$(find dfall_pkg)/param/BatteryMonitor.yaml"
 				ns      = "BatteryMonitor"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/SafeController.yaml"
+				file    = "$(find dfall_pkg)/param/SafeController.yaml"
 				ns      = "SafeController"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/RemoteController.yaml"
+				file    = "$(find dfall_pkg)/param/RemoteController.yaml"
 				ns      = "RemoteController"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/TuningController.yaml"
+				file    = "$(find dfall_pkg)/param/TuningController.yaml"
 				ns      = "TuningController"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/PickerController.yaml"
+				file    = "$(find dfall_pkg)/param/PickerController.yaml"
 				ns      = "PickerController"
 			/>
 		</node>
@@ -155,7 +155,7 @@
 		<!-- AGENT GUI (aka. the "student GUI") -->
 		<group if="$(arg withGUI)">
 			<node
-				pkg    = "d_fall_pps"
+				pkg    = "dfall_pkg"
 				name   = "flyingAgentGUI"
 				output = "screen"
 				type   = "flyingAgentGUI"
diff --git a/dfall_ws/src/d_fall_pps/launch/Coordinator.launch b/dfall_ws/src/d_fall_pps/launch/Coordinator.launch
index 290bd237..61dacd38 100755
--- a/dfall_ws/src/d_fall_pps/launch/Coordinator.launch
+++ b/dfall_ws/src/d_fall_pps/launch/Coordinator.launch
@@ -10,14 +10,14 @@
 	<!-- <param name="param" value="$(arg coordID)"/> -->
 
 	<!-- Example of how to specify the coordID from command line -->
-	<!-- roslaunch d_fall_pps coordID:=001 -->
+	<!-- roslaunch dfall_pkg coordID:=001 -->
 
 	<group ns="coord$(arg coordID)">
 
 		<!-- COORDINATOR GUI -->
 		<group if="$(arg withGUI)">
 			<node
-				pkg="d_fall_pps"
+				pkg="dfall_pkg"
 				name="flyingAgentGUI"
 				output="screen"
 				type="flyingAgentGUI"
@@ -30,7 +30,7 @@
 
 		<!-- PARAMETER SERVICE -->
 		<node
-			pkg    = "d_fall_pps"
+			pkg    = "dfall_pkg"
 			name   = "ParameterService"
 			output = "screen"
 			type   = "ParameterService"
@@ -39,12 +39,12 @@
 			<param name="coordID"  value="$(arg coordID)" />
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/BatteryMonitor.yaml"
+				file    = "$(find dfall_pkg)/param/BatteryMonitor.yaml"
 				ns      = "YamlFileNames"
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find d_fall_pps)/param/ClientConfig.yaml"
+				file    = "$(find dfall_pkg)/param/ClientConfig.yaml"
 				ns      = "SafeController"
 			/>
 		</node>
diff --git a/dfall_ws/src/d_fall_pps/launch/Teacher.launch b/dfall_ws/src/d_fall_pps/launch/Teacher.launch
index 609043d1..b093995b 100755
--- a/dfall_ws/src/d_fall_pps/launch/Teacher.launch
+++ b/dfall_ws/src/d_fall_pps/launch/Teacher.launch
@@ -2,7 +2,7 @@
 
 	<!-- CENTRAL MANAGER -->
 	<node
-		pkg="d_fall_pps"
+		pkg="dfall_pkg"
 		name="CentralManagerService"
 		output="screen"
 		type="CentralManagerService"
@@ -11,17 +11,17 @@
 
 	<!-- VICON DATA PUBLISHER -->
 	<node
-		pkg="d_fall_pps"
+		pkg="dfall_pkg"
 		name="ViconDataPublisher"
 		output="screen"
 		type="ViconDataPublisher"
 		>
-		<rosparam command="load" file="$(find d_fall_pps)/param/ViconConfig.yaml" />
+		<rosparam command="load" file="$(find dfall_pkg)/param/ViconConfig.yaml" />
 	</node>
 
 	<!-- TEACHER GUI -->
 	<node
-		pkg="d_fall_pps"
+		pkg="dfall_pkg"
 		name="my_GUI"
 		output="screen"
 		type="my_GUI"
diff --git a/dfall_ws/src/d_fall_pps/package.xml b/dfall_ws/src/d_fall_pps/package.xml
index 91b8fcda..12f6dea7 100755
--- a/dfall_ws/src/d_fall_pps/package.xml
+++ b/dfall_ws/src/d_fall_pps/package.xml
@@ -1,8 +1,8 @@
 <?xml version="1.0"?>
 <package>
-  <name>d_fall_pps</name>
+  <name>dfall_pkg</name>
   <version>0.0.0</version>
-  <description>The d_fall_pps package</description>
+  <description>The dfall_pkg package</description>
 
   <!-- One maintainer tag required, multiple allowed, one person per tag --> 
   <!-- Example:  -->
@@ -19,7 +19,7 @@
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
   <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/d_fall_pps</url> -->
+  <!-- <url type="website">http://wiki.ros.org/dfall_pkg</url> -->
 
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
diff --git a/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint b/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
index 73bb4fa7..0ec71316 100755
--- a/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
+++ b/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
@@ -2,6 +2,6 @@
 
 if [ "$#" -ne 4 ]
 then echo "usage: safe_controller_setpoint <x> <y> <z> <yaw>"
-else rostopic pub -1 /$ROS_NAMESPACE/SafeControllerService/Setpoint d_fall_pps/Setpoint "{x: $1, y: $2, z: $3, yaw: $4}";
+else rostopic pub -1 /$ROS_NAMESPACE/SafeControllerService/Setpoint dfall_pkg/Setpoint "{x: $1, y: $2, z: $3, yaw: $4}";
 fi
 
diff --git a/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp b/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
index e5e0c03f..0f862521 100644
--- a/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
+++ b/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
@@ -44,13 +44,13 @@
 #include <fstream>
 #include <string>
 
-#include "d_fall_pps/CrazyflieContext.h"
-#include "d_fall_pps/CrazyflieEntry.h"
-#include "d_fall_pps/CrazyflieDB.h"
+#include "dfall_pkg/CrazyflieContext.h"
+#include "dfall_pkg/CrazyflieEntry.h"
+#include "dfall_pkg/CrazyflieDB.h"
 
 using namespace std;
 
-namespace d_fall_pps {
+namespace dfall_pkg {
 
 string escape(string input) {
     string escaped;
@@ -116,7 +116,7 @@ vector<string> nextLine(istream& str) {
 }
 
 string getCrazyflieDBPath() {
-    string packagePath = ros::package::getPath("d_fall_pps") + "/";
+    string packagePath = ros::package::getPath("dfall_pkg") + "/";
     string dbFile = packagePath + "param/Crazyflie.db";
     return dbFile;
 }
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
index db199ea1..2dedaf61 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
@@ -976,8 +976,8 @@ int main(int argc, char* argv[]) {
 	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
 
 	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-	//     "using namespace d_fall_pps;"
+	// to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+	//     "using namespace dfall_pkg;"
 	// in the "DEFINES" section at the top of this file.
 	//ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
index d8b8aebf..bfc3bebc 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
@@ -1888,8 +1888,8 @@ int main(int argc, char* argv[]) {
 	ros::ServiceServer service = nodeHandle.advertiseService("DemoController", calculateControlOutput);
 
 	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-	// to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-	//     "using namespace d_fall_pps;"
+	// to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+	//     "using namespace dfall_pkg;"
 	// in the "DEFINES" section at the top of this file.
 	ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
index eb5b88ce..5aa78721 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
@@ -51,11 +51,11 @@
 #include <ros/package.h>
 
 //the generated structs from the msg-files have to be included
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/Setpoint.h"
-#include "d_fall_pps/ControlCommand.h"
-#include "d_fall_pps/Controller.h"
-#include "d_fall_pps/DebugMsg.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
 
 // Include the Parameter Service shared definitions
 #include "nodes/Constants.h"
@@ -119,7 +119,7 @@ float estimator_frequency = 200;
 #define LQR_ANGLE_MODE  2
 
 // Namespacing the package
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 
 //    ----------------------------------------------------------------------------------
@@ -956,8 +956,8 @@ int main(int argc, char* argv[]) {
     ros::ServiceServer service = nodeHandle.advertiseService("MpcController", calculateControlOutput);
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
+    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+    //     "using namespace dfall_pkg;"
     // in the "DEFINES" section at the top of this file.
     ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
index a92c51dd..3e6a8057 100755
--- a/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
@@ -1373,7 +1373,7 @@ int main(int argc, char* argv[])
 
     // SafeControllerServicePublisher:
     ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
-    safeControllerServiceSetpointPublisher = namespaceNodeHandle.advertise<d_fall_pps::Setpoint>("SafeControllerService/Setpoint", 1);
+    safeControllerServiceSetpointPublisher = namespaceNodeHandle.advertise<dfall_pkg::Setpoint>("SafeControllerService/Setpoint", 1);
     ros::Subscriber controllerSetpointSubscriber = namespaceNodeHandle.subscribe("student_GUI/ControllerSetpoint", 1, controllerSetPointCallback);
     ros::Subscriber safeSetpointSubscriber = namespaceNodeHandle.subscribe("SafeControllerService/Setpoint", 1, safeSetPointCallback);
 
@@ -1421,7 +1421,7 @@ int main(int argc, char* argv[])
 
     // Open a ROS "bag" to store data for post-analysis
 	// std::string package_path;
-	// package_path = ros::package::getPath("d_fall_pps") + "/";
+	// package_path = ros::package::getPath("dfall_pkg") + "/";
 	// ROS_INFO_STREAM(package_path);
 	// std::string record_file = package_path + "LoggingPPSClient.bag";
 	// bag.open(record_file, rosbag::bagmode::Write);
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
index 917e7fa0..fe88d56e 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
@@ -96,12 +96,12 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
     ros::NodeHandle nodeHandle("~");
     // Instantiate a local variable for the command string that will be passed to the "system":
     std::string cmd;
-    // Get the abolute path to "d_fall_pps":
-    std::string d_fall_pps_path = ros::package::getPath("d_fall_pps");
+    // Get the abolute path to "dfall_pkg":
+    std::string dfall_pkg_path = ros::package::getPath("dfall_pkg");
     // Construct the system command string for (re-)loading the parameters:
-    cmd = "rosparam load " + d_fall_pps_path + "/param" + "/" + yaml_filename_to_load + ".yaml " + m_base_namespace + "/" + yaml_filename_to_load;
+    cmd = "rosparam load " + dfall_pkg_path + "/param" + "/" + yaml_filename_to_load + ".yaml " + m_base_namespace + "/" + yaml_filename_to_load;
     // Let the user know what is about to happen
-    ROS_INFO_STREAM("[PARAMETER SERVICE] The following path will be used for locating the .yaml file: " << d_fall_pps_path  << " The comand line string sent to the 'system' is: " << cmd );
+    ROS_INFO_STREAM("[PARAMETER SERVICE] The following path will be used for locating the .yaml file: " << dfall_pkg_path  << " The comand line string sent to the 'system' is: " << cmd );
     // Send the "load yaml" command to the system
     system(cmd.c_str());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
index 63346c0f..f814b8d0 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
@@ -1912,8 +1912,8 @@ int main(int argc, char* argv[]) {
     ros::ServiceServer service = nodeHandle.advertiseService("PickerController", calculateControlOutput);
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
+    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+    //     "using namespace dfall_pkg;"
     // in the "DEFINES" section at the top of this file.
     //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
index d7fa4a2d..2ae0b709 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
@@ -1642,8 +1642,8 @@ int main(int argc, char* argv[]) {
     ros::ServiceServer service = nodeHandle.advertiseService("RemoteController", calculateControlOutput);
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
+    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+    //     "using namespace dfall_pkg;"
     // in the "DEFINES" section at the top of this file.
     ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
index d5bea535..968ecc3a 100755
--- a/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
@@ -541,7 +541,7 @@ int main(int argc, char* argv[]) {
     ROS_INFO("[SAFE CONTROLLER] Service ready :-)");
     
 	// std::string package_path;
-	// package_path = ros::package::getPath("d_fall_pps") + "/";
+	// package_path = ros::package::getPath("dfall_pkg") + "/";
 	// ROS_INFO_STREAM(package_path);
 	// std::string record_file = package_path + "LoggingSafeController.bag";
 	// bag.open(record_file, rosbag::bagmode::Write);
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
index 4df4b3d6..67ac27e2 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
@@ -1040,8 +1040,8 @@ int main(int argc, char* argv[]) {
 	ros::Subscriber customCommandReceivedSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("StudentControllerService/CustomButtonPressed", 1, customCommandReceivedCallback);
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
+    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+    //     "using namespace dfall_pkg;"
     // in the "DEFINES" section at the top of this file.
     //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
index 05ff0300..d62e2260 100644
--- a/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
@@ -1775,8 +1775,8 @@ int main(int argc, char* argv[]) {
 
 
     // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "d_fall_pps" as specified by the line:
-    //     "using namespace d_fall_pps;"
+    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
+    //     "using namespace dfall_pkg;"
     // in the "DEFINES" section at the top of this file.
     //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
 
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp b/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
index a6c1f4e6..6107a8e3 100755
--- a/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
+++ b/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
@@ -33,14 +33,14 @@
 #include <string.h>
 #include "DataStreamClient.h"
 #include "ros/ros.h"
-#include "d_fall_pps/ViconData.h"
-#include "d_fall_pps/UnlabeledMarker.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/UnlabeledMarker.h"
 
 // #define TESTING_FAKE_DATA
 
 // notice that unit here are in milimeters
 using namespace ViconDataStreamSDK::CPP;
-using namespace d_fall_pps;
+using namespace dfall_pkg;
 
 int main(int argc, char* argv[]) {
 
-- 
GitLab


From c71605be90f17bb4a95beae7375bcc91ca071a53 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 7 Feb 2019 22:17:27 +0100
Subject: [PATCH 53/87] Change folder name from d_fall_pps to dfall_pkg

---
 .gitignore                                          |   4 ++--
 .../src/{d_fall_pps => dfall_pkg}/CMakeLists.txt    |   0
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro              |   0
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc              |   0
 .../GUI_Qt/CrazyFlyGUI/images/center_rect.svg       |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone.png             | Bin
 .../GUI_Qt/CrazyFlyGUI/images/drone.svg             |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg    |   0
 .../GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg   |   0
 .../GUI_Qt/CrazyFlyGUI/include/CFLinker.h           |   0
 .../GUI_Qt/CrazyFlyGUI/include/centerMarker.h       |   0
 .../GUI_Qt/CrazyFlyGUI/include/channelLUT.h         |   0
 .../GUI_Qt/CrazyFlyGUI/include/cornergrabber.h      |   0
 .../GUI_Qt/CrazyFlyGUI/include/crazyFly.h           |   0
 .../GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h       |   0
 .../GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h    |   0
 .../GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h  |   0
 .../GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h      |   0
 .../GUI_Qt/CrazyFlyGUI/include/marker.h             |   0
 .../GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h |   0
 .../GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h    |   0
 .../GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h     |   0
 .../include/rosNodeThread_for_managerGUI.h          |   0
 .../GUI_Qt/CrazyFlyGUI/include/tablePiece.h         |   0
 .../GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp             |   0
 .../GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp         |   0
 .../GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp           |   0
 .../GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp        |   0
 .../GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp             |   0
 .../GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp         |   0
 .../GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp      |   0
 .../GUI_Qt/CrazyFlyGUI/src/main.cpp                 |   0
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp        |   0
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui         |   0
 .../GUI_Qt/CrazyFlyGUI/src/marker.cpp               |   0
 .../GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp   |   0
 .../GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp      |   0
 .../GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp       |   0
 .../src/rosNodeThread_for_managerGUI.cpp            |   0
 .../GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp           |   0
 .../GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro        |   0
 .../GUI_Qt/flyingAgentGUI/flyingagentgui.qrc        |   0
 .../flyingAgentGUI/forms/connectstartstopbar.ui     |   0
 .../GUI_Qt/flyingAgentGUI/forms/controllertabs.ui   |   0
 .../GUI_Qt/flyingAgentGUI/forms/coordinator.ui      |   0
 .../GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui   |   0
 .../flyingAgentGUI/forms/defaultcontrollertab.ui    |   0
 .../forms/enablecontrollerloadyamlbar.ui            |   0
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui       |   0
 .../flyingAgentGUI/forms/pickercontrollertab.ui     |   0
 .../flyingAgentGUI/forms/safecontrollertab.ui       |   0
 .../flyingAgentGUI/forms/studentcontrollertab.ui    |   0
 .../GUI_Qt/flyingAgentGUI/forms/topbanner.ui        |   0
 .../flyingAgentGUI/forms/tuningcontrollertab.ui     |   0
 .../GUI_Qt/flyingAgentGUI/images/battery_20.png     | Bin
 .../GUI_Qt/flyingAgentGUI/images/battery_40.png     | Bin
 .../GUI_Qt/flyingAgentGUI/images/battery_60.png     | Bin
 .../GUI_Qt/flyingAgentGUI/images/battery_80.png     | Bin
 .../GUI_Qt/flyingAgentGUI/images/battery_empty.png  | Bin
 .../GUI_Qt/flyingAgentGUI/images/battery_full.png   | Bin
 .../flyingAgentGUI/images/battery_unavailable.png   | Bin
 .../flyingAgentGUI/images/battery_unknown.png       | Bin
 .../GUI_Qt/flyingAgentGUI/images/emergency_stop.png | Bin
 .../images/flying_state_disabling.png               | Bin
 .../flyingAgentGUI/images/flying_state_enabling.png | Bin
 .../flyingAgentGUI/images/flying_state_flying.png   | Bin
 .../flyingAgentGUI/images/flying_state_off.png      | Bin
 .../images/flying_state_unavailable.png             | Bin
 .../flyingAgentGUI/images/flying_state_unknown.png  | Bin
 .../GUI_Qt/flyingAgentGUI/images/rf_connected.png   | Bin
 .../GUI_Qt/flyingAgentGUI/images/rf_connecting.png  | Bin
 .../flyingAgentGUI/images/rf_disconnected.png       | Bin
 .../include/Constants_for_Qt_compile.h              |   0
 .../PickerControllerConstants_for_Qt_compile.h      |   0
 .../flyingAgentGUI/include/connectstartstopbar.h    |   0
 .../GUI_Qt/flyingAgentGUI/include/controllertabs.h  |   0
 .../GUI_Qt/flyingAgentGUI/include/coordinator.h     |   0
 .../GUI_Qt/flyingAgentGUI/include/coordinatorrow.h  |   0
 .../flyingAgentGUI/include/defaultcontrollertab.h   |   0
 .../include/enablecontrollerloadyamlbar.h           |   0
 .../GUI_Qt/flyingAgentGUI/include/mainwindow.h      |   0
 .../flyingAgentGUI/include/pickercontrollertab.h    |   0
 .../include/rosNodeThread_for_flyingAgentGUI.h      |   0
 .../flyingAgentGUI/include/safecontrollertab.h      |   0
 .../flyingAgentGUI/include/studentcontrollertab.h   |   0
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h       |   0
 .../flyingAgentGUI/include/tuningcontrollertab.h    |   0
 .../flyingAgentGUI/src/connectstartstopbar.cpp      |   0
 .../GUI_Qt/flyingAgentGUI/src/controllertabs.cpp    |   0
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp       |   0
 .../GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp    |   0
 .../flyingAgentGUI/src/defaultcontrollertab.cpp     |   0
 .../src/enablecontrollerloadyamlbar.cpp             |   0
 .../GUI_Qt/flyingAgentGUI/src/main.cpp              |   0
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp        |   0
 .../flyingAgentGUI/src/pickercontrollertab.cpp      |   0
 .../src/rosNodeThread_for_flyingAgentGUI.cpp        |   0
 .../GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp |   0
 .../flyingAgentGUI/src/studentcontrollertab.cpp     |   0
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp         |   0
 .../flyingAgentGUI/src/tuningcontrollertab.cpp      |   0
 .../GUI_Qt/studentGUI/images/battery_20.png         | Bin
 .../GUI_Qt/studentGUI/images/battery_40.png         | Bin
 .../GUI_Qt/studentGUI/images/battery_60.png         | Bin
 .../GUI_Qt/studentGUI/images/battery_80.png         | Bin
 .../GUI_Qt/studentGUI/images/battery_empty.png      | Bin
 .../GUI_Qt/studentGUI/images/battery_full.png       | Bin
 .../GUI_Qt/studentGUI/images/battery_unknown.png    | Bin
 .../studentGUI/images/flying_state_disabling.png    | Bin
 .../studentGUI/images/flying_state_enabling.png     | Bin
 .../studentGUI/images/flying_state_flying.png       | Bin
 .../GUI_Qt/studentGUI/images/flying_state_off.png   | Bin
 .../studentGUI/images/flying_state_unknown.png      | Bin
 .../GUI_Qt/studentGUI/images/rf_connected.png       | Bin
 .../GUI_Qt/studentGUI/images/rf_connecting.png      | Bin
 .../GUI_Qt/studentGUI/images/rf_disconnected.png    | Bin
 .../GUI_Qt/studentGUI/include/MainWindow.h          |   0
 .../include/rosNodeThread_for_studentGUI.h          |   0
 .../GUI_Qt/studentGUI/src/MainWindow.cpp            |   0
 .../GUI_Qt/studentGUI/src/MainWindow.ui             |   0
 .../GUI_Qt/studentGUI/src/main.cpp                  |   0
 .../studentGUI/src/rosNodeThread_for_studentGUI.cpp |   0
 .../GUI_Qt/studentGUI/studentGUI.pro                |   0
 .../GUI_Qt/studentGUI/studentgui.qrc                |   0
 .../src/{d_fall_pps => dfall_pkg}/PPS.perspective   |   0
 .../crazyradio/CrazyRadio.py                        |   0
 .../crazyradio/LICENSE.txt                          |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/Makefile   |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/README.md  |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/TestCF.py  |   0
 .../crazyradio/build/lib/cflib/__init__.py          |   0
 .../build/lib/cflib/bootloader/__init__.py          |   0
 .../build/lib/cflib/bootloader/boottypes.py         |   0
 .../build/lib/cflib/bootloader/cloader.py           |   0
 .../build/lib/cflib/crazyflie/__init__.py           |   0
 .../build/lib/cflib/crazyflie/commander.py          |   0
 .../crazyradio/build/lib/cflib/crazyflie/console.py |   0
 .../crazyradio/build/lib/cflib/crazyflie/extpos.py  |   0
 .../build/lib/cflib/crazyflie/localization.py       |   0
 .../crazyradio/build/lib/cflib/crazyflie/log.py     |   0
 .../crazyradio/build/lib/cflib/crazyflie/mem.py     |   0
 .../crazyradio/build/lib/cflib/crazyflie/param.py   |   0
 .../build/lib/cflib/crazyflie/platformservice.py    |   0
 .../crazyradio/build/lib/cflib/crazyflie/swarm.py   |   0
 .../build/lib/cflib/crazyflie/syncCrazyflie.py      |   0
 .../build/lib/cflib/crazyflie/syncLogger.py         |   0
 .../crazyradio/build/lib/cflib/crazyflie/toc.py     |   0
 .../build/lib/cflib/crazyflie/toccache.py           |   0
 .../crazyradio/build/lib/cflib/crtp/__init__.py     |   0
 .../crazyradio/build/lib/cflib/crtp/crtpdriver.py   |   0
 .../crazyradio/build/lib/cflib/crtp/crtpstack.py    |   0
 .../crazyradio/build/lib/cflib/crtp/debugdriver.py  |   0
 .../crazyradio/build/lib/cflib/crtp/exceptions.py   |   0
 .../crazyradio/build/lib/cflib/crtp/radiodriver.py  |   0
 .../crazyradio/build/lib/cflib/crtp/serialdriver.py |   0
 .../crazyradio/build/lib/cflib/crtp/udpdriver.py    |   0
 .../crazyradio/build/lib/cflib/crtp/usbdriver.py    |   0
 .../crazyradio/build/lib/cflib/drivers/__init__.py  |   0
 .../crazyradio/build/lib/cflib/drivers/cfusb.py     |   0
 .../build/lib/cflib/drivers/crazyradio.py           |   0
 .../crazyradio/build/lib/cflib/utils/__init__.py    |   0
 .../crazyradio/build/lib/cflib/utils/callbacks.py   |   0
 .../crazyradio/build/lib/lpslib/__init__.py         |   0
 .../crazyradio/build/lib/lpslib/lopoanchor.py       |   0
 .../crazyradio/build/lib/test/__init__.py           |   0
 .../crazyradio/build/lib/test/crazyflie/__init__.py |   0
 .../build/lib/test/crazyflie/test_swarm.py          |   0
 .../build/lib/test/crazyflie/test_syncCrazyflie.py  |   0
 .../build/lib/test/crazyflie/test_syncLogger.py     |   0
 .../crazyradio/build/lib/test/crtp/__init__.py      |   0
 .../build/lib/test/crtp/test_crtpstack.py           |   0
 .../crazyradio/build/lib/test/support/__init__.py   |   0
 .../build/lib/test/support/asyncCallbackCaller.py   |   0
 .../crazyradio/build/lib/test/utils/__init__.py     |   0
 .../build/lib/test/utils/test_callbacks.py          |   0
 .../crazyradio/cflib.egg-info/PKG-INFO              |   0
 .../crazyradio/cflib.egg-info/SOURCES.txt           |   0
 .../crazyradio/cflib.egg-info/dependency_links.txt  |   0
 .../crazyradio/cflib.egg-info/requires.txt          |   0
 .../crazyradio/cflib.egg-info/top_level.txt         |   0
 .../crazyradio/cflib/__init__.py                    |   0
 .../crazyradio/cflib/bootloader/__init__.py         |   0
 .../crazyradio/cflib/bootloader/boottypes.py        |   0
 .../crazyradio/cflib/bootloader/cloader.py          |   0
 .../crazyradio/cflib/crazyflie/__init__.py          |   0
 .../crazyradio/cflib/crazyflie/commander.py         |   0
 .../crazyradio/cflib/crazyflie/console.py           |   0
 .../crazyradio/cflib/crazyflie/extpos.py            |   0
 .../crazyradio/cflib/crazyflie/localization.py      |   0
 .../crazyradio/cflib/crazyflie/log.py               |   0
 .../crazyradio/cflib/crazyflie/mem.py               |   0
 .../crazyradio/cflib/crazyflie/param.py             |   0
 .../crazyradio/cflib/crazyflie/platformservice.py   |   0
 .../crazyradio/cflib/crazyflie/swarm.py             |   0
 .../crazyradio/cflib/crazyflie/syncCrazyflie.py     |   0
 .../crazyradio/cflib/crazyflie/syncLogger.py        |   0
 .../crazyradio/cflib/crazyflie/toc.py               |   0
 .../crazyradio/cflib/crazyflie/toccache.py          |   0
 .../crazyradio/cflib/crtp/__init__.py               |   0
 .../crazyradio/cflib/crtp/crtpdriver.py             |   0
 .../crazyradio/cflib/crtp/crtpstack.py              |   0
 .../crazyradio/cflib/crtp/debugdriver.py            |   0
 .../crazyradio/cflib/crtp/exceptions.py             |   0
 .../crazyradio/cflib/crtp/radiodriver.py            |   0
 .../crazyradio/cflib/crtp/serialdriver.py           |   0
 .../crazyradio/cflib/crtp/udpdriver.py              |   0
 .../crazyradio/cflib/crtp/usbdriver.py              |   0
 .../crazyradio/cflib/drivers/__init__.py            |   0
 .../crazyradio/cflib/drivers/cfusb.py               |   0
 .../crazyradio/cflib/drivers/crazyradio.py          |   0
 .../crazyradio/cflib/utils/__init__.py              |   0
 .../crazyradio/cflib/utils/callbacks.py             |   0
 .../crazyradio/dist/cflib-0.1.3-py3.5.egg           | Bin
 .../crazyradio/examples/autonomousSequence.py       |   0
 .../crazyradio/examples/basiclog.py                 |   0
 .../crazyradio/examples/basiclogSync.py             |   0
 .../crazyradio/examples/basicparam.py               |   0
 .../crazyradio/examples/erase-ow.py                 |   0
 .../crazyradio/examples/flash-memory.py             |   0
 .../crazyradio/examples/flowsequenceSync.py         |   0
 .../crazyradio/examples/lps_reboot_to_bootloader.py |   0
 .../crazyradio/examples/multiramp.py                |   0
 .../crazyradio/examples/radio-test.py               |   0
 .../crazyradio/examples/ramp.py                     |   0
 .../crazyradio/examples/read-eeprom.py              |   0
 .../crazyradio/examples/read-ow.py                  |   0
 .../crazyradio/examples/scan.py                     |   0
 .../crazyradio/examples/swarmSequence.py            |   0
 .../crazyradio/examples/swarmSequenceCircle.py      |   0
 .../crazyradio/examples/write-eeprom.py             |   0
 .../crazyradio/examples/write-ow.py                 |   0
 .../crazyradio/lpslib/__init__.py                   |   0
 .../crazyradio/lpslib/lopoanchor.py                 |   0
 .../crazyradio/module.json                          |   0
 .../crazyradio/requirements-dev.txt                 |   0
 .../crazyradio/requirements.txt                     |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/setup.cfg  |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/setup.py   |   0
 .../crazyradio/setup_linux.sh                       |   0
 .../crazyradio/test/__init__.py                     |   0
 .../crazyradio/test/crazyflie/__init__.py           |   0
 .../crazyradio/test/crazyflie/test_swarm.py         |   0
 .../crazyradio/test/crazyflie/test_syncCrazyflie.py |   0
 .../crazyradio/test/crazyflie/test_syncLogger.py    |   0
 .../crazyradio/test/crtp/__init__.py                |   0
 .../crazyradio/test/crtp/test_crtpstack.py          |   0
 .../crazyradio/test/support/__init__.py             |   0
 .../crazyradio/test/support/asyncCallbackCaller.py  |   0
 .../crazyradio/test/utils/__init__.py               |   0
 .../crazyradio/test/utils/test_callbacks.py         |   0
 .../crazyradio/tools/build/bdist                    |   0
 .../crazyradio/tools/build/build                    |   0
 .../crazyradio/tools/build/test                     |   0
 .../crazyradio/tools/build/verify                   |   0
 .../{d_fall_pps => dfall_pkg}/crazyradio/tox.ini    |   0
 .../include/classes/GetParamtersAndNamespaces.h     |   0
 .../include/nodes/BatteryMonitor.h                  |   0
 .../include/nodes/CentralManagerService.h           |   0
 .../include/nodes/Constants.h                       |   0
 .../include/nodes/CrazyflieIO.h                     |   0
 .../include/nodes/DefaultControllerService.h        |   0
 .../include/nodes/DemoControllerService.h           |   0
 .../include/nodes/PPSClient.h                       |   0
 .../include/nodes/ParameterService.h                |   0
 .../include/nodes/PickerControllerConstants.h       |   0
 .../include/nodes/PickerControllerService.h         |   0
 .../include/nodes/RemoteControllerService.h         |   0
 .../include/nodes/SafeControllerService.h           |   0
 .../include/nodes/StudentControllerService.h        |   0
 .../include/nodes/TuningControllerService.h         |   0
 .../{d_fall_pps => dfall_pkg}/launch/Agent.launch   |   0
 .../src/{d_fall_pps => dfall_pkg}/launch/Config.sh  |   0
 .../launch/Coordinator.launch                       |   0
 .../{d_fall_pps => dfall_pkg}/launch/Teacher.launch |   0
 .../{d_fall_pps => dfall_pkg}/msg/AreaBounds.msg    |   0
 .../msg/ControlCommand.msg                          |   0
 .../msg/CrazyflieContext.msg                        |   0
 .../{d_fall_pps => dfall_pkg}/msg/CrazyflieDB.msg   |   0
 .../{d_fall_pps => dfall_pkg}/msg/CrazyflieData.msg |   0
 .../msg/CrazyflieEntry.msg                          |   0
 .../{d_fall_pps => dfall_pkg}/msg/CustomButton.msg  |   0
 .../msg/CustomButtonWithHeader.msg                  |   0
 .../src/{d_fall_pps => dfall_pkg}/msg/DebugMsg.msg  |   0
 .../msg/FloatWithHeader.msg                         |   0
 .../{d_fall_pps => dfall_pkg}/msg/IntWithHeader.msg |   0
 .../src/{d_fall_pps => dfall_pkg}/msg/Setpoint.msg  |   0
 .../{d_fall_pps => dfall_pkg}/msg/SetpointV2.msg    |   0
 .../msg/SetpointWithHeader.msg                      |   0
 .../msg/StringWithHeader.msg                        |   0
 .../msg/UnlabeledMarker.msg                         |   0
 .../src/{d_fall_pps => dfall_pkg}/msg/ViconData.msg |   0
 .../msg/ViconSubscribeObjectName.msg                |   0
 dfall_ws/src/{d_fall_pps => dfall_pkg}/package.xml  |   0
 .../param/BatteryMonitor.yaml                       |   0
 .../param/ClientConfig.yaml                         |   0
 .../param/DefaultController.yaml                    |   0
 .../param/DemoController.yaml                       |   0
 .../param/MpcController.yaml                        |   0
 .../param/PickerController.yaml                     |   0
 .../param/RemoteController.yaml                     |   0
 .../param/SafeController.yaml                       |   0
 .../param/StudentController.yaml                    |   0
 .../param/TuningController.yaml                     |   0
 .../param/ViconConfig.yaml                          |   0
 .../param/YamlFileNames.yaml                        |   0
 .../scripts/land_crazyflie                          |   0
 .../scripts/load_custom_controller                  |   0
 .../scripts/load_safe_controller                    |   0
 .../scripts/motors_off_crazyflie                    |   0
 .../scripts/safe_controller_setpoint                |   0
 .../scripts/take_off_crazyflie                      |   0
 .../{d_fall_pps => dfall_pkg}/src/CrazyflieIO.cpp   |   0
 .../src/classes/GetParamtersAndNamespaces.cpp       |   0
 .../src/nodes/BatteryMonitor.cpp                    |   0
 .../src/nodes/CentralManagerService.cpp             |   0
 .../src/nodes/DefaultControllerService.cpp          |   0
 .../src/nodes/DemoControllerService.cpp             |   0
 .../src/nodes/MpcControllerService.cpp              |   0
 .../src/nodes/PPSClient.cpp                         |   0
 .../src/nodes/ParameterService.cpp                  |   0
 .../src/nodes/PickerControllerService.cpp           |   0
 .../src/nodes/RemoteControllerService.cpp           |   0
 .../src/nodes/SafeControllerService.cpp             |   0
 .../src/nodes/StudentControllerService.cpp          |   0
 .../src/nodes/TuningControllerService.cpp           |   0
 .../src/nodes/ViconDataPublisher.cpp                |   0
 .../src/{d_fall_pps => dfall_pkg}/srv/CMCommand.srv |   0
 .../src/{d_fall_pps => dfall_pkg}/srv/CMQuery.srv   |   0
 .../src/{d_fall_pps => dfall_pkg}/srv/CMRead.srv    |   0
 .../src/{d_fall_pps => dfall_pkg}/srv/CMUpdate.srv  |   0
 .../{d_fall_pps => dfall_pkg}/srv/Controller.srv    |   0
 .../srv/GetSetpointService.srv                      |   0
 .../{d_fall_pps => dfall_pkg}/srv/IntIntService.srv |   0
 .../srv/LoadYamlFromFilename.srv                    |   0
 342 files changed, 2 insertions(+), 2 deletions(-)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/CMakeLists.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/center_rect.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/CFLinker.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/centerMarker.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/channelLUT.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/crazyFly.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/marker.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/include/tablePiece.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/main.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/marker.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/coordinator.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/topbanner.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_20.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_40.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_60.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_80.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_empty.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_full.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/battery_unknown.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/emergency_stop.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_off.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/rf_connected.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/rf_connecting.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/controllertabs.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/coordinator.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/mainwindow.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/topbanner.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/coordinator.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/main.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/topbanner.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_20.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_40.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_60.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_80.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_empty.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_full.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/battery_unknown.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/flying_state_disabling.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/flying_state_enabling.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/flying_state_flying.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/flying_state_off.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/flying_state_unknown.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/rf_connected.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/rf_connecting.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/images/rf_disconnected.png (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/include/MainWindow.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/src/MainWindow.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/src/MainWindow.ui (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/src/main.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/studentGUI.pro (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/GUI_Qt/studentGUI/studentgui.qrc (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/PPS.perspective (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/CrazyRadio.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/LICENSE.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/Makefile (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/README.md (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/TestCF.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/bootloader/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/bootloader/boottypes.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/bootloader/cloader.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/commander.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/console.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/extpos.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/localization.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/log.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/mem.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/param.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/platformservice.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/swarm.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/syncLogger.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/toc.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crazyflie/toccache.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/crtpdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/crtpstack.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/debugdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/exceptions.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/radiodriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/serialdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/udpdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/crtp/usbdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/drivers/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/drivers/cfusb.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/drivers/crazyradio.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/utils/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/cflib/utils/callbacks.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/lpslib/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/lpslib/lopoanchor.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crazyflie/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crazyflie/test_swarm.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crazyflie/test_syncLogger.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crtp/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/crtp/test_crtpstack.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/support/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/support/asyncCallbackCaller.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/utils/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/build/lib/test/utils/test_callbacks.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib.egg-info/PKG-INFO (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib.egg-info/SOURCES.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib.egg-info/dependency_links.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib.egg-info/requires.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib.egg-info/top_level.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/bootloader/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/bootloader/boottypes.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/bootloader/cloader.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/commander.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/console.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/extpos.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/localization.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/log.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/mem.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/param.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/platformservice.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/swarm.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/syncCrazyflie.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/syncLogger.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/toc.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crazyflie/toccache.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/crtpdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/crtpstack.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/debugdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/exceptions.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/radiodriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/serialdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/udpdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/crtp/usbdriver.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/drivers/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/drivers/cfusb.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/drivers/crazyradio.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/utils/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/cflib/utils/callbacks.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/dist/cflib-0.1.3-py3.5.egg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/autonomousSequence.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/basiclog.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/basiclogSync.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/basicparam.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/erase-ow.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/flash-memory.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/flowsequenceSync.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/lps_reboot_to_bootloader.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/multiramp.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/radio-test.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/ramp.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/read-eeprom.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/read-ow.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/scan.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/swarmSequence.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/swarmSequenceCircle.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/write-eeprom.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/examples/write-ow.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/lpslib/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/lpslib/lopoanchor.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/module.json (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/requirements-dev.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/requirements.txt (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/setup.cfg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/setup.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/setup_linux.sh (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crazyflie/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crazyflie/test_swarm.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crazyflie/test_syncCrazyflie.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crazyflie/test_syncLogger.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crtp/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/crtp/test_crtpstack.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/support/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/support/asyncCallbackCaller.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/utils/__init__.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/test/utils/test_callbacks.py (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/tools/build/bdist (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/tools/build/build (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/tools/build/test (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/tools/build/verify (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/crazyradio/tox.ini (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/classes/GetParamtersAndNamespaces.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/BatteryMonitor.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/CentralManagerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/Constants.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/CrazyflieIO.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/DefaultControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/DemoControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/PPSClient.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/ParameterService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/PickerControllerConstants.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/PickerControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/RemoteControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/SafeControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/StudentControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/include/nodes/TuningControllerService.h (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/launch/Agent.launch (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/launch/Config.sh (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/launch/Coordinator.launch (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/launch/Teacher.launch (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/AreaBounds.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/ControlCommand.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CrazyflieContext.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CrazyflieDB.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CrazyflieData.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CrazyflieEntry.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CustomButton.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/CustomButtonWithHeader.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/DebugMsg.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/FloatWithHeader.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/IntWithHeader.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/Setpoint.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/SetpointV2.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/SetpointWithHeader.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/StringWithHeader.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/UnlabeledMarker.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/ViconData.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/msg/ViconSubscribeObjectName.msg (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/package.xml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/BatteryMonitor.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/ClientConfig.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/DefaultController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/DemoController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/MpcController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/PickerController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/RemoteController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/SafeController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/StudentController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/TuningController.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/ViconConfig.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/param/YamlFileNames.yaml (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/land_crazyflie (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/load_custom_controller (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/load_safe_controller (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/motors_off_crazyflie (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/safe_controller_setpoint (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/scripts/take_off_crazyflie (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/CrazyflieIO.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/classes/GetParamtersAndNamespaces.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/BatteryMonitor.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/CentralManagerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/DefaultControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/DemoControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/MpcControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/PPSClient.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/ParameterService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/PickerControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/RemoteControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/SafeControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/StudentControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/TuningControllerService.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/src/nodes/ViconDataPublisher.cpp (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/CMCommand.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/CMQuery.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/CMRead.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/CMUpdate.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/Controller.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/GetSetpointService.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/IntIntService.srv (100%)
 rename dfall_ws/src/{d_fall_pps => dfall_pkg}/srv/LoadYamlFromFilename.srv (100%)

diff --git a/.gitignore b/.gitignore
index 26806938..54bbb139 100755
--- a/.gitignore
+++ b/.gitignore
@@ -1,8 +1,8 @@
 dfall_ws/build/
 dfall_ws/devel/
 
-dfall_ws/src/d_fall_pps/lib/vicon/
-dfall_ws/src/d_fall_pps/include/DataStreamClient.h
+dfall_ws/src/dfall_pkg/lib/vicon/
+dfall_ws/src/dfall_pkg/include/DataStreamClient.h
 
 # Qt Project files with user preferences
 *.pro.user
diff --git a/dfall_ws/src/d_fall_pps/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/CMakeLists.txt
rename to dfall_ws/src/dfall_pkg/CMakeLists.txt
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/marker.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/marker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/marker.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/main.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/main.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/main.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/marker.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/marker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/marker.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingagentgui.qrc
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/connectstartstopbar.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinator.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/coordinatorrow.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/pickercontrollertab.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/safecontrollertab.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/topbanner.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/tuningcontrollertab.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_20.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_20.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_20.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_40.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_40.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_40.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_60.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_60.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_60.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_80.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_80.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_80.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_empty.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_empty.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_empty.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_full.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_full.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_full.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_unavailable.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/battery_unknown.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/emergency_stop.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_disabling.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_enabling.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_flying.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_off.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_unavailable.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/flying_state_unknown.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_connected.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connected.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_connected.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_connecting.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/images/rf_disconnected.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/Constants_for_Qt_compile.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/controllertabs.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinator.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinatorrow.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/mainwindow.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/safecontrollertab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/topbanner.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/controllertabs.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinator.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/main.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/safecontrollertab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_20.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_20.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_20.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_40.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_40.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_40.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_60.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_60.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_60.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_80.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_80.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_80.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_empty.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_empty.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_empty.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_full.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_full.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_full.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_unknown.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/battery_unknown.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_unknown.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_disabling.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_disabling.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_disabling.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_enabling.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_enabling.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_enabling.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_flying.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_flying.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_flying.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_off.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_off.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_off.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_unknown.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/flying_state_unknown.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_unknown.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connected.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connected.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connected.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connecting.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_connecting.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connecting.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_disconnected.png
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/images/rf_disconnected.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_disconnected.png
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/main.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro
diff --git a/dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc
similarity index 100%
rename from dfall_ws/src/d_fall_pps/GUI_Qt/studentGUI/studentgui.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc
diff --git a/dfall_ws/src/d_fall_pps/PPS.perspective b/dfall_ws/src/dfall_pkg/PPS.perspective
similarity index 100%
rename from dfall_ws/src/d_fall_pps/PPS.perspective
rename to dfall_ws/src/dfall_pkg/PPS.perspective
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/CrazyRadio.py
rename to dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/LICENSE.txt b/dfall_ws/src/dfall_pkg/crazyradio/LICENSE.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/LICENSE.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/LICENSE.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/Makefile b/dfall_ws/src/dfall_pkg/crazyradio/Makefile
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/Makefile
rename to dfall_ws/src/dfall_pkg/crazyradio/Makefile
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/README.md b/dfall_ws/src/dfall_pkg/crazyradio/README.md
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/README.md
rename to dfall_ws/src/dfall_pkg/crazyradio/README.md
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/TestCF.py b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/TestCF.py
rename to dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/boottypes.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/boottypes.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/bootloader/cloader.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/bootloader/cloader.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/commander.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/commander.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/console.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/console.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/extpos.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/extpos.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/localization.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/localization.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/log.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/log.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/mem.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/mem.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/param.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/param.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/platformservice.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/platformservice.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/swarm.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/swarm.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncCrazyflie.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/syncLogger.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toc.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toc.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crazyflie/toccache.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crazyflie/toccache.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/crtpstack.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/crtpstack.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/debugdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/debugdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/exceptions.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/exceptions.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/radiodriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/radiodriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/serialdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/serialdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/udpdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/udpdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/crtp/usbdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/crtp/usbdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/cfusb.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/cfusb.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/drivers/crazyradio.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/drivers/crazyradio.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/cflib/utils/callbacks.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/cflib/utils/callbacks.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/lpslib/lopoanchor.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/lpslib/lopoanchor.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_swarm.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_swarm.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncCrazyflie.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crazyflie/test_syncLogger.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/crtp/test_crtpstack.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/crtp/test_crtpstack.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/support/asyncCallbackCaller.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/support/asyncCallbackCaller.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/build/lib/test/utils/test_callbacks.py
rename to dfall_ws/src/dfall_pkg/crazyradio/build/lib/test/utils/test_callbacks.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/PKG-INFO
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/PKG-INFO
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/SOURCES.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/SOURCES.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/dependency_links.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/dependency_links.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/requires.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/requires.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt b/dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib.egg-info/top_level.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib.egg-info/top_level.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/boottypes.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/boottypes.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/boottypes.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/bootloader/cloader.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/bootloader/cloader.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/commander.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/commander.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/console.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/console.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/console.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/extpos.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/extpos.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/localization.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/localization.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/log.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/log.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/mem.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/mem.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/param.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/param.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/platformservice.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/platformservice.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/swarm.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/swarm.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncCrazyflie.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncCrazyflie.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/syncLogger.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/syncLogger.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toc.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toc.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toccache.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crazyflie/toccache.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crazyflie/toccache.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/crtpstack.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/crtpstack.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/debugdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/debugdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/exceptions.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/exceptions.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/exceptions.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/radiodriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/radiodriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/serialdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/serialdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/udpdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/udpdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/udpdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/usbdriver.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/crtp/usbdriver.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/crtp/usbdriver.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/cfusb.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/cfusb.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/drivers/crazyradio.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/drivers/crazyradio.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/cflib/utils/callbacks.py
rename to dfall_ws/src/dfall_pkg/crazyradio/cflib/utils/callbacks.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg b/dfall_ws/src/dfall_pkg/crazyradio/dist/cflib-0.1.3-py3.5.egg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/dist/cflib-0.1.3-py3.5.egg
rename to dfall_ws/src/dfall_pkg/crazyradio/dist/cflib-0.1.3-py3.5.egg
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/autonomousSequence.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/autonomousSequence.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/basiclog.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/basiclog.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/basiclog.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/basiclogSync.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/basiclogSync.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/basicparam.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/basicparam.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/basicparam.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/erase-ow.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/erase-ow.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/erase-ow.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/flash-memory.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/flash-memory.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/flash-memory.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/flowsequenceSync.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/flowsequenceSync.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/lps_reboot_to_bootloader.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/lps_reboot_to_bootloader.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/lps_reboot_to_bootloader.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/multiramp.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/multiramp.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/multiramp.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/radio-test.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/radio-test.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/radio-test.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/ramp.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/ramp.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/ramp.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/read-eeprom.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/read-eeprom.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/read-eeprom.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/read-ow.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/read-ow.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/read-ow.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/scan.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/scan.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/scan.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/scan.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequence.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequence.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequence.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequenceCircle.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/swarmSequenceCircle.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/swarmSequenceCircle.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/write-eeprom.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/write-eeprom.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/write-eeprom.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/examples/write-ow.py b/dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/examples/write-ow.py
rename to dfall_ws/src/dfall_pkg/crazyradio/examples/write-ow.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/lpslib/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/lpslib/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/lpslib/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py b/dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/lpslib/lopoanchor.py
rename to dfall_ws/src/dfall_pkg/crazyradio/lpslib/lopoanchor.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/module.json b/dfall_ws/src/dfall_pkg/crazyradio/module.json
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/module.json
rename to dfall_ws/src/dfall_pkg/crazyradio/module.json
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/requirements-dev.txt b/dfall_ws/src/dfall_pkg/crazyradio/requirements-dev.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/requirements-dev.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/requirements-dev.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/requirements.txt b/dfall_ws/src/dfall_pkg/crazyradio/requirements.txt
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/requirements.txt
rename to dfall_ws/src/dfall_pkg/crazyradio/requirements.txt
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/setup.cfg b/dfall_ws/src/dfall_pkg/crazyradio/setup.cfg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/setup.cfg
rename to dfall_ws/src/dfall_pkg/crazyradio/setup.cfg
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/setup.py b/dfall_ws/src/dfall_pkg/crazyradio/setup.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/setup.py
rename to dfall_ws/src/dfall_pkg/crazyradio/setup.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/setup_linux.sh b/dfall_ws/src/dfall_pkg/crazyradio/setup_linux.sh
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/setup_linux.sh
rename to dfall_ws/src/dfall_pkg/crazyradio/setup_linux.sh
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_swarm.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_swarm.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_swarm.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncCrazyflie.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncCrazyflie.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crazyflie/test_syncLogger.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crazyflie/test_syncLogger.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crtp/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crtp/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crtp/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py b/dfall_ws/src/dfall_pkg/crazyradio/test/crtp/test_crtpstack.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/crtp/test_crtpstack.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/crtp/test_crtpstack.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/support/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/support/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/support/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/support/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py b/dfall_ws/src/dfall_pkg/crazyradio/test/support/asyncCallbackCaller.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/support/asyncCallbackCaller.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/support/asyncCallbackCaller.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py b/dfall_ws/src/dfall_pkg/crazyradio/test/utils/__init__.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/utils/__init__.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/utils/__init__.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py b/dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_callbacks.py
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/test/utils/test_callbacks.py
rename to dfall_ws/src/dfall_pkg/crazyradio/test/utils/test_callbacks.py
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/tools/build/bdist b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/bdist
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/tools/build/bdist
rename to dfall_ws/src/dfall_pkg/crazyradio/tools/build/bdist
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/tools/build/build b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/build
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/tools/build/build
rename to dfall_ws/src/dfall_pkg/crazyradio/tools/build/build
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/tools/build/test b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/test
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/tools/build/test
rename to dfall_ws/src/dfall_pkg/crazyradio/tools/build/test
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/tools/build/verify b/dfall_ws/src/dfall_pkg/crazyradio/tools/build/verify
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/tools/build/verify
rename to dfall_ws/src/dfall_pkg/crazyradio/tools/build/verify
diff --git a/dfall_ws/src/d_fall_pps/crazyradio/tox.ini b/dfall_ws/src/dfall_pkg/crazyradio/tox.ini
similarity index 100%
rename from dfall_ws/src/d_fall_pps/crazyradio/tox.ini
rename to dfall_ws/src/dfall_pkg/crazyradio/tox.ini
diff --git a/dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/classes/GetParamtersAndNamespaces.h
rename to dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h b/dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/BatteryMonitor.h
rename to dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h b/dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/CentralManagerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/Constants.h b/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/Constants.h
rename to dfall_ws/src/dfall_pkg/include/nodes/Constants.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h b/dfall_ws/src/dfall_pkg/include/nodes/CrazyflieIO.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/CrazyflieIO.h
rename to dfall_ws/src/dfall_pkg/include/nodes/CrazyflieIO.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/DefaultControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/DemoControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/DemoControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h b/dfall_ws/src/dfall_pkg/include/nodes/PPSClient.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/PPSClient.h
rename to dfall_ws/src/dfall_pkg/include/nodes/PPSClient.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h b/dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/ParameterService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/PickerControllerConstants.h
rename to dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/PickerControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/RemoteControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/RemoteControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/SafeControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/SafeControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/StudentControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
similarity index 100%
rename from dfall_ws/src/d_fall_pps/include/nodes/TuningControllerService.h
rename to dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
diff --git a/dfall_ws/src/d_fall_pps/launch/Agent.launch b/dfall_ws/src/dfall_pkg/launch/Agent.launch
similarity index 100%
rename from dfall_ws/src/d_fall_pps/launch/Agent.launch
rename to dfall_ws/src/dfall_pkg/launch/Agent.launch
diff --git a/dfall_ws/src/d_fall_pps/launch/Config.sh b/dfall_ws/src/dfall_pkg/launch/Config.sh
similarity index 100%
rename from dfall_ws/src/d_fall_pps/launch/Config.sh
rename to dfall_ws/src/dfall_pkg/launch/Config.sh
diff --git a/dfall_ws/src/d_fall_pps/launch/Coordinator.launch b/dfall_ws/src/dfall_pkg/launch/Coordinator.launch
similarity index 100%
rename from dfall_ws/src/d_fall_pps/launch/Coordinator.launch
rename to dfall_ws/src/dfall_pkg/launch/Coordinator.launch
diff --git a/dfall_ws/src/d_fall_pps/launch/Teacher.launch b/dfall_ws/src/dfall_pkg/launch/Teacher.launch
similarity index 100%
rename from dfall_ws/src/d_fall_pps/launch/Teacher.launch
rename to dfall_ws/src/dfall_pkg/launch/Teacher.launch
diff --git a/dfall_ws/src/d_fall_pps/msg/AreaBounds.msg b/dfall_ws/src/dfall_pkg/msg/AreaBounds.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/AreaBounds.msg
rename to dfall_ws/src/dfall_pkg/msg/AreaBounds.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/ControlCommand.msg b/dfall_ws/src/dfall_pkg/msg/ControlCommand.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/ControlCommand.msg
rename to dfall_ws/src/dfall_pkg/msg/ControlCommand.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CrazyflieContext.msg b/dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CrazyflieContext.msg
rename to dfall_ws/src/dfall_pkg/msg/CrazyflieContext.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CrazyflieDB.msg b/dfall_ws/src/dfall_pkg/msg/CrazyflieDB.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CrazyflieDB.msg
rename to dfall_ws/src/dfall_pkg/msg/CrazyflieDB.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CrazyflieData.msg b/dfall_ws/src/dfall_pkg/msg/CrazyflieData.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CrazyflieData.msg
rename to dfall_ws/src/dfall_pkg/msg/CrazyflieData.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CrazyflieEntry.msg b/dfall_ws/src/dfall_pkg/msg/CrazyflieEntry.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CrazyflieEntry.msg
rename to dfall_ws/src/dfall_pkg/msg/CrazyflieEntry.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CustomButton.msg b/dfall_ws/src/dfall_pkg/msg/CustomButton.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CustomButton.msg
rename to dfall_ws/src/dfall_pkg/msg/CustomButton.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/CustomButtonWithHeader.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/CustomButtonWithHeader.msg
rename to dfall_ws/src/dfall_pkg/msg/CustomButtonWithHeader.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/DebugMsg.msg b/dfall_ws/src/dfall_pkg/msg/DebugMsg.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/DebugMsg.msg
rename to dfall_ws/src/dfall_pkg/msg/DebugMsg.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/FloatWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/FloatWithHeader.msg
rename to dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/IntWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/IntWithHeader.msg
rename to dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/Setpoint.msg b/dfall_ws/src/dfall_pkg/msg/Setpoint.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/Setpoint.msg
rename to dfall_ws/src/dfall_pkg/msg/Setpoint.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/SetpointV2.msg b/dfall_ws/src/dfall_pkg/msg/SetpointV2.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/SetpointV2.msg
rename to dfall_ws/src/dfall_pkg/msg/SetpointV2.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/SetpointWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/SetpointWithHeader.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/SetpointWithHeader.msg
rename to dfall_ws/src/dfall_pkg/msg/SetpointWithHeader.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/StringWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/StringWithHeader.msg
rename to dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/UnlabeledMarker.msg b/dfall_ws/src/dfall_pkg/msg/UnlabeledMarker.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/UnlabeledMarker.msg
rename to dfall_ws/src/dfall_pkg/msg/UnlabeledMarker.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/ViconData.msg b/dfall_ws/src/dfall_pkg/msg/ViconData.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/ViconData.msg
rename to dfall_ws/src/dfall_pkg/msg/ViconData.msg
diff --git a/dfall_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg b/dfall_ws/src/dfall_pkg/msg/ViconSubscribeObjectName.msg
similarity index 100%
rename from dfall_ws/src/d_fall_pps/msg/ViconSubscribeObjectName.msg
rename to dfall_ws/src/dfall_pkg/msg/ViconSubscribeObjectName.msg
diff --git a/dfall_ws/src/d_fall_pps/package.xml b/dfall_ws/src/dfall_pkg/package.xml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/package.xml
rename to dfall_ws/src/dfall_pkg/package.xml
diff --git a/dfall_ws/src/d_fall_pps/param/BatteryMonitor.yaml b/dfall_ws/src/dfall_pkg/param/BatteryMonitor.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/BatteryMonitor.yaml
rename to dfall_ws/src/dfall_pkg/param/BatteryMonitor.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/ClientConfig.yaml
rename to dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/DefaultController.yaml
rename to dfall_ws/src/dfall_pkg/param/DefaultController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/DemoController.yaml b/dfall_ws/src/dfall_pkg/param/DemoController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/DemoController.yaml
rename to dfall_ws/src/dfall_pkg/param/DemoController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/MpcController.yaml b/dfall_ws/src/dfall_pkg/param/MpcController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/MpcController.yaml
rename to dfall_ws/src/dfall_pkg/param/MpcController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/PickerController.yaml b/dfall_ws/src/dfall_pkg/param/PickerController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/PickerController.yaml
rename to dfall_ws/src/dfall_pkg/param/PickerController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/RemoteController.yaml b/dfall_ws/src/dfall_pkg/param/RemoteController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/RemoteController.yaml
rename to dfall_ws/src/dfall_pkg/param/RemoteController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/SafeController.yaml b/dfall_ws/src/dfall_pkg/param/SafeController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/SafeController.yaml
rename to dfall_ws/src/dfall_pkg/param/SafeController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/StudentController.yaml b/dfall_ws/src/dfall_pkg/param/StudentController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/StudentController.yaml
rename to dfall_ws/src/dfall_pkg/param/StudentController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/TuningController.yaml b/dfall_ws/src/dfall_pkg/param/TuningController.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/TuningController.yaml
rename to dfall_ws/src/dfall_pkg/param/TuningController.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/ViconConfig.yaml b/dfall_ws/src/dfall_pkg/param/ViconConfig.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/ViconConfig.yaml
rename to dfall_ws/src/dfall_pkg/param/ViconConfig.yaml
diff --git a/dfall_ws/src/d_fall_pps/param/YamlFileNames.yaml b/dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml
similarity index 100%
rename from dfall_ws/src/d_fall_pps/param/YamlFileNames.yaml
rename to dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml
diff --git a/dfall_ws/src/d_fall_pps/scripts/land_crazyflie b/dfall_ws/src/dfall_pkg/scripts/land_crazyflie
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/land_crazyflie
rename to dfall_ws/src/dfall_pkg/scripts/land_crazyflie
diff --git a/dfall_ws/src/d_fall_pps/scripts/load_custom_controller b/dfall_ws/src/dfall_pkg/scripts/load_custom_controller
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/load_custom_controller
rename to dfall_ws/src/dfall_pkg/scripts/load_custom_controller
diff --git a/dfall_ws/src/d_fall_pps/scripts/load_safe_controller b/dfall_ws/src/dfall_pkg/scripts/load_safe_controller
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/load_safe_controller
rename to dfall_ws/src/dfall_pkg/scripts/load_safe_controller
diff --git a/dfall_ws/src/d_fall_pps/scripts/motors_off_crazyflie b/dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/motors_off_crazyflie
rename to dfall_ws/src/dfall_pkg/scripts/motors_off_crazyflie
diff --git a/dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint b/dfall_ws/src/dfall_pkg/scripts/safe_controller_setpoint
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/safe_controller_setpoint
rename to dfall_ws/src/dfall_pkg/scripts/safe_controller_setpoint
diff --git a/dfall_ws/src/d_fall_pps/scripts/take_off_crazyflie b/dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie
similarity index 100%
rename from dfall_ws/src/d_fall_pps/scripts/take_off_crazyflie
rename to dfall_ws/src/dfall_pkg/scripts/take_off_crazyflie
diff --git a/dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp b/dfall_ws/src/dfall_pkg/src/CrazyflieIO.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/CrazyflieIO.cpp
rename to dfall_ws/src/dfall_pkg/src/CrazyflieIO.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/classes/GetParamtersAndNamespaces.cpp
rename to dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/BatteryMonitor.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/CentralManagerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/CentralManagerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/CentralManagerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/DefaultControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/DemoControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/MpcControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PPSClient.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/PPSClient.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/PPSClient.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/ParameterService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/PickerControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/RemoteControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/SafeControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/StudentControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/TuningControllerService.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
diff --git a/dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
similarity index 100%
rename from dfall_ws/src/d_fall_pps/src/nodes/ViconDataPublisher.cpp
rename to dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
diff --git a/dfall_ws/src/d_fall_pps/srv/CMCommand.srv b/dfall_ws/src/dfall_pkg/srv/CMCommand.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/CMCommand.srv
rename to dfall_ws/src/dfall_pkg/srv/CMCommand.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/CMQuery.srv b/dfall_ws/src/dfall_pkg/srv/CMQuery.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/CMQuery.srv
rename to dfall_ws/src/dfall_pkg/srv/CMQuery.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/CMRead.srv b/dfall_ws/src/dfall_pkg/srv/CMRead.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/CMRead.srv
rename to dfall_ws/src/dfall_pkg/srv/CMRead.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/CMUpdate.srv b/dfall_ws/src/dfall_pkg/srv/CMUpdate.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/CMUpdate.srv
rename to dfall_ws/src/dfall_pkg/srv/CMUpdate.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/Controller.srv b/dfall_ws/src/dfall_pkg/srv/Controller.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/Controller.srv
rename to dfall_ws/src/dfall_pkg/srv/Controller.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/GetSetpointService.srv b/dfall_ws/src/dfall_pkg/srv/GetSetpointService.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/GetSetpointService.srv
rename to dfall_ws/src/dfall_pkg/srv/GetSetpointService.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/IntIntService.srv b/dfall_ws/src/dfall_pkg/srv/IntIntService.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/IntIntService.srv
rename to dfall_ws/src/dfall_pkg/srv/IntIntService.srv
diff --git a/dfall_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv b/dfall_ws/src/dfall_pkg/srv/LoadYamlFromFilename.srv
similarity index 100%
rename from dfall_ws/src/d_fall_pps/srv/LoadYamlFromFilename.srv
rename to dfall_ws/src/dfall_pkg/srv/LoadYamlFromFilename.srv
-- 
GitLab


From 2eceb1d30e2db5aa09cdad8780c9a08d8e3fd759 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 7 Feb 2019 22:29:09 +0100
Subject: [PATCH 54/87] Update the description, maintainer email, and license
 in the package.xml file

---
 dfall_ws/src/dfall_pkg/package.xml | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/package.xml b/dfall_ws/src/dfall_pkg/package.xml
index 12f6dea7..f07c112e 100755
--- a/dfall_ws/src/dfall_pkg/package.xml
+++ b/dfall_ws/src/dfall_pkg/package.xml
@@ -2,18 +2,18 @@
 <package>
   <name>dfall_pkg</name>
   <version>0.0.0</version>
-  <description>The dfall_pkg package</description>
+  <description>The Distributed Flying and Localisation Laboratory (D-FaLL) package</description>
 
   <!-- One maintainer tag required, multiple allowed, one person per tag --> 
   <!-- Example:  -->
   <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
-  <maintainer email="crazyflie@todo.todo">crazyflie</maintainer>
+  <maintainer email="pbeuchat43@gmail.com">crazyflie</maintainer>
 
 
   <!-- One license tag required, multiple allowed, one license per tag -->
   <!-- Commonly used license strings: -->
   <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
-  <license>TODO</license>
+  <license>GPLv3</license>
 
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
-- 
GitLab


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 55/87] 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


From 6aad68b0985dd1e6062691f38e1e9d0df2c3f5c6 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sat, 9 Feb 2019 18:27:18 +0100
Subject: [PATCH 56/87] Removed all the commented out old code from the Picker
 Controller

---
 .../include/nodes/PickerControllerService.h   | 265 +--------
 .../src/dfall_pkg/param/PickerController.yaml |  27 -
 .../src/nodes/PickerControllerService.cpp     | 510 ------------------
 3 files changed, 1 insertion(+), 801 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
index e7cfd58f..fa7c40f3 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
@@ -65,12 +65,6 @@
 #include "dfall_pkg/Controller.h"
 #include "dfall_pkg/DebugMsg.h"
 
-//the generated structs from the msg-files have to be included
-// #include "dfall_pkg/Setpoint.h"
-// #include "dfall_pkg/SetpointV2.h"
-// #include "dfall_pkg/ControlCommand.h"
-// #include "dfall_pkg/CustomButton.h"
-
 // Include the DFALL service types
 #include "dfall_pkg/LoadYamlFromFilename.h"
 #include "dfall_pkg/GetSetpointService.h"
@@ -106,39 +100,6 @@ using namespace dfall_pkg;
 
 // These constants are defined to make the code more readable and adaptable.
 
-// FOR WHICH BUTTON WAS PRESSED IN THE PICKER CONTOLLER
-// #define PICKER_BUTTON_GOTOSTART     1
-// #define PICKER_BUTTON_ATTACH        2
-// #define PICKER_BUTTON_PICKUP        3
-// #define PICKER_BUTTON_GOTOEND       4
-// #define PICKER_BUTTON_PUTDOWN       5
-// #define PICKER_BUTTON_SQUAT         6
-// #define PICKER_BUTTON_JUMP          7
-
-// #define PICKER_BUTTON_1             11
-// #define PICKER_BUTTON_2             12
-// #define PICKER_BUTTON_3             13
-// #define PICKER_BUTTON_4             14
-
-
-// These constants define the modes that can be used for controller the Crazyflie 2.0,
-// the constants defined here need to be in agreement with those defined in the
-// firmware running on the Crazyflie 2.0.
-// The following is a short description about each mode:
-// MOTOR_MODE    In this mode the Crazyflie will apply the requested 16-bit per motor
-//               command directly to each of the motors
-// RATE_MODE     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.
-// ANGE_MODE     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_MOTOR   6
-// #define CF_COMMAND_TYPE_RATE    7
-// #define CF_COMMAND_TYPE_ANGLE   8
-
 // These constants define the method used for estimating the Inertial
 // frame state.
 // All methods are run at all times, this flag indicates which estimate
@@ -331,184 +292,6 @@ ros::Publisher m_setpointChangedPublisher;
 
 
 
-// // Current time
-// int m_time_ticks = 0;
-// float m_time_seconds;
-
-// // > Mass of the Crazyflie quad-rotor, in [grams]
-// float m_mass_CF_grams;
-
-// // > Mass of the letters to be lifted, in [grams]
-// float m_mass_E_grams;
-// float m_mass_T_grams;
-// float m_mass_H_grams;
-
-// // > Total mass of the Crazyflie plus whatever it is carrying, in [grams]
-// float m_mass_total_grams;
-
-// // Thickness of the object at pick-up and put-down, in [meters]
-// // > This should also account for extra height due to 
-// //   the surface where the object is
-// float m_thickness_of_object_at_pickup;
-// float m_thickness_of_object_at_putdown;
-
-// // (x,y) coordinates of the pickup location
-// std::vector<float> m_pickup_coordinates_xy(2);
-
-// // (x,y) coordinates of the drop off location
-// std::vector<float> m_dropoff_coordinates_xy_for_E(2);
-// std::vector<float> m_dropoff_coordinates_xy_for_T(2);
-// std::vector<float> m_dropoff_coordinates_xy_for_H(2);
-
-// // Length of the string from the Crazyflie
-// // to the end of the Picker, in [meters]
-// float m_picker_string_length;
-
-// // > The setpoints for (x,y,z) position and yaw angle, in that order
-// float m_setpoint[4] = {0.0,0.0,0.4,0.0};
-// float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
-
-// // > Small adjustments to the x-y setpoint
-// float m_xAdjustment = 0.0f;
-// float m_yAdjustment = 0.0f;
-
-// // Boolean for whether to limit rate of change of the setpoint
-// bool m_shouldSmoothSetpointChanges = true;
-
-// // Max setpoint change per second
-// float m_max_setpoint_change_per_second_horizontal;
-// float m_max_setpoint_change_per_second_vertical;
-// float m_max_setpoint_change_per_second_yaw_degrees;
-// float m_max_setpoint_change_per_second_yaw_radians;
-
-
-// // Frequency at which the controller is running
-// float m_vicon_frequency;
-
-
-
-
-
-// THE FOLLOWING PARAMETERS ARE USED
-// FOR THE LOW-LEVEL CONTROLLER
-
-// // Frequency at which the controller is running
-// float control_frequency;
-
-// // > Coefficients of the 16-bit command to thrust conversion
-// std::vector<float> motorPoly(3);
-
-// // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
-// std::vector<float> gainMatrixThrust_NineStateVector (9,0.0);
-// std::vector<float> gainMatrixRollRate               (9,0.0);
-// std::vector<float> gainMatrixPitchRate              (9,0.0);
-// std::vector<float> gainMatrixYawRate                (9,0.0);
-
-// // The 16-bit command limits
-// float cmd_sixteenbit_min;
-// float cmd_sixteenbit_max;
-
-
-// // VARIABLES FOR THE ESTIMATOR
-
-// // Frequency at which the controller is running
-// float estimator_frequency;
-
-// // > A flag for which estimator to use:
-// int estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
-// // > The current state interial estimate,
-// //   for use by the controller
-// float current_stateInertialEstimate[12];
-
-// // > The measurement of the Crazyflie at the "current" time step,
-// //   to avoid confusion
-// float current_xzy_rpy_measurement[6];
-
-// // > The measurement of the Crazyflie at the "previous" time step,
-// //   used for computing finite difference velocities
-// float previous_xzy_rpy_measurement[6];
-
-// // > The full 12 state estimate maintained by the finite
-// //   difference state estimator
-// float stateInterialEstimate_viaFiniteDifference[12];
-
-// // > The full 12 state estimate maintained by the point mass
-// //   kalman filter state estimator
-// float stateInterialEstimate_viaPointMassKalmanFilter[12];
-
-// // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
-// // > For the (x,y,z) position
-// std::vector<float> PMKF_Ahat_row1_for_positions (2,0.0);
-// std::vector<float> PMKF_Ahat_row2_for_positions (2,0.0);
-// std::vector<float> PMKF_Kinf_for_positions      (2,0.0);
-// // > For the (roll,pitch,yaw) angles
-// std::vector<float> PMKF_Ahat_row1_for_angles    (2,0.0);
-// std::vector<float> PMKF_Ahat_row2_for_angles    (2,0.0);
-// std::vector<float> PMKF_Kinf_for_angles         (2,0.0);
-
-
-
-// // VARIABLES FOR THE NAMESPACES FOR THE PARAMETER SERVICES
-// // > For the paramter service of this agent
-// std::string namespace_to_own_agent_parameter_service;
-// // > For the parameter service of the coordinator
-// std::string namespace_to_coordinator_parameter_service;
-
-
-// // ROS PUBLISHER FOR SENDING OUT THE DEBUG MESSAGES
-// ros::Publisher debugPublisher;
-
-
-// // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
-
-// // Boolean whether to execute the convert into body frame function
-// bool shouldPerformConvertIntoBodyFrame = false;
-
-
-// // VARIABLES RELATING TO THE PUBLISHING OF A DEBUG MESSAGE
-
-// // Boolean indiciating whether the "Debug Message" of this agent should be published or not
-// bool shouldPublishDebugMessage = false;
-
-// // Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
-// bool shouldDisplayDebugInfo = false;
-
-
-// // VARIABLES RELATING TO PUBLISHING CURRENT POSITION AND FOLLOWING ANOTHER AGENT'S
-// // POSITION
-
-// // The ID of this agent, i.e., the ID of this compute
-// int my_agentID = 0;
-
-// // Boolean indicating whether the (x,y,z,yaw) of this agent should be published or not
-// // > The default behaviour is: do not publish,
-// // > This varaible is changed based on parameters loaded from the YAML file
-// bool shouldPublishCurrent_xyz_yaw = false;
-
-
-// // ROS Publisher for my current (x,y,z,yaw) position
-// ros::Publisher my_current_xyz_yaw_publisher;
-
-// // ROS Publisher for the current setpoint
-// ros::Publisher pickerSetpointToGUIPublisher;
-
-
-// RELEVANT NOTES ABOUT THE VARIABLES DECLARE HERE:
-// The "CrazyflieData" type used for the "request" variable is a
-// structure as defined in the file "CrazyflieData.msg" which has the following
-// properties:
-//     string crazyflieName              The name given to the Crazyflie in the Vicon software
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-
-
-
 
 
 //    ----------------------------------------------------------------------------------
@@ -535,16 +318,6 @@ ros::Publisher m_setpointChangedPublisher;
 // ADDED FOR THE PICKER
 void perControlCycleOperations();
 
-// CALLBACK FROM ROS MESSAGES RECEIVED
-//void buttonPressedCallback(const std_msgs::Int32& msg);
-// void zSetpointCallback(const std_msgs::Float32& msg);
-// void yawSetpointCallback(const std_msgs::Float32& msg);
-// void massCallback(const std_msgs::Float32& msg);
-// void xAdjustmentCallback(const std_msgs::Float32& msg);
-// void yAdjustmentCallback(const std_msgs::Float32& msg);
-
-//void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2);
-
 
 // SEPARATE CALLBACK FUNCTIONS FOR EACH BUTTON
 void buttonPressed_goto_start();
@@ -556,30 +329,6 @@ void buttonPressed_squat();
 void buttonPressed_jump();
 void buttonPressed_standby();
 
-// void buttonPressed_1();
-// void buttonPressed_2();
-// void buttonPressed_3();
-// void buttonPressed_4();
-
-
-// SEPARATE CALLBACK FUNCTIONS FOR EACH BUTTON
-// > WITH A SETPOINT IN THE MESSAGE
-// void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2);
-
-// void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2);
-// void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2);
-
-
-
-
 
 
 
@@ -629,17 +378,5 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 void publish_current_xyz_yaw(float x, float y, float z, float yaw);
 
 // FOR LOADING THE YAML PARAMETERS
-// float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
-// void  getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
-// int   getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
-// void  getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
-// int   getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
-// bool  getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
-
 void isReadyPickerControllerYamlCallback(const IntWithHeader & msg);
-void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle);
-
-//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-//void fetchYamlParameters(ros::NodeHandle& nodeHandle);
-//void processFetchedParameters();
-
+void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/PickerController.yaml b/dfall_ws/src/dfall_pkg/param/PickerController.yaml
index e9ee0b09..f319b4fd 100644
--- a/dfall_ws/src/dfall_pkg/param/PickerController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/PickerController.yaml
@@ -6,33 +6,6 @@ max_setpoint_change_per_second_yaw_degrees : 90.00 # [degrees]
 
 
 
-# Mass of the letters
-#mass_E : 3.2
-#mass_T : 2.9
-#mass_H : 3.3
-
-# Thickness of the object at pick-up and put-down, in [meters]
-# > This should also account for extra height due to 
-#   the surface where the object is
-#thickness_of_object_at_pickup  : 0.02
-#thickness_of_object_at_putdown : 0.03
-
-# (x,y) coordinates of the pickup location
-#pickup_coordinates_xy : [-0.26, 0.12]
-
-# (x,y) coordinates of the drop off location
-#dropoff_coordinates_xy_for_E : [ 0.33, -0.03]
-#dropoff_coordinates_xy_for_T : [ 0.24, 0.00]
-#dropoff_coordinates_xy_for_H : [ 0.28, 0.00]
-
-# Length of the string from the Crazyflie
-# to the end of the Picker, in [meters]
-#picker_string_length : 0.30
-
-
-
-
-
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index 59a38b1c..209c4979 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -152,305 +152,52 @@ void perControlCycleOperations()
 void buttonPressed_goto_start()
 {
 	ROS_INFO("[PICKER CONTROLLER] Goto Start button pressed");
-
-	// // The drone should move smoothly to the start point:
-	// m_shouldSmoothSetpointChanges = true;
-	// // Set the (x,y) coordinates for the start point:
-	// m_setpoint[0] = m_pickup_coordinates_xy[0];
-	// m_setpoint[1] = m_pickup_coordinates_xy[1];
-	// // Set the z coordinate to be a little more than the
-	// // length of the "picker string"
-	// m_setpoint[2] = m_picker_string_length + 0.10;
-	// // Publish the setpoint so that the GUI updates
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_attach()
 {
 	ROS_INFO("[PICKER CONTROLLER] Attach button pressed");
-
-	// m_shouldSmoothSetpointChanges = true;
-	// m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_pickup;
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_lift_up()
 {
 	ROS_INFO("[PICKER CONTROLLER] Pick up button pressed");
-
-	// m_shouldSmoothSetpointChanges = true;
-	// m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
-	// m_setpoint[2] = m_picker_string_length + 0.25;
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_goto_end()
 {
 	ROS_INFO("[PICKER CONTROLLER] Goto End button pressed");
 
-	// m_shouldSmoothSetpointChanges = true;
-	// m_setpoint[0] = m_dropoff_coordinates_xy_for_E[0];
-	// m_setpoint[1] = m_dropoff_coordinates_xy_for_E[1];
-	// publishCurrentSetpoint();
 }	
 
 void buttonPressed_put_down()
 {
 	ROS_INFO("[PICKER CONTROLLER] Put down button pressed");
-
-	// m_shouldSmoothSetpointChanges = true;
-	// m_setpoint[2] = m_picker_string_length + m_thickness_of_object_at_putdown;
-	// m_mass_total_grams = m_mass_CF_grams;
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_squat()
 {
 	ROS_INFO("[PICKER CONTROLLER] Squat button pressed");
-
-	// m_shouldSmoothSetpointChanges = true;
-	// m_setpoint[2] = m_picker_string_length - 0.10;
-	// m_mass_total_grams = m_mass_CF_grams;
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_jump()
 {
 	ROS_INFO("[PICKER CONTROLLER] Jump button pressed");
-
-	// m_shouldSmoothSetpointChanges = false;
-	// m_setpoint[2] = m_picker_string_length + 0.10;
-	// m_mass_total_grams = m_mass_CF_grams;
-	// publishCurrentSetpoint();
 }
 
 void buttonPressed_standby()
 {
 	ROS_INFO("[PICKER CONTROLLER] Standby button pressed");
-
-	// m_shouldSmoothSetpointChanges = false;
-	// m_setpoint[2] = m_picker_string_length + 0.10;
-	// m_mass_total_grams = m_mass_CF_grams;
-	// publishCurrentSetpoint();
 }
 
 
 
-// THESE CALLBACK FUNCTIONS ALLOW YOU TO IMPLEMENT SOME
-// CUSTOM ACTION IN RESPONSE TO THE RESPECTIVE BUTTON PRESSES
-
-// void buttonPressed_1()
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed");
-// }
-// void buttonPressed_2()
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed");
-// }
-
-// void buttonPressed_3()
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed");
-// }
-
-// void buttonPressed_4()
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed");
-// }
-
-
-
-
-
-
-
-
-
-
-// void zSetpointCallback(const std_msgs::Float32& msg)
-// {
-// 	// The "data" in the message is z-height in [meters]
-// 	float z_height = msg.data;
-// 	// Display the data
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Z Slider changed to " << z_height << " [m]" );
-// 	// Update the z-component of the setpoint class variable
-// 	m_setpoint[2] = z_height;
-// }
-
-
-// void yawSetpointCallback(const std_msgs::Float32& msg)
-// {
-// 	// The "data" in the message is yaw-angle in [radians]
-// 	float yaw_angle = msg.data;
-// 	// Display the data
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Yaw Dial changed to " << (yaw_angle*RAD2DEG) << " [deg]" );
-// 	// Update the yaw-component of the setpoint class variable
-// 	m_setpoint[3] = yaw_angle;
-// }
-
-// void massCallback(const std_msgs::Float32& msg)
-// {
-// 	// The "data" in the message is mass in [grams]
-// 	float mass = msg.data;
-// 	// Display the data
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Mass slider changed to " << mass << " [grams]" );
-// 	// Update the total mass class variable
-// 	m_mass_total_grams = mass;
-// }
-
-// void xAdjustmentCallback(const std_msgs::Float32& msg)
-// {
-// 	// The "data" in the message is adjustment in [meters]
-// 	float x_adjustment = msg.data;
-// 	// Display the data
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] X adjustment slider changed to " << x_adjustment << " [m]" );
-// 	// Update the x-adjustment class variable
-// 	m_xAdjustment = x_adjustment;
-// }
-
-// void yAdjustmentCallback(const std_msgs::Float32& msg)
-// {
-// 	// The "data" in the message is adjustment in [meters]
-// 	float y_adjustment = msg.data;
-// 	// Display the data
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Y adjustment slider changed to " << y_adjustment << " [m]" );
-// 	// Update the y-adjustment class variable
-// 	m_yAdjustment = y_adjustment;
-// }
-
-
-
-
-
-
-
-
 
 
 
 
 
 
-// CALLBACK FUNCTION THAT RUN WHEN THE RESPECTIVE BUTTON IS PRESSED
-// > AND A SETPOINT IS PROVIDED
-
-// void buttonPressedWithSetpoint_gotoStart(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto Start button pressed: (x,y,z)=(" << newSetpointV2.x << "," << newSetpointV2.y << "," << newSetpointV2.z << "), smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the (x,y,z) coordinates:
-// 	m_setpoint[0] = newSetpointV2.x;
-// 	m_setpoint[1] = newSetpointV2.y;
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_attach(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Attach button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the z coordinate:
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_pickup(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Pick up button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the z coordinate:
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Update the mass of the Crazyflie
-// 	m_mass_total_grams = m_mass_CF_grams + m_mass_E_grams;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_gotoEnd(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Goto End button pressed: (x,y)=(" << newSetpointV2.x << "," << newSetpointV2.y << "), smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the (x,y) coordinates:
-// 	m_setpoint[0] = newSetpointV2.x;
-// 	m_setpoint[1] = newSetpointV2.y;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_putdown(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Put down button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the z coordinate:
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Update the mass of the Crazyflie
-// 	m_mass_total_grams = m_mass_CF_grams;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_squat(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Squat button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the z coordinate:
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Update the mass of the Crazyflie
-// 	m_mass_total_grams = m_mass_CF_grams;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-// void buttonPressedWithSetpoint_jump(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO_STREAM("[PICKER CONTROLLER] Jump button pressed: z=" << newSetpointV2.z << ", smooth=" << int(newSetpointV2.isChecked) );
-
-// 	// Use the boolean for the smoothing flag
-// 	m_shouldSmoothSetpointChanges = newSetpointV2.isChecked;
-// 	// Set the z coordinate:
-// 	m_setpoint[2] = newSetpointV2.z;
-// 	// Update the mass of the Crazyflie
-// 	m_mass_total_grams = m_mass_CF_grams;
-// 	// Publish the setpoint so that the GUI updates
-// 	//publishCurrentSetpoint();
-// }
-
-
-// void buttonPressedWithSetpoint_1(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 1 pressed with a setpoint provided");
-// }
-
-// void buttonPressedWithSetpoint_2(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 2 pressed with a setpoint provided");
-// }
-
-// void buttonPressedWithSetpoint_3(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 3 pressed with a setpoint provided");
-// }
-
-// void buttonPressedWithSetpoint_4(const SetpointV2& newSetpointV2)
-// {
-// 	ROS_INFO("[PICKER CONTROLLER] Button 4 pressed with a setpoint provided with a setpoint provided");
-// }
-
-
 
 
 
@@ -1296,147 +1043,6 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 
 
 
-// // 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;
-//     m_setpoint[1] = newSetpoint.y;
-//     m_setpoint[2] = newSetpoint.z;
-//     m_setpoint[3] = newSetpoint.yaw;
-// }
-
-
-// void publishCurrentSetpoint()
-// {
-// 	Setpoint msg_setpoint;
-//     msg_setpoint.x   = m_setpoint[0];
-//     msg_setpoint.y   = m_setpoint[1];
-//     msg_setpoint.z   = m_setpoint[2];
-//     msg_setpoint.yaw = m_setpoint[3];
-
-//     pickerSetpointToGUIPublisher.publish(msg_setpoint);
-// }
-
-
-
-
-
-//    ----------------------------------------------------------------------------------
-//     CCCC  U   U   SSSS  TTTTT   OOO   M   M
-//    C      U   U  S        T    O   O  MM MM
-//    C      U   U   SSS     T    O   O  M M M
-//    C      U   U      S    T    O   O  M   M
-//     CCCC   UUU   SSSS     T     OOO   M   M
-//
-//     CCCC   OOO   M   M  M   M    A    N   N  DDDD
-//    C      O   O  MM MM  MM MM   A A   NN  N  D   D
-//    C      O   O  M M M  M M M  A   A  N N N  D   D
-//    C      O   O  M   M  M   M  AAAAA  N  NN  D   D
-//     CCCC   OOO   M   M  M   M  A   A  N   N  DDDD
-//    ----------------------------------------------------------------------------------
-
-// CUSTOM COMMAND RECEIVED CALLBACK
-// void buttonPressedCallback(const std_msgs::Int32& msg)
-// {
-// 	// Extract the data from the message
-// 	int button_index = msg.data;
-
-// 	// Switch between the button pressed
-// 	switch(button_index)
-// 	{
-// 		case PICKER_BUTTON_GOTOSTART:
-// 			buttonPressed_gotoStart();
-// 			break;
-// 		case PICKER_BUTTON_ATTACH:
-// 			buttonPressed_attach();
-// 			break;
-// 		case PICKER_BUTTON_PICKUP:
-// 			buttonPressed_pickup();
-// 			break;
-// 		case PICKER_BUTTON_GOTOEND:
-// 			buttonPressed_gotoEnd();
-// 			break;
-// 		case PICKER_BUTTON_PUTDOWN:
-// 			buttonPressed_putdown();
-// 			break;
-// 		case PICKER_BUTTON_SQUAT:
-// 			buttonPressed_squat();
-// 			break;
-// 		case PICKER_BUTTON_JUMP:
-// 			buttonPressed_jump();
-// 			break;
-// 		case PICKER_BUTTON_1:
-// 			buttonPressed_1();
-// 			break;
-// 		case PICKER_BUTTON_2:
-// 			buttonPressed_2();
-// 			break;
-// 		case PICKER_BUTTON_3:
-// 			buttonPressed_3();
-// 			break;
-// 		case PICKER_BUTTON_4:
-// 			buttonPressed_4();
-// 			break;
-// 		default:
-// 		{
-// 			// Let the user know that the command was not recognised
-// 			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
-// 			break;
-// 		}
-// 	}
-// }
-
-
-
-// void buttonPressedWithSetpointCallback(const SetpointV2& newSetpointV2)
-// {
-// 	// Extract the "buttonID" from the message
-// 	int button_index = newSetpointV2.buttonID;
-
-// 	// Switch between the button pressed
-// 	switch(button_index)
-// 	{
-// 		case PICKER_BUTTON_GOTOSTART:
-// 			buttonPressedWithSetpoint_gotoStart(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_ATTACH:
-// 			buttonPressedWithSetpoint_attach(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_PICKUP:
-// 			buttonPressedWithSetpoint_pickup(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_GOTOEND:
-// 			buttonPressedWithSetpoint_gotoEnd(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_PUTDOWN:
-// 			buttonPressedWithSetpoint_putdown(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_SQUAT:
-// 			buttonPressedWithSetpoint_squat(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_JUMP:
-// 			buttonPressedWithSetpoint_jump(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_1:
-// 			buttonPressedWithSetpoint_1(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_2:
-// 			buttonPressedWithSetpoint_2(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_3:
-// 			buttonPressedWithSetpoint_3(newSetpointV2);
-// 			break;
-// 		case PICKER_BUTTON_4:
-// 			buttonPressedWithSetpoint_4(newSetpointV2);
-// 			break;
-// 		default:
-// 		{
-// 			// Let the user know that the command was not recognised
-// 			ROS_INFO_STREAM("[PICKER CONTROLLER] A button pressed message was received in the controller but not recognised, message.data = " << button_index );
-// 			break;
-// 		}
-// 	}
-// }
 
 
 
@@ -1538,27 +1144,6 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 
 	// GET THE PARAMETERS:
 
-	// // // > The mass of the letters
-	// m_mass_E_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_E");
-	// m_mass_T_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_T");
-	// m_mass_H_grams = getParameterFloat(nodeHandle_for_paramaters , "mass_H");
-
-	// // Thickness of the object at pick-up and put-down, in [meters]
-	// // > This should also account for extra height due to the surface where the object is
-	// m_thickness_of_object_at_pickup  = getParameterFloat(nodeHandle_for_paramaters , "thickness_of_object_at_pickup");
-	// m_thickness_of_object_at_putdown = getParameterFloat(nodeHandle_for_paramaters , "thickness_of_object_at_putdown");
-
-	// // (x,y) coordinates of the pickup location
-	// getParameterFloatVector(nodeHandle_for_paramaters, "pickup_coordinates_xy", m_pickup_coordinates_xy, 2);
-
-	// // (x,y) coordinates of the drop off location
-	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_E", m_dropoff_coordinates_xy_for_E, 2);
-	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_T", m_dropoff_coordinates_xy_for_T, 2);
-	// getParameterFloatVector(nodeHandle_for_paramaters, "dropoff_coordinates_xy_for_H", m_dropoff_coordinates_xy_for_H, 2);
-
-	// // Length of the string from the Crazyflie to the end of the Picker, in [meters]
-	// m_picker_string_length = getParameterFloat(nodeHandle_for_paramaters , "picker_string_length");
-
 	// Max setpoint change per second
 	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_horizontal");
 	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_vertical");
@@ -1633,74 +1218,6 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 
 
 
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT  PPPP     A    RRRR     A    M   M   ( )
-//    G      E        T    P   P   A A   R   R   A A   MM MM  (   )
-//    G      EEE      T    PPPP   A   A  RRRR   A   A  M M M  (   )
-//    G   G  E        T    P      AAAAA  R  R   AAAAA  M   M  (   )
-//     GGGG  EEEEE    T    P      A   A  R   R  A   A  M   M   ( )
-//    ----------------------------------------------------------------------------------
-
-
-// // 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;
-//     if(!nodeHandle.getParam(name, val))
-//     {
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     return val;
-// }
-// // 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)){
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     if(val.size() != length) {
-//         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
-//     }
-// }
-// // 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;
-//     if(!nodeHandle.getParam(name, val))
-//     {
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     return val;
-// }
-// // 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)){
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     if(val.size() != length) {
-//         ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
-//     }
-// }
-// // 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)){
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     return val.size();
-// }
-// // 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;
-//     if(!nodeHandle.getParam(name, val))
-//     {
-//         ROS_ERROR_STREAM("missing parameter '" << name << "'");
-//     }
-//     return val;
-// }
-    
 
 
 
@@ -1911,39 +1428,12 @@ int main(int argc, char* argv[]) {
     // of this service the "calculateControlOutput" function is called.
     ros::ServiceServer service = nodeHandle.advertiseService("PickerController", calculateControlOutput);
 
-    // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
-    //     "using namespace dfall_pkg;"
-    // in the "DEFINES" section at the top of this file.
-    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
-
     // Instantiate the instance variable "my_current_xyz_yaw_publisher" to be a "ros::Publisher"
     // that advertises under the name "<my_agentID>/my_current_xyz_yaw_topic" where <my_agentID>
     // is filled in with the student ID number of this computer. The messages published will
     // have the structure defined in the file "Setpoint.msg" (located in the "msg" folder).
     //my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
 
-    // Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
-    // type variable that subscribes to the "StudentCustomButton" topic and calls the class
-    // function "customCommandReceivedCallback" each time a messaged is received on this topic
-    // and the message received is passed as an input argument to the callback function.
-    //ros::Subscriber buttonPressedCallbackSubscriber = nodeHandle.subscribe("GUIButton", 1, customCommandReceivedCallback);
-
-
-
-    // // ADDED FOR THE PICKER
-    // ros::Subscriber pickerButtonPressedSubscriber  =  nodeHandle.subscribe("ButtonPressed", 1, buttonPressedCallback);
-    // ros::Subscriber pickerZSetpointSubscriber      =  nodeHandle.subscribe("ZSetpoint", 1, zSetpointCallback);
-    // ros::Subscriber pickerYawSetpointSubscriber    =  nodeHandle.subscribe("YawSetpoint", 1, yawSetpointCallback);
-    // ros::Subscriber pickerMassSubscriber           =  nodeHandle.subscribe("Mass", 1, massCallback);
-    // ros::Subscriber pickerXAdjustmentSubscriber    =  nodeHandle.subscribe("XAdjustment", 1, xAdjustmentCallback);
-    // ros::Subscriber pickerYAdjustmentSubscriber    =  nodeHandle.subscribe("YAdjustment", 1, yAdjustmentCallback);
-
-    // pickerSetpointToGUIPublisher = nodeHandle.advertise<Setpoint>("SetpointToGUI", 1);
-
-    // ros::Subscriber pickerButtonPressedWithSetpointSubscriber  =  nodeHandle.subscribe("ButtonPressedWithSetpoint", 1, buttonPressedWithSetpointCallback);
-
-
 
     // Print out some information to the user.
     ROS_INFO("[Picker CONTROLLER] Service ready :-)");
-- 
GitLab


From 112cd7de280cdbaea71e2b5f1a5081d7cad0d95e Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 09:24:03 +0100
Subject: [PATCH 57/87] Emergency stop button now hidden when flying agent gui
 is launched for an agent

---
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp       | 15 ++++++++++++++-
 1 file changed, 14 insertions(+), 1 deletion(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index fb731181..b0a339e6 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -105,6 +105,10 @@ TopBanner::TopBanner(QWidget *parent) :
     // INITIALISATIONS ARE COMPLETE
     if (m_type == TYPE_AGENT)
     {
+        // Hide the "emergency stop"
+        ui->emergency_stop_button->hide();
+
+        // Load the context for this agent
     	loadCrazyflieContext(m_ID,1000);
     }
     else if (m_type == TYPE_COORDINATOR)
@@ -113,12 +117,18 @@ TopBanner::TopBanner(QWidget *parent) :
 		QString qstr_title = "Flying Agent GUI: for COORDINATOR ID ";
 		qstr_title.append( QString::number(m_ID) );
 		ui->top_banner_label->setText(qstr_title);
+
+        // show the "emergency stop"
+        ui->emergency_stop_button->show();
 	}
 	else
 	{
 		// Set the label to inform the user of the error
 		QString qstr_title = "Flying Agent GUI: for UNKNOWN NODE TYPE";
 		ui->top_banner_label->setText(qstr_title);
+
+        // Hide the "emergency stop"
+        ui->emergency_stop_button->hide();
     }
 
 }
@@ -174,7 +184,7 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
 	contextCall.request.studentID = ID_to_request_from_database;
 	//ROS_INFO_STREAM("StudentID:" << m_agentID);
 
-	centralManagerDatabaseService.waitForExistence(ros::Duration(-1));
+	centralManagerDatabaseService.waitForExistence(ros::Duration(2));
 
 	if(centralManagerDatabaseService.call(contextCall))
 	{
@@ -203,6 +213,9 @@ void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_
 	{
 		ROS_ERROR_STREAM("[TOP BANNER GUI] Failed to load context for agentID = " << m_ID);
 
+        // Set the Crazyflie Name String to be a question mark
+        qstr_crazyflie_name.append("?");
+
         m_object_name_for_emitting_pose_data = "";
 
         if (emit_after_milliseconds == 0)
-- 
GitLab


From 0b74418c81b57cc23ebd553a6c5853716f4e4e57 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 09:36:46 +0100
Subject: [PATCH 58/87] Changed header field from shouldCheckForID to
 shouldCheckForAgentID

---
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp         |  2 +-
 .../flyingAgentGUI/src/connectstartstopbar.cpp       |  6 +++---
 .../GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp     | 10 +++++-----
 .../src/enablecontrollerloadyamlbar.cpp              | 12 ++++++------
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp         |  4 ++--
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp          |  2 +-
 .../flyingAgentGUI/src/tuningcontrollertab.cpp       |  6 +++---
 dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py      | 10 +++++-----
 .../include/classes/GetParamtersAndNamespaces.h      |  2 +-
 dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg       |  2 +-
 dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg         |  2 +-
 dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg      |  2 +-
 .../src/classes/GetParamtersAndNamespaces.cpp        |  6 +++---
 dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp  |  2 +-
 .../dfall_pkg/src/nodes/DefaultControllerService.cpp |  4 ++--
 .../dfall_pkg/src/nodes/DemoControllerService.cpp    |  4 ++--
 .../src/dfall_pkg/src/nodes/FlyingAgentClient.cpp    | 10 +++++-----
 .../src/dfall_pkg/src/nodes/ParameterService.cpp     |  4 ++--
 .../dfall_pkg/src/nodes/PickerControllerService.cpp  |  4 ++--
 .../dfall_pkg/src/nodes/StudentControllerService.cpp |  4 ++--
 .../dfall_pkg/src/nodes/TuningControllerService.cpp  |  6 +++---
 21 files changed, 52 insertions(+), 52 deletions(-)

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 f1119906..441e11d9 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
@@ -1110,7 +1110,7 @@ void MainGUIWindow::on_all_motors_off_button_clicked()
 {
     dfall_pkg::IntWithHeader msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     //commandAllAgentsPublisher.publish(msg);
     emergencyStopPublisher.publish(msg);
 }
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 b15b8e0b..0d8c8bfd 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
@@ -709,7 +709,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
     {
         case TYPE_AGENT:
         {
-            msg.shouldCheckForID = false;
+            msg.shouldCheckForAgentID = false;
             break;
         }
         case TYPE_COORDINATOR:
@@ -717,7 +717,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
             // Lock the mutex
             m_agentIDs_toCoordinate_mutex.lock();
             // Add the "coordinate all" flag
-            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
@@ -733,7 +733,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
 
         default:
         {
-            msg.shouldCheckForID = true;
+            msg.shouldCheckForAgentID = true;
             ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
             break;
         }
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 a31d6804..2492c229 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
@@ -762,7 +762,7 @@ void CoordinatorRow::on_rf_connect_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_RECONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
     ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Connect button clicked");
@@ -773,7 +773,7 @@ void CoordinatorRow::on_rf_disconnect_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_DISCONNECT;
     this->crazyRadioCommandPublisher.publish(msg);
     ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disconnect button clicked");
@@ -784,7 +784,7 @@ void CoordinatorRow::on_enable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_CRAZYFLY_TAKE_OFF;
     this->flyingStateCommandPublisher.publish(msg);
     ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Enable flying button clicked");
@@ -795,7 +795,7 @@ void CoordinatorRow::on_disable_flying_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_CRAZYFLY_LAND;
     this->flyingStateCommandPublisher.publish(msg);
     ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disable flying button clicked");
@@ -806,7 +806,7 @@ void CoordinatorRow::on_motors_off_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->flyingStateCommandPublisher.publish(msg);
     ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Motors-off button clicked");
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 5b3de64b..00b09c8a 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
@@ -269,7 +269,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader
     {
         case TYPE_AGENT:
         {
-            msg.shouldCheckForID = false;
+            msg.shouldCheckForAgentID = false;
             break;
         }
         case TYPE_COORDINATOR:
@@ -277,7 +277,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader
             // Lock the mutex
             m_agentIDs_toCoordinate_mutex.lock();
             // Add the "coordinate all" flag
-            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
@@ -293,7 +293,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader
 
         default:
         {
-            msg.shouldCheckForID = true;
+            msg.shouldCheckForAgentID = true;
             ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
             break;
         }
@@ -313,7 +313,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith
     {
         case TYPE_AGENT:
         {
-            msg.shouldCheckForID = false;
+            msg.shouldCheckForAgentID = false;
             break;
         }
         case TYPE_COORDINATOR:
@@ -321,7 +321,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith
             // Lock the mutex
             m_agentIDs_toCoordinate_mutex.lock();
             // Add the "coordinate all" flag
-            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
@@ -337,7 +337,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith
 
         default:
         {
-            msg.shouldCheckForID = true;
+            msg.shouldCheckForAgentID = true;
             ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
             break;
         }
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index b96cbfa5..2ca4c562 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -185,7 +185,7 @@ void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
     // Specify the data
     yaml_filename_msg.data = "BatteryMonitor";
     // Set for whom this applies to
-    yaml_filename_msg.shouldCheckForID = false;
+    yaml_filename_msg.shouldCheckForAgentID = false;
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 #endif
@@ -203,7 +203,7 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
     // Specify the data
     yaml_filename_msg.data = "ClientConfig";
     // Set for whom this applies to
-    yaml_filename_msg.shouldCheckForID = false;
+    yaml_filename_msg.shouldCheckForAgentID = false;
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
 #endif
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index b0a339e6..9990e51c 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -262,7 +262,7 @@ void TopBanner::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
-    msg.shouldCheckForID = false;
+    msg.shouldCheckForAgentID = false;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     this->emergencyStopPublisher.publish(msg);
     ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index afcfb970..b2b101c8 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -537,7 +537,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m
     {
         case TYPE_AGENT:
         {
-            msg.shouldCheckForID = false;
+            msg.shouldCheckForAgentID = false;
             break;
         }
         case TYPE_COORDINATOR:
@@ -545,7 +545,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m
             // Lock the mutex
             m_agentIDs_toCoordinate_mutex.lock();
             // Add the "coordinate all" flag
-            msg.shouldCheckForID = !(m_shouldCoordinateAll);
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
             // Add the agent IDs if necessary
             if (!m_shouldCoordinateAll)
             {
@@ -561,7 +561,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m
 
         default:
         {
-            msg.shouldCheckForID = true;
+            msg.shouldCheckForAgentID = true;
             ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
             break;
         }
diff --git a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
index ddc1fdf4..3345d606 100755
--- a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
+++ b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py
@@ -170,7 +170,7 @@ class CrazyRadioClient:
         self._send_to_commander_motor(0, 0, 0, 0)
         # change state to motors OFF
         msg = IntWithHeader()
-        msg.shouldCheckForID = False
+        msg.shouldCheckForAgentID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
         self.FlyingAgentClient_command_pub.publish(msg)
         time.sleep(0.1)
@@ -230,7 +230,7 @@ class CrazyRadioClient:
         self.change_status_to(CONNECTED)
         # change state to motors OFF
         msg = IntWithHeader()
-        msg.shouldCheckForID = False
+        msg.shouldCheckForAgentID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
         cf_client.FlyingAgentClient_command_pub.publish(msg)
 
@@ -260,7 +260,7 @@ class CrazyRadioClient:
 
         # change state to motors OFF
         msg = IntWithHeader()
-        msg.shouldCheckForID = False
+        msg.shouldCheckForAgentID = False
         msg.data = CMD_CRAZYFLY_MOTORS_OFF
         self.FlyingAgentClient_command_pub.publish(msg)
 
@@ -300,7 +300,7 @@ class CrazyRadioClient:
         command_is_relevant = False
 
         # Check the header details of the message for it relevance
-        if (msg.shouldCheckForID == False):
+        if (msg.shouldCheckForAgentID == False):
             command_is_relevant = True
         else:
             for this_ID in msg.agentIDs:
@@ -435,7 +435,7 @@ if __name__ == '__main__':
     cf_client._send_to_commander_motor(0, 0, 0, 0)
     # change state to motors OFF
     msg = IntWithHeader()
-    msg.shouldCheckForID = False
+    msg.shouldCheckForAgentID = False
     msg.data = CMD_CRAZYFLY_MOTORS_OFF
     cf_client.FlyingAgentClient_command_pub.publish(msg)
     #wait for client to send its commands
diff --git a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
index f61481cf..9bc7a6e8 100644
--- a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
+++ b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
@@ -129,4 +129,4 @@ void constructNamespaceForCoordinator( int coordID, std::string & coord_namespac
 void constructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace );
 
 // Check the header of a message for whether it is relevant
-bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs );
\ No newline at end of file
+bool checkMessageHeader( int agentID , bool shouldCheckForAgentID , const std::vector<uint> & agentIDs );
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg
index cc51997e..229050a8 100755
--- a/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg
+++ b/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg
@@ -1,3 +1,3 @@
 float32 data
-bool shouldCheckForID
+bool shouldCheckForAgentID
 uint32[] agentIDs
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg
index 64cbfd8c..1eb4c40c 100755
--- a/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg
+++ b/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg
@@ -1,3 +1,3 @@
 uint32 data
-bool shouldCheckForID
+bool shouldCheckForAgentID
 uint32[] agentIDs
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg
index 8a93139a..3c03b7a2 100755
--- a/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg
+++ b/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg
@@ -1,3 +1,3 @@
 string data
-bool shouldCheckForID
+bool shouldCheckForAgentID
 uint32[] agentIDs
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
index d8d7af9c..9c7fdcaf 100644
--- a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
+++ b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
@@ -209,11 +209,11 @@ void constructNamespaceForCoordinatorParameterService( int coordID, std::string
 
 
 // Check the header of a message for whether it is relevant
-bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs )
+bool checkMessageHeader( int agentID , bool shouldCheckForAgentID , const std::vector<uint> & agentIDs )
 {
-	// The messag is by default relevant if the "shouldCheckForID"
+	// The messag is by default relevant if the "shouldCheckForAgentID"
 	// flag is false
-	if (!shouldCheckForID)
+	if (!shouldCheckForAgentID)
 	{
 		return true;
 	}
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
index f83abf9a..f9ea5fbf 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
@@ -310,7 +310,7 @@ void updateBatteryStateBasedOnLevel(int level)
 void isReadyBatteryMonitorYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 20a5397d..234299b9 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -675,7 +675,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -895,7 +895,7 @@ int main(int argc, char* argv[])
 	// Specify the Yaml filename as a string
 	loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
 	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
 	// Wait until the serivce exists
 	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
 	// Make the service call
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
index ded12476..7988825d 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp
@@ -1456,7 +1456,7 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 void isReadyDemoControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -1849,7 +1849,7 @@ int main(int argc, char* argv[]) {
 	// Specify the data
 	yaml_filename_msg.data = "DemoController";
 	// Set for whom this applies to
-	yaml_filename_msg.shouldCheckForID = false;
+	yaml_filename_msg.shouldCheckForAgentID = false;
 	// Sleep to make the publisher known to ROS (in seconds)
 	//ros::Duration(1.0).sleep();
 	// Send the message
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 467973ab..72859686 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -417,7 +417,7 @@ void loadCrazyflieContext() {
             ROS_INFO("[FLYING AGENT CLIENT] CF is now different for this student. Disconnect and turn it off");
 
             IntWithHeader msg;
-            msg.shouldCheckForID = false;
+            msg.shouldCheckForAgentID = false;
             msg.data = CMD_DISCONNECT;
             crazyRadioCommandPublisher.publish(msg);
         }
@@ -438,7 +438,7 @@ void loadCrazyflieContext() {
 void commandCallback(const IntWithHeader & msg) {
 
     // Check whether the message is relevant
-    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
     // Continue if the message is relevant
     if (isRevelant)
@@ -962,7 +962,7 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn
 void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
 {
     // Check whether the message is relevant
-    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
     // Continue if the message is relevant
     if (isRevelant)
@@ -1065,7 +1065,7 @@ void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
 void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
 {
     // Check whether the message is relevant
-    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
     // Continue if the message is relevant
     if (isRevelant)
@@ -1261,7 +1261,7 @@ int main(int argc, char* argv[])
 	// // Specify the Yaml filename as a string
 	// loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
 	// // Set for whom this applies to
-	// loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	// loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
 	// // Wait until the serivce exists
 	// requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
 	// // Make the service call
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
index fe88d56e..8be89f51 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
@@ -138,9 +138,9 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo
         }
     }
     // Copy across the boolean field
-    yaml_ready_msg.shouldCheckForID = yaml_filename_to_load_with_header.shouldCheckForID;
+    yaml_ready_msg.shouldCheckForAgentID = yaml_filename_to_load_with_header.shouldCheckForAgentID;
     // Copy across the vector of IDs
-    if (yaml_filename_to_load_with_header.shouldCheckForID)
+    if (yaml_filename_to_load_with_header.shouldCheckForAgentID)
     {
         for ( int i_ID=0 ; i_ID<yaml_filename_to_load_with_header.agentIDs.size() ; i_ID++ )
         {
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index 209c4979..b581597e 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -1090,7 +1090,7 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 void isReadyPickerControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -1344,7 +1344,7 @@ int main(int argc, char* argv[]) {
 	// Specify the Yaml filename as a string
 	loadYamlFromFilenameCall.request.stringWithHeader.data = "PickerController";
 	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
 	// Wait until the serivce exists
 	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
 	// Make the service call
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index f7d7eb78..2cb30434 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -716,7 +716,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -950,7 +950,7 @@ int main(int argc, char* argv[]) {
 	// Specify the Yaml filename as a string
 	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
 	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
 	// Wait until the serivce exists
 	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
 	// Make the service call
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
index e20ab24b..3e2d5fd4 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
@@ -1320,7 +1320,7 @@ void setNewSetpoint(float x, float y, float z, float yaw)
 void requestGainChangeCallback(const FloatWithHeader& newGain)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForID , newGain.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForAgentID , newGain.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -1360,7 +1360,7 @@ void requestGainChangeCallback(const FloatWithHeader& newGain)
 void isReadyTuningControllerYamlCallback(const IntWithHeader & msg)
 {
 	// Check whether the message is relevant
-	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs );
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
 	// Continue if the message is relevant
 	if (isRevelant)
@@ -1690,7 +1690,7 @@ int main(int argc, char* argv[]) {
 	// Specify the Yaml filename as a string
 	loadYamlFromFilenameCall.request.stringWithHeader.data = "TuningController";
 	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false;
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
 	// Wait until the serivce exists
 	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
 	// Make the service call
-- 
GitLab


From a8b7f4644d50c53865e790feeeb6da17334c1016 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 10:44:16 +0100
Subject: [PATCH 59/87] Adjusted System Config GUI so that it can be compile
 stand alone with Qt

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         |   9 +-
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro        |   6 +-
 .../{src => forms}/mainguiwindow.ui           |   0
 .../CrazyFlyGUI/include/mainguiwindow.h       |   9 +-
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  | 224 ++++++++++--------
 5 files changed, 145 insertions(+), 103 deletions(-)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/{src => forms}/mainguiwindow.ui (100%)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index ee4cb694..9071a97a 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -57,9 +57,10 @@ find_package(Qt5Svg REQUIRED)
 
 
 # GUI -- Add src, includes, and resources
-set(MY_GUI_LIB_PATH_SRC ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/src)
-set(MY_GUI_LIB_PATH_INC ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/include)
-set(MY_RESOURCE_FILE_QRC ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc)
+set(MY_GUI_LIB_PATH_SRC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/src)
+set(MY_GUI_LIB_PATH_INC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/include)
+set(MY_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/forms)
+set(MY_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc)
 
 
 
@@ -99,7 +100,7 @@ set(SRC_HDRS_QOBJECT_GUI
   ${MY_GUI_LIB_PATH_INC}/CFLinker.h
   )
 # GUI -- wrap UI file and QOBJECT files
-qt5_wrap_ui(UIS_HDRS_GUI ${MY_GUI_LIB_PATH_SRC}/mainguiwindow.ui)
+qt5_wrap_ui(UIS_HDRS_GUI ${MY_GUI_LIB_PATH_FORMS}/mainguiwindow.ui)
 qt5_wrap_cpp(SRC_MOC_HDRS_GUI ${SRC_HDRS_QOBJECT_GUI})
 # GUI -- wrap resource file qrc->rcc
 qt5_add_resources(MY_RESOURCE_FILE_RCC ${MY_RESOURCE_FILE_QRC})
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
index 1f9cbd2f..61aa744e 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
@@ -20,6 +20,8 @@ QT+= svg
 
 
 SOURCES += \
+    src/centerMarker.cpp \
+    src/channelLUT.cpp \
     src/cornergrabber.cpp \
     src/crazyFlyZone.cpp \
     src/crazyFlyZoneTab.cpp \
@@ -31,6 +33,8 @@ SOURCES += \
     src/tablePiece.cpp
 
 HEADERS  += \
+    include/centerMarker.h \
+    include/channelLUT.h \
     include/cornergrabber.h \
     include/crazyFlyZone.h \
     include/crazyFlyZoneTab.h \
@@ -44,4 +48,4 @@ HEADERS  += \
     include/crazyFly.h
 
 FORMS    += \
-    src/mainguiwindow.ui
+    forms/mainguiwindow.ui
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
index d5aceaf6..e0f696cc 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
@@ -216,11 +216,12 @@ private:
     Ui::MainGUIWindow *ui;
     myGraphicsScene* scene;
 
+    void _init();
+
+#ifdef CATKIN_MAKE
     ros::Timer m_timer_yaml_file_for_safe_controller;
     ros::Timer m_timer_yaml_file_for_custom_controller;
 
-    void _init();
-
     void safeYamlFileTimerCallback(const ros::TimerEvent&);
     void customYamlFileTimerCallback(const ros::TimerEvent&);
 
@@ -232,6 +233,7 @@ private:
     void getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length);
     int getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val);
     bool getParameterBool(ros::NodeHandle& nodeHandle, std::string name);
+#endif
 
 
     #ifdef CATKIN_MAKE
@@ -271,6 +273,8 @@ private:
 
     int getTabIndexFromName(QString name);
 
+
+#ifdef CATKIN_MAKE
     CrazyflieDB m_data_base;
 
     void clear_database_file();
@@ -282,6 +286,7 @@ private:
     void save_database_file();
 
     void insert_or_update_entry_database(CrazyflieEntry entry);
+#endif
 
 };
 
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 441e11d9..1fb3cf4a 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
@@ -265,7 +265,7 @@ void MainGUIWindow::_init()
     QShortcut* close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close()));
 
 
-    #ifdef CATKIN_MAKE
+#ifdef CATKIN_MAKE
     _rosNodeThread->init();
     qRegisterMetaType<ptrToMessage>("ptrToMessage");
     QObject::connect(_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const ptrToMessage&)));
@@ -298,7 +298,7 @@ void MainGUIWindow::_init()
     // to all of the agents nodes that they should (re/dis)-connect from
     // the Crazy-Radio
     crazyRadioCommandAllAgentsPublisher = nodeHandle.advertise<std_msgs::Int32>("crazyRadioCommandAllAgents", 1);
-    #endif
+#endif
 }
 
 void MainGUIWindow::doTabClosed(int tab_index)
@@ -845,6 +845,7 @@ void MainGUIWindow::on_unlink_button_clicked()
 
 void MainGUIWindow::on_save_in_DB_button_clicked()
 {
+#ifdef CATKIN_MAKE
     // we need to update and then save?
     CrazyflieDB tmp_db;
     for(int i = 0; i < cf_linker->links.size(); i++)
@@ -889,8 +890,11 @@ void MainGUIWindow::on_save_in_DB_button_clicked()
     //std_msgs::Int32 msg;
     //msg.data = 1;
     //this->DBChangedPublisher.publish(msg);
+#endif
 }
 
+
+#ifdef CATKIN_MAKE
 void MainGUIWindow::clear_database_file()
 {
     CrazyflieDB tmp_db;
@@ -917,7 +921,10 @@ void MainGUIWindow::clear_database_file()
         ROS_INFO("Failed to read DB");
     }
 }
+#endif
+
 
+#ifdef CATKIN_MAKE
 void MainGUIWindow::fill_database_file()
 {
     clear_database_file();
@@ -930,7 +937,10 @@ void MainGUIWindow::fill_database_file()
     }
     save_database_file();
 }
+#endif
+
 
+#ifdef CATKIN_MAKE
 void MainGUIWindow::save_database_file()
 {
     CMCommand commandCall;
@@ -944,7 +954,10 @@ void MainGUIWindow::save_database_file()
         ROS_ERROR("failed to save db");
     }
 }
+#endif
 
+
+#ifdef CATKIN_MAKE
 void MainGUIWindow::insert_or_update_entry_database(CrazyflieEntry entry)
 {
     CMUpdate updateCall;
@@ -952,7 +965,10 @@ void MainGUIWindow::insert_or_update_entry_database(CrazyflieEntry entry)
     updateCall.request.crazyflieEntry = entry;
     _rosNodeThread->m_update_db_client.call(updateCall);
 }
+#endif
 
+
+#ifdef CATKIN_MAKE
 int MainGUIWindow::read_database_from_file(CrazyflieDB &read_db)
 {
     CMRead getDBCall;
@@ -967,9 +983,12 @@ int MainGUIWindow::read_database_from_file(CrazyflieDB &read_db)
         return -1;
     }
 }
+#endif
+
 
 void MainGUIWindow::on_load_from_DB_button_clicked()
 {
+#ifdef CATKIN_MAKE
     CrazyflieDB tmp_db;
 
     if(read_database_from_file(tmp_db) == 0)
@@ -1039,6 +1058,7 @@ void MainGUIWindow::on_load_from_DB_button_clicked()
     {
         ROS_ERROR("Failed to read DB");
     }
+#endif
 }
 
 void MainGUIWindow::on_comboBoxCFs_currentTextChanged(const QString &arg1)
@@ -1053,7 +1073,9 @@ void MainGUIWindow::on_comboBoxCFs_currentTextChanged(const QString &arg1)
     }
     else
     {
+        #ifdef CATKIN_MAKE
         ROS_INFO("name not found in LUT");
+        #endif
     }
 }
 
@@ -1080,156 +1102,161 @@ void MainGUIWindow::on_comboBoxCFs_currentTextChanged(const QString &arg1)
 // > (RE)CONNECT THE RADIO
 void MainGUIWindow::on_all_connect_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_RECONNECT;
-    crazyRadioCommandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_RECONNECT;
+//    crazyRadioCommandAllAgentsPublisher.publish(msg);
 }
 // > DISCONNECT THE RADIO
 void MainGUIWindow::on_all_disconnect_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_DISCONNECT;
-    crazyRadioCommandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_DISCONNECT;
+//    crazyRadioCommandAllAgentsPublisher.publish(msg);
 }
 // > TAKE-OFF
 void MainGUIWindow::on_all_take_off_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_CRAZYFLY_TAKE_OFF;
-    commandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_CRAZYFLY_TAKE_OFF;
+//    commandAllAgentsPublisher.publish(msg);
 }
 // > LAND
 void MainGUIWindow::on_all_land_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_CRAZYFLY_LAND;
-    commandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_CRAZYFLY_LAND;
+//    commandAllAgentsPublisher.publish(msg);
 }
 // > MOTORS OFF
 void MainGUIWindow::on_all_motors_off_button_clicked()
 {
+#ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     msg.shouldCheckForAgentID = false;
     //commandAllAgentsPublisher.publish(msg);
     emergencyStopPublisher.publish(msg);
+#endif
 }
 // > ENABLE SAFE CONTROLLER
 void MainGUIWindow::on_all_enable_safe_controller_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_SAFE_CONTROLLER;
-    commandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_USE_SAFE_CONTROLLER;
+//    commandAllAgentsPublisher.publish(msg);
 }
 // > ENABLE SAFE CONTROLLER
 void MainGUIWindow::on_all_enable_custom_controller_button_clicked()
 {
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_CUSTOM_CONTROLLER;
-    commandAllAgentsPublisher.publish(msg);
+//    std_msgs::Int32 msg;
+//    msg.data = CMD_USE_CUSTOM_CONTROLLER;
+//    commandAllAgentsPublisher.publish(msg);
 }
 // > LOAD THE YAML PARAMETERS FOR THE SAFE CONTROLLER
 void MainGUIWindow::on_all_load_safe_controller_yaml_own_agent_button_clicked()
 {
-	// Disable the button
-	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
-	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
-
-	// Send the message that the YAML paremters should be loaded
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_SAFE_CONTROLLER_AGENT;
-    requestLoadControllerYamlPublisher.publish(msg);
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
+//	// Disable the button
+//	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
+//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
+
+//	// Send the message that the YAML paremters should be loaded
+//    std_msgs::Int32 msg;
+//    msg.data = LOAD_YAML_SAFE_CONTROLLER_AGENT;
+//    requestLoadControllerYamlPublisher.publish(msg);
+
+//    // Start a timer which will enable the button in its callback
+//    // > This is required because the agent node waits some time between
+//    //   re-loading the values from the YAML file and then assigning then
+//    //   to the local variable of the agent.
+//    // > Thus we use this timer to prevent the user from clicking the
+//    //   button in the GUI repeatedly.
+//    ros::NodeHandle nodeHandle("~");
+//    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
 }
 // > LOAD THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER
 void MainGUIWindow::on_all_load_custom_controller_yaml_own_agent_button_clicked()
 {
-	// Disable the button
-	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
-	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
-
-	// Send the message that the YAML paremters should be loaded
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_AGENT;
-    requestLoadControllerYamlPublisher.publish(msg);
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
+//	// Disable the button
+//	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
+//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
+
+//	// Send the message that the YAML paremters should be loaded
+//    std_msgs::Int32 msg;
+//    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_AGENT;
+//    requestLoadControllerYamlPublisher.publish(msg);
+
+//    // Start a timer which will enable the button in its callback
+//    // > This is required because the agent node waits some time between
+//    //   re-loading the values from the YAML file and then assigning then
+//    //   to the local variable of the agent.
+//    // > Thus we use this timer to prevent the user from clicking the
+//    //   button in the GUI repeatedly.
+//    ros::NodeHandle nodeHandle("~");
+//    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
 
 }
 // > SEND THE YAML PARAMETERS FOR THE SAFE CONTROLLER
 void MainGUIWindow::on_all_load_safe_controller_yaml_coordinator_button_clicked()
 {
-	// Disable the button
-	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
-	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
-
-	// Send the message that the YAML paremters should be loaded
-    // by the coordinator (and then the agent informed)
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_SAFE_CONTROLLER_COORDINATOR;
-    requestLoadControllerYamlPublisher.publish(msg);
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
+//	// Disable the button
+//	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
+//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
+
+//	// Send the message that the YAML paremters should be loaded
+//    // by the coordinator (and then the agent informed)
+//    std_msgs::Int32 msg;
+//    msg.data = LOAD_YAML_SAFE_CONTROLLER_COORDINATOR;
+//    requestLoadControllerYamlPublisher.publish(msg);
+
+//    // Start a timer which will enable the button in its callback
+//    // > This is required because the agent node waits some time between
+//    //   re-loading the values from the YAML file and then assigning then
+//    //   to the local variable of the agent.
+//    // > Thus we use this timer to prevent the user from clicking the
+//    //   button in the GUI repeatedly.
+//    ros::NodeHandle nodeHandle("~");
+//    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
 }
 // > SEND THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER
 void MainGUIWindow::on_all_load_custom_controller_yaml_coordinator_button_clicked()
 {
-	// Disable the button
-	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
-	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
-
-    // Send the message that the YAML paremters should be loaded
-    // by the coordinator (and then the agent informed)
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR;
-    requestLoadControllerYamlPublisher.publish(msg);
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
+//	// Disable the button
+//	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
+//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
+
+//    // Send the message that the YAML paremters should be loaded
+//    // by the coordinator (and then the agent informed)
+//    std_msgs::Int32 msg;
+//    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR;
+//    requestLoadControllerYamlPublisher.publish(msg);
+
+//    // Start a timer which will enable the button in its callback
+//    // > This is required because the agent node waits some time between
+//    //   re-loading the values from the YAML file and then assigning then
+//    //   to the local variable of the agent.
+//    // > Thus we use this timer to prevent the user from clicking the
+//    //   button in the GUI repeatedly.
+//    ros::NodeHandle nodeHandle("~");
+//    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
 
 }
+
+#ifdef CATKIN_MAKE
 // > CALLBACK TO RE-ENABLE THE SAFE CONTROLLER YAML BUTTONS
 void MainGUIWindow::safeYamlFileTimerCallback(const ros::TimerEvent&)
 {
-    // Enble the "load" and the "send" safe controller YAML button again
-    ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(true);
-	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(true);
+//    // Enble the "load" and the "send" safe controller YAML button again
+//    ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(true);
+//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(true);
 }
 // > CALLBACK TO RE-ENABLE THE CUSTOM CONTROLLER YAML BUTTONS
 void MainGUIWindow::customYamlFileTimerCallback(const ros::TimerEvent&)
 {
-    // Enble the "load" and the "send" custom controller YAML button again
-    ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(true);
-	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(true);
+//    // Enble the "load" and the "send" custom controller YAML button again
+//    ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(true);
+//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(true);
 }
+#endif
 
 /*
 // > CALLBACK TO SEND THE CUSTOM CONTROLLER YAML PARAMETERS AS A MESSAGE
@@ -1312,6 +1339,9 @@ void MainGUIWindow::customSendYamlAsMessageTimerCallback(const ros::TimerEvent&)
 //    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
 //    ----------------------------------------------------------------------------------
 
+
+#ifdef CATKIN_MAKE
+
 // load parameters from corresponding YAML file
 //
 float MainGUIWindow::getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
@@ -1371,3 +1401,5 @@ bool MainGUIWindow::getParameterBool(ros::NodeHandle& nodeHandle, std::string na
     }
     return val;
 }
+
+#endif
-- 
GitLab


From 908b8212d8fb427daca24bd009e7080e9b39a966 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 11:44:54 +0100
Subject: [PATCH 60/87] Removed the command all buttons from the System Config
 GUI. Also removed the get yaml paramters functions and pointed to the overall
 class. Needs to be tested for ROS compilation

---
 .../GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro        |   4 +-
 .../GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui | 379 +++---------------
 .../include/constants_for_qt_compile.h        | 286 +++++++++++++
 .../CrazyFlyGUI/include/globalDefinitions.h   |   5 -
 .../CrazyFlyGUI/include/mainguiwindow.h       |  82 +---
 .../GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp       |   2 +-
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  | 339 +---------------
 7 files changed, 373 insertions(+), 724 deletions(-)
 create mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
index 61aa744e..0175414f 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
@@ -45,7 +45,9 @@ HEADERS  += \
     include/tablePiece.h \
     include/globalDefinitions.h \
     include/marker.h \
-    include/crazyFly.h
+    include/crazyFly.h \
+    \
+    include/constants_for_qt_compile.h
 
 FORMS    += \
     forms/mainguiwindow.ui
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
index 737f460b..2d50c2a9 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
@@ -6,7 +6,7 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1176</width>
+    <width>1228</width>
     <height>1559</height>
    </rect>
   </property>
@@ -273,7 +273,7 @@
       </property>
       <layout class="QVBoxLayout" name="verticalLayout_2">
        <item>
-        <widget class="QPushButton" name="all_motors_off_button">
+        <widget class="QPushButton" name="emergency_stop_button">
          <property name="sizePolicy">
           <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -300,7 +300,7 @@
           </font>
          </property>
          <property name="text">
-          <string>All motors OFF</string>
+          <string>Emergency Stop</string>
          </property>
         </widget>
        </item>
@@ -870,329 +870,56 @@
          </widget>
          <widget class="QWidget" name="tab">
           <attribute name="title">
-           <string>Command all</string>
+           <string>Mocap</string>
           </attribute>
           <layout class="QGridLayout" name="gridLayout_2">
-           <item row="10" column="1">
-            <widget class="QPushButton" name="all_load_custom_controller_yaml_coordinator_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Load Custom YAML</string>
-             </property>
-            </widget>
-           </item>
-           <item row="6" column="0" colspan="2">
-            <widget class="QLabel" name="all_yaml_label">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>20</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>40</height>
-              </size>
-             </property>
-             <property name="font">
-              <font>
-               <weight>75</weight>
-               <bold>true</bold>
-              </font>
-             </property>
-             <property name="text">
-              <string>LOAD YAML PARAMETERS</string>
-             </property>
-             <property name="alignment">
-              <set>Qt::AlignBottom|Qt::AlignHCenter</set>
-             </property>
-            </widget>
-           </item>
-           <item row="3" column="0">
-            <widget class="QPushButton" name="all_take_off_button">
-             <property name="sizePolicy">
-              <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-               <horstretch>0</horstretch>
-               <verstretch>0</verstretch>
-              </sizepolicy>
-             </property>
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Take off</string>
-             </property>
-            </widget>
-           </item>
-           <item row="1" column="1">
-            <widget class="QPushButton" name="all_connect_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Reconnect</string>
-             </property>
-            </widget>
-           </item>
-           <item row="2" column="0" colspan="2">
-            <widget class="QLabel" name="all_flying_state_label">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>20</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>40</height>
-              </size>
-             </property>
-             <property name="font">
-              <font>
-               <weight>75</weight>
-               <bold>true</bold>
-              </font>
-             </property>
-             <property name="text">
-              <string>FLYING STATE</string>
-             </property>
-             <property name="alignment">
-              <set>Qt::AlignBottom|Qt::AlignHCenter</set>
-             </property>
-            </widget>
-           </item>
-           <item row="5" column="0">
-            <widget class="QPushButton" name="all_enable_safe_controller_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Enable Safe</string>
-             </property>
-            </widget>
-           </item>
-           <item row="8" column="1">
-            <widget class="QPushButton" name="all_load_custom_controller_yaml_own_agent_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Load Custom YAML</string>
-             </property>
-            </widget>
-           </item>
-           <item row="1" column="0">
-            <widget class="QPushButton" name="all_disconnect_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Disconnect</string>
-             </property>
-            </widget>
-           </item>
-           <item row="5" column="1">
-            <widget class="QPushButton" name="all_enable_custom_controller_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Enable Custom</string>
-             </property>
-            </widget>
-           </item>
-           <item row="3" column="1">
-            <widget class="QPushButton" name="all_land_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Land</string>
-             </property>
-            </widget>
-           </item>
-           <item row="8" column="0">
-            <widget class="QPushButton" name="all_load_safe_controller_yaml_own_agent_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Load Safe YAML</string>
-             </property>
-            </widget>
-           </item>
-           <item row="7" column="0" colspan="2">
-            <widget class="QLabel" name="all_yaml_agent_label">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>&gt; From agenet's local file</string>
-             </property>
-            </widget>
-           </item>
-           <item row="10" column="0">
-            <widget class="QPushButton" name="all_load_safe_controller_yaml_coordinator_button">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>50</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>Load Safe YAML</string>
-             </property>
-            </widget>
-           </item>
-           <item row="9" column="0" colspan="2">
-            <widget class="QLabel" name="all_yaml_coordinator_label">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>30</height>
-              </size>
-             </property>
-             <property name="text">
-              <string>&gt; From coordinator's file</string>
-             </property>
-            </widget>
-           </item>
-           <item row="0" column="0" colspan="2">
-            <widget class="QLabel" name="all_radio_label">
-             <property name="minimumSize">
-              <size>
-               <width>0</width>
-               <height>20</height>
-              </size>
-             </property>
-             <property name="maximumSize">
-              <size>
-               <width>16777215</width>
-               <height>40</height>
-              </size>
-             </property>
-             <property name="font">
-              <font>
-               <weight>75</weight>
-               <bold>true</bold>
-              </font>
-             </property>
-             <property name="lineWidth">
-              <number>1</number>
-             </property>
-             <property name="text">
-              <string>CRAZYRADIO</string>
-             </property>
-             <property name="alignment">
-              <set>Qt::AlignBottom|Qt::AlignHCenter</set>
-             </property>
-            </widget>
+           <item row="0" column="0">
+            <layout class="QGridLayout" name="gridLayout_6">
+             <item row="0" column="0">
+              <widget class="QLabel" name="all_radio_label">
+               <property name="minimumSize">
+                <size>
+                 <width>0</width>
+                 <height>20</height>
+                </size>
+               </property>
+               <property name="maximumSize">
+                <size>
+                 <width>16777215</width>
+                 <height>40</height>
+                </size>
+               </property>
+               <property name="font">
+                <font>
+                 <weight>75</weight>
+                 <bold>true</bold>
+                </font>
+               </property>
+               <property name="lineWidth">
+                <number>1</number>
+               </property>
+               <property name="text">
+                <string>Work in progress.</string>
+               </property>
+               <property name="alignment">
+                <set>Qt::AlignBottom|Qt::AlignHCenter</set>
+               </property>
+              </widget>
+             </item>
+             <item row="1" column="0">
+              <spacer name="verticalSpacer">
+               <property name="orientation">
+                <enum>Qt::Vertical</enum>
+               </property>
+               <property name="sizeHint" stdset="0">
+                <size>
+                 <width>20</width>
+                 <height>40</height>
+                </size>
+               </property>
+              </spacer>
+             </item>
+            </layout>
            </item>
           </layout>
          </widget>
@@ -1245,8 +972,8 @@
     <rect>
      <x>0</x>
      <y>0</y>
-     <width>1176</width>
-     <height>25</height>
+     <width>1228</width>
+     <height>40</height>
     </rect>
    </property>
   </widget>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h
new file mode 100644
index 00000000..b361da05
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h
@@ -0,0 +1,286 @@
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    Constants that are used across multiple files
+//
+//    ----------------------------------------------------------------------------------
+
+
+//    ----------------------------------------------------------------------------------
+//    U   U
+//    U   U
+//    U   U
+//    U   U
+//     UUU
+//    ----------------------------------------------------------------------------------
+
+
+// Conversions between degrees and radians
+#define RAD2DEG 180.0/PI
+#define DEG2RAD PI/180.0
+
+// PI
+#define PI 3.141592653589
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+
+
+// The types, i.e., agent or coordinator
+#define TYPE_INVALID      -1
+#define TYPE_COORDINATOR   1
+#define TYPE_AGENT         2
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+
+
+// 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
+
+// Types of controllers being used:
+#define SAFE_CONTROLLER      1
+#define DEMO_CONTROLLER      2
+#define STUDENT_CONTROLLER   3
+#define MPC_CONTROLLER       4
+#define REMOTE_CONTROLLER    5
+#define TUNING_CONTROLLER    6
+#define PICKER_CONTROLLER    7
+
+// The constants that "command" changes in the
+// operation state of this agent
+#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEMO_CONTROLLER      2
+#define CMD_USE_STUDENT_CONTROLLER   3
+#define CMD_USE_MPC_CONTROLLER       4
+#define CMD_USE_REMOTE_CONTROLLER    5
+#define CMD_USE_TUNING_CONTROLLER    6
+#define CMD_USE_PICKER_CONTROLLER    7
+
+
+#define CMD_CRAZYFLY_TAKE_OFF        11
+#define CMD_CRAZYFLY_LAND            12
+#define CMD_CRAZYFLY_MOTORS_OFF      13
+
+// Flying states
+#define STATE_MOTORS_OFF     1
+#define STATE_TAKE_OFF       2
+#define STATE_FLYING         3
+#define STATE_LAND           4
+#define STATE_UNAVAILABLE    5
+
+
+// Commands for CrazyRadio
+#define CMD_RECONNECT  0
+#define CMD_DISCONNECT 1
+
+
+// CrazyRadio states:
+#define CRAZY_RADIO_STATE_CONNECTED      0
+#define CRAZY_RADIO_STATE_CONNECTING     1
+#define CRAZY_RADIO_STATE_DISCONNECTED   2
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
+//    B   B   A A     T      T    E      R   R   Y Y
+//    BBBB   A   A    T      T    EEE    RRRR     Y
+//    B   B  AAAAA    T      T    E      R   R    Y
+//    BBBB   A   A    T      T    EEEEE  R   R    Y
+//    ----------------------------------------------------------------------------------
+
+// Battery levels
+#define BATTERY_LEVEL_000            0
+#define BATTERY_LEVEL_010            1
+#define BATTERY_LEVEL_020            2
+#define BATTERY_LEVEL_030            3
+#define BATTERY_LEVEL_040            4
+#define BATTERY_LEVEL_050            5
+#define BATTERY_LEVEL_060            6
+#define BATTERY_LEVEL_070            7
+#define BATTERY_LEVEL_080            8
+#define BATTERY_LEVEL_090            9
+#define BATTERY_LEVEL_100           10
+#define BATTERY_LEVEL_UNAVAILABLE   -1
+
+// Battery states
+#define BATTERY_STATE_NORMAL         0
+#define BATTERY_STATE_LOW            1
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    Y   Y    A    M   M  L
+//     Y Y    A A   MM MM  L
+//      Y    A   A  M M M  L
+//      Y    AAAAA  M   M  L
+//      Y    A   A  M   M  LLLLL
+//    ----------------------------------------------------------------------------------
+
+// For where to load the yaml file from
+#define LOAD_YAML_FROM_AGENT             1
+#define LOAD_YAML_FROM_COORDINATOR       2
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    
+//    
+//    
+//    
+//    
+//    ----------------------------------------------------------------------------------
+
+// For standard buttons in the GUI
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// OLD STUFF FOR LOADING YAML FILES
+// For which controller parameters to load from file
+#define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
+#define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
+#define LOAD_YAML_STUDENT_CONTROLLER_AGENT          3
+#define LOAD_YAML_MPC_CONTROLLER_AGENT              4
+#define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
+#define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
+#define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
+
+#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
+#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
+#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR    13
+#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR        14
+#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
+#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
+#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
+
+
+// For sending commands to the controller node informing
+// which parameters to fetch
+// > NOTE: these are identical to the #defines above, but
+//         used because they have the name distinguishes
+//         between:
+//         - "loading" a yaml file into ram
+//         - "fetching" the values that were loaded into ram
+#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT      1
+#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
+#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT   3
+#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT       4
+#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
+#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
+#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
+
+#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
+#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
+#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR   13
+#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
+#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
+#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
+#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
index c25a843d..2a85b0fc 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
@@ -41,9 +41,4 @@
 #define FROM_CENTIMETERS_TO_UNITS            1
 #define FROM_MILIMETERS_TO_UNITS             0.1
 
-#define PI                                   3.1415926
-
-#define FROM_RADIANS_TO_DEGREES            180.0/PI
-#define FROM_DEGREES_TO_RADIANS            PI/180.0
-
 #endif
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
index e0f696cc..e9fa1320 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
@@ -58,28 +58,19 @@
 #include "dfall_pkg/CrazyflieDB.h"
 #include "dfall_pkg/CrazyflieEntry.h"
 
+// Include the shared definitions
+#include "nodes/Constants.h"
 
-// The constants that are sent to the agents in order to
-// "command" changes in their operation state
-#define CMD_USE_SAFE_CONTROLLER   1
-#define CMD_USE_CUSTOM_CONTROLLER 2
-#define CMD_CRAZYFLY_TAKE_OFF     3
-#define CMD_CRAZYFLY_LAND         4
-#define CMD_CRAZYFLY_MOTORS_OFF   5
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
 
-// The constants that are sent to the agents in order to
-// adjust their radio connection
-#define CMD_RECONNECT  0
-#define CMD_DISCONNECT 1
 
-// For which controller parameters to load
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT          1
-#define LOAD_YAML_CUSTOM_CONTROLLER_AGENT        2
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR    3
-#define LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR  4
+using namespace dfall_pkg;
 
 
-using namespace dfall_pkg;
+#else
+// Include the shared definitions
+#include "include/constants_for_qt_compile.h"
 
 #endif
 
@@ -171,12 +162,14 @@ private slots:
 
     void on_load_from_DB_button_clicked();
 
-    #ifdef CATKIN_MAKE
+#ifdef CATKIN_MAKE
     void updateNewViconData(const ptrToMessage& p_msg);
-    #endif
+#endif
+
     void on_checkBox_vicon_crazyflies_toggled(bool checked);
 
     void on_scaleSpinBox_valueChanged(double arg1);
+
     void on_refresh_cfs_button_clicked();
 
     void on_refresh_student_ids_button_clicked();
@@ -188,27 +181,13 @@ private slots:
     void updateComboBoxes();
 
     void setTabIndex(int index);
+
     void doTabClosed(int tab_index);
 
     void on_comboBoxCFs_currentTextChanged(const QString &arg1);
-
     
-    // For the buttons that "command" all of the agent nodes
-    // > For the radio connection
-    void on_all_connect_button_clicked();
-    void on_all_disconnect_button_clicked();
-    // > For changing the operation state
-    void on_all_take_off_button_clicked();
-    void on_all_land_button_clicked();
-    void on_all_motors_off_button_clicked();
-    void on_all_enable_safe_controller_button_clicked();
-    void on_all_enable_custom_controller_button_clicked();
-    // > For loading the parameter
-    void on_all_load_safe_controller_yaml_own_agent_button_clicked();
-    void on_all_load_custom_controller_yaml_own_agent_button_clicked();
-    // > For sending a message with updated parameters
-    void on_all_load_safe_controller_yaml_coordinator_button_clicked();
-    void on_all_load_custom_controller_yaml_coordinator_button_clicked();
+    // For the emergency stop button
+    void on_emergency_stop_button_clicked();
     
 
 private:
@@ -219,14 +198,6 @@ private:
     void _init();
 
 #ifdef CATKIN_MAKE
-    ros::Timer m_timer_yaml_file_for_safe_controller;
-    ros::Timer m_timer_yaml_file_for_custom_controller;
-
-    void safeYamlFileTimerCallback(const ros::TimerEvent&);
-    void customYamlFileTimerCallback(const ros::TimerEvent&);
-
-    void customSendYamlAsMessageTimerCallback(const ros::TimerEvent&);
-    
     float getParameterFloat(ros::NodeHandle& nodeHandle, std::string name);
     void getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length);
     int getParameterInt(ros::NodeHandle& nodeHandle, std::string name);
@@ -236,7 +207,7 @@ private:
 #endif
 
 
-    #ifdef CATKIN_MAKE
+#ifdef CATKIN_MAKE
     rosNodeThread* _rosNodeThread;
     std::vector<Marker*> markers_vector;
     std::vector<crazyFly*> crazyflies_vector;
@@ -246,26 +217,7 @@ private:
 
     //ros::Publisher DBChangedPublisher;
     ros::Publisher emergencyStopPublisher;
-
-    // Publsher for sending "commands" from here (the master) to all
-    // of the agent nodes (where a "command" is the integer that
-    // gives the directive to "take-off", "land, "motors-off", etc...)
-    ros::Publisher commandAllAgentsPublisher;
-
-    // Publisher for sending a request from here (the master) to all "Parameter Service" nodes
-    // that it should re-load parameters from the YAML file for the controllers.
-    // > This is recieved and acted on by both Coordinate and Agent type "Parameter Services",
-    // > A coordinator type "Parameter Service" will subsequently request the agents to fetch
-    //   the parameters from itself.
-    // > A agent type "Parameter Service" will subsequently request its own agent to fetch
-    //   the parameters from itself.
-    ros::Publisher requestLoadControllerYamlPublisher;
-
-    // Publisher for sending a request from here (the master) to all
-    // of the agents nodes that they should (re/dis)-connect from
-    // the Crazy-Radio
-    ros::Publisher crazyRadioCommandAllAgentsPublisher;
-    #endif
+#endif
 
     void updateComboBoxesCFs();
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
index d83ccd4e..8d40b6eb 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
@@ -88,7 +88,7 @@ void crazyFly::updateCF(const CrazyflieData* p_crazyfly_msg)
 
 
         this->setPos(m_x * FROM_METERS_TO_UNITS, -m_y * FROM_METERS_TO_UNITS);    // - y because of coordinates
-        this->setRotation(- m_yaw * FROM_RADIANS_TO_DEGREES); //negative beacause anti-clock wise should be positive
+        this->setRotation(- m_yaw * RAD2DEG); //negative beacause anti-clock wise should be positive
     }
 }
 
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 1fb3cf4a..3b495f9f 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
@@ -260,7 +260,7 @@ void MainGUIWindow::_init()
 
     // Add keyboard shortcuts
     // > for "all motors off", press the space bar
-    ui->all_motors_off_button->setShortcut(tr("Space"));
+    ui->emergency_stop_button->setShortcut(tr("Space"));
     // > for "kill GUI node", press "CTRL+C" while the GUI window is the focus
     QShortcut* close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close()));
 
@@ -280,24 +280,6 @@ void MainGUIWindow::_init()
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
     ros::NodeHandle nodeHandle_dfall_root("/dfall");
     emergencyStopPublisher = nodeHandle_dfall_root.advertise<dfall_pkg::IntWithHeader>("emergencyStop", 1);
-
-    // Initialise the publisher for sending "commands" from here (the master)
-    // to all of the agent nodes
-    commandAllAgentsPublisher = nodeHandle.advertise<std_msgs::Int32>("commandAllAgents", 1);
-
-    // Publisher for sending a request from here (the master) to all "Parameter Service" nodes
-    // that it should re-load parameters from the YAML file for the controllers.
-    // > This is recieved and acted on by both Coordinate and Agent type "Parameter Services",
-    // > A coordinator type "Parameter Service" will subsequently request the agents to fetch
-    //   the parameters from itself.
-    // > A agent type "Parameter Service" will subsequently request its own agent to fetch
-    //   the parameters from itself.
-    requestLoadControllerYamlPublisher = nodeHandle.advertise<std_msgs::Int32>("requestLoadControllerYaml", 1);
-    
-    // Initialise the publisher for sending a request from here (the master)
-    // to all of the agents nodes that they should (re/dis)-connect from
-    // the Crazy-Radio
-    crazyRadioCommandAllAgentsPublisher = nodeHandle.advertise<std_msgs::Int32>("crazyRadioCommandAllAgents", 1);
 #endif
 }
 
@@ -1084,322 +1066,27 @@ void MainGUIWindow::on_comboBoxCFs_currentTextChanged(const QString &arg1)
 
 
 //    ----------------------------------------------------------------------------------
-//     CCCC   OOO   M   M  M   M    A    N   N  DDDD          A    L      L
-//    C      O   O  MM MM  MM MM   A A   NN  N  D   D        A A   L      L
-//    C      O   O  M M M  M M M  A   A  N N N  D   D       A   A  L      L
-//    C      O   O  M   M  M   M  AAAAA  N  NN  D   D       AAAAA  L      L
-//     CCCC   OOO   M   M  M   M  A   A  N   N  DDDD        A   A  LLLLL  LLLLL
+//    EEEEE  M   M  EEEEE  RRRR    GGGG  EEEEE  N   N   CCCC  Y   Y
+//    E      MM MM  E      R   R  G      E      NN  N  C       Y Y
+//    EEE    M M M  EEE    RRRR   G  GG  EEE    N N N  C        Y
+//    E      M   M  E      R   R  G   G  E      N  NN  C        Y
+//    EEEEE  M   M  EEEEE  R   R   GGG   EEEEE  N   N   CCCC    Y
 //
-//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
-//    B   B  U   U    T      T    O   O  NN  N  S
-//    BBBB   U   U    T      T    O   O  N N N   SSS
-//    B   B  U   U    T      T    O   O  N  NN      S
-//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//     SSSS  TTTTT   OOO   PPPP
+//    S        T    O   O  P   P
+//     SSS     T    O   O  PPPP
+//        S    T    O   O  P
+//    SSSS     T     OOO   P
 //    ----------------------------------------------------------------------------------
 
 
-// For the buttons that commands all of the agent nodes to:
-// > (RE)CONNECT THE RADIO
-void MainGUIWindow::on_all_connect_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_RECONNECT;
-//    crazyRadioCommandAllAgentsPublisher.publish(msg);
-}
-// > DISCONNECT THE RADIO
-void MainGUIWindow::on_all_disconnect_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_DISCONNECT;
-//    crazyRadioCommandAllAgentsPublisher.publish(msg);
-}
-// > TAKE-OFF
-void MainGUIWindow::on_all_take_off_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_CRAZYFLY_TAKE_OFF;
-//    commandAllAgentsPublisher.publish(msg);
-}
-// > LAND
-void MainGUIWindow::on_all_land_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_CRAZYFLY_LAND;
-//    commandAllAgentsPublisher.publish(msg);
-}
-// > MOTORS OFF
-void MainGUIWindow::on_all_motors_off_button_clicked()
+// > EMERGENCY STOP
+void MainGUIWindow::on_emergency_stop_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     msg.data = CMD_CRAZYFLY_MOTORS_OFF;
     msg.shouldCheckForAgentID = false;
-    //commandAllAgentsPublisher.publish(msg);
     emergencyStopPublisher.publish(msg);
 #endif
 }
-// > ENABLE SAFE CONTROLLER
-void MainGUIWindow::on_all_enable_safe_controller_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_USE_SAFE_CONTROLLER;
-//    commandAllAgentsPublisher.publish(msg);
-}
-// > ENABLE SAFE CONTROLLER
-void MainGUIWindow::on_all_enable_custom_controller_button_clicked()
-{
-//    std_msgs::Int32 msg;
-//    msg.data = CMD_USE_CUSTOM_CONTROLLER;
-//    commandAllAgentsPublisher.publish(msg);
-}
-// > LOAD THE YAML PARAMETERS FOR THE SAFE CONTROLLER
-void MainGUIWindow::on_all_load_safe_controller_yaml_own_agent_button_clicked()
-{
-//	// Disable the button
-//	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
-//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
-
-//	// Send the message that the YAML paremters should be loaded
-//    std_msgs::Int32 msg;
-//    msg.data = LOAD_YAML_SAFE_CONTROLLER_AGENT;
-//    requestLoadControllerYamlPublisher.publish(msg);
-
-//    // Start a timer which will enable the button in its callback
-//    // > This is required because the agent node waits some time between
-//    //   re-loading the values from the YAML file and then assigning then
-//    //   to the local variable of the agent.
-//    // > Thus we use this timer to prevent the user from clicking the
-//    //   button in the GUI repeatedly.
-//    ros::NodeHandle nodeHandle("~");
-//    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
-}
-// > LOAD THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER
-void MainGUIWindow::on_all_load_custom_controller_yaml_own_agent_button_clicked()
-{
-//	// Disable the button
-//	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
-//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
-
-//	// Send the message that the YAML paremters should be loaded
-//    std_msgs::Int32 msg;
-//    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_AGENT;
-//    requestLoadControllerYamlPublisher.publish(msg);
-
-//    // Start a timer which will enable the button in its callback
-//    // > This is required because the agent node waits some time between
-//    //   re-loading the values from the YAML file and then assigning then
-//    //   to the local variable of the agent.
-//    // > Thus we use this timer to prevent the user from clicking the
-//    //   button in the GUI repeatedly.
-//    ros::NodeHandle nodeHandle("~");
-//    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
-
-}
-// > SEND THE YAML PARAMETERS FOR THE SAFE CONTROLLER
-void MainGUIWindow::on_all_load_safe_controller_yaml_coordinator_button_clicked()
-{
-//	// Disable the button
-//	ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(false);
-//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(false);
-
-//	// Send the message that the YAML paremters should be loaded
-//    // by the coordinator (and then the agent informed)
-//    std_msgs::Int32 msg;
-//    msg.data = LOAD_YAML_SAFE_CONTROLLER_COORDINATOR;
-//    requestLoadControllerYamlPublisher.publish(msg);
-
-//    // Start a timer which will enable the button in its callback
-//    // > This is required because the agent node waits some time between
-//    //   re-loading the values from the YAML file and then assigning then
-//    //   to the local variable of the agent.
-//    // > Thus we use this timer to prevent the user from clicking the
-//    //   button in the GUI repeatedly.
-//    ros::NodeHandle nodeHandle("~");
-//    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::safeYamlFileTimerCallback, this, true);
-}
-// > SEND THE YAML PARAMETERS FOR THE CUSTOM CONTROLLER
-void MainGUIWindow::on_all_load_custom_controller_yaml_coordinator_button_clicked()
-{
-//	// Disable the button
-//	ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(false);
-//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(false);
-
-//    // Send the message that the YAML paremters should be loaded
-//    // by the coordinator (and then the agent informed)
-//    std_msgs::Int32 msg;
-//    msg.data = LOAD_YAML_CUSTOM_CONTROLLER_COORDINATOR;
-//    requestLoadControllerYamlPublisher.publish(msg);
-
-//    // Start a timer which will enable the button in its callback
-//    // > This is required because the agent node waits some time between
-//    //   re-loading the values from the YAML file and then assigning then
-//    //   to the local variable of the agent.
-//    // > Thus we use this timer to prevent the user from clicking the
-//    //   button in the GUI repeatedly.
-//    ros::NodeHandle nodeHandle("~");
-//    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
-
-}
-
-#ifdef CATKIN_MAKE
-// > CALLBACK TO RE-ENABLE THE SAFE CONTROLLER YAML BUTTONS
-void MainGUIWindow::safeYamlFileTimerCallback(const ros::TimerEvent&)
-{
-//    // Enble the "load" and the "send" safe controller YAML button again
-//    ui->all_load_safe_controller_yaml_own_agent_button->setEnabled(true);
-//	ui->all_load_safe_controller_yaml_coordinator_button->setEnabled(true);
-}
-// > CALLBACK TO RE-ENABLE THE CUSTOM CONTROLLER YAML BUTTONS
-void MainGUIWindow::customYamlFileTimerCallback(const ros::TimerEvent&)
-{
-//    // Enble the "load" and the "send" custom controller YAML button again
-//    ui->all_load_custom_controller_yaml_own_agent_button->setEnabled(true);
-//	ui->all_load_custom_controller_yaml_coordinator_button->setEnabled(true);
-}
-#endif
-
-/*
-// > CALLBACK TO SEND THE CUSTOM CONTROLLER YAML PARAMETERS AS A MESSAGE
-void MainGUIWindow::customSendYamlAsMessageTimerCallback(const ros::TimerEvent&)
-{
-	// Load the CUSTOM controller YAML parameters from file into a message for
-	// sending directly to the "CustonControllerService" node of every agent
-
-	ros::NodeHandle nodeHandle("~");
-
-	// Instaniate a local variable of the message type
-	CustomControllerYAML customControllerYamlMessage;
-
-	// Load the data directly from the YAML file into the message
-
-	// > For the mass
-	customControllerYamlMessage.mass = MainGUIWindow::getParameterFloat(nodeHandle, "mass");
-
-    // Debugging this this works
-    ROS_INFO_STREAM("DEBUGGING: mass loaded from the custom controller YAML = " << customControllerYamlMessage.mass );
-
-	// > For the control_frequency
-	customControllerYamlMessage.control_frequency = MainGUIWindow::getParameterFloat(nodeHandle, "control_frequency");
-
-	// > For the motorPoly coefficients
-    std::vector<float> temp_motorPoly(3);
-	MainGUIWindow::getParameterFloatVector(nodeHandle, "motorPoly", temp_motorPoly, 3);
-    // Copy the loaded data into the message
-    for ( int i=0 ; i<3 ; i++ )
-    {
-        customControllerYamlMessage.motorPoly.push_back( temp_motorPoly[i] );
-    }
-
-    // > For the boolean about whether to execute the convert into body frame function
-    customControllerYamlMessage.shouldPerformConvertIntoBodyFrame = MainGUIWindow::getParameterBool(nodeHandle, "shouldPerformConvertIntoBodyFrame");
-
-    // > For the boolean about publishing the agents current position
-	customControllerYamlMessage.shouldPublishCurrent_xyz_yaw = MainGUIWindow::getParameterBool(nodeHandle, "shouldPublishCurrent_xyz_yaw");
-
-	// > For the boolean about following another agent
-	customControllerYamlMessage.shouldFollowAnotherAgent = MainGUIWindow::getParameterBool(nodeHandle, "shouldFollowAnotherAgent");
-
-	// > For the ordered agent ID's for following eachother in a line
-    std::vector<int> temp_follow_in_a_line_agentIDs(100);
-	int temp_number_of_agents_in_a_line = MainGUIWindow::getParameterIntVectorWithUnknownLength(nodeHandle, "follow_in_a_line_agentIDs", temp_follow_in_a_line_agentIDs);
-	// > Double check that the sizes agree
-    if ( temp_number_of_agents_in_a_line != temp_follow_in_a_line_agentIDs.size() )
-    {
-    	// Update the user if the sizes don't agree
-    	ROS_ERROR_STREAM("parameter 'follow_in_a_line_agentIDs' was loaded with two different lengths, " << temp_number_of_agents_in_a_line << " versus " << temp_follow_in_a_line_agentIDs.size() );
-    }
-    // Copy the loaded data into the message
-    for ( int i=0 ; i<temp_number_of_agents_in_a_line ; i++ )
-    {
-        customControllerYamlMessage.follow_in_a_line_agentIDs.push_back( temp_follow_in_a_line_agentIDs[i] );
-    }    
-
-    // Publish the message containing the loaded YAML parameters
-    customYAMLasMessagePublisher.publish(customControllerYamlMessage);
-
-	// Start a timer which will enable the button in its callback
-    m_timer_yaml_file_for_custom_controller = nodeHandle.createTimer(ros::Duration(0.5), &MainGUIWindow::customYamlFileTimerCallback, this, true);
-}
-*/
-
-
-
-
-//    ----------------------------------------------------------------------------------
-//    L       OOO     A    DDDD        Y   Y    A    M   M  L
-//    L      O   O   A A   D   D        Y Y    A A   MM MM  L
-//    L      O   O  A   A  D   D         Y    A   A  M M M  L
-//    L      O   O  AAAAA  D   D         Y    AAAAA  M   M  L
-//    LLLLL   OOO   A   A  DDDD          Y    A   A  M   M  LLLLL
-//
-//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
-//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
-//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
-//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
-//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
-//    ----------------------------------------------------------------------------------
-
-
-#ifdef CATKIN_MAKE
-
-// load parameters from corresponding YAML file
-//
-float MainGUIWindow::getParameterFloat(ros::NodeHandle& nodeHandle, std::string name)
-{
-    float val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-
-void MainGUIWindow::getParameterFloatVector(ros::NodeHandle& nodeHandle, std::string name, std::vector<float>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
-    }
-}
-
-int MainGUIWindow::getParameterInt(ros::NodeHandle& nodeHandle, std::string name)
-{
-    int val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-
-void MainGUIWindow::getParameterIntVectorWithKnownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val, int length)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    if(val.size() != length) {
-        ROS_ERROR_STREAM("parameter '" << name << "' has wrong array length, " << length << " needed");
-    }
-}
-
-int MainGUIWindow::getParameterIntVectorWithUnknownLength(ros::NodeHandle& nodeHandle, std::string name, std::vector<int>& val)
-{
-    if(!nodeHandle.getParam(name, val)){
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val.size();
-}
-
-bool MainGUIWindow::getParameterBool(ros::NodeHandle& nodeHandle, std::string name)
-{
-    bool val;
-    if(!nodeHandle.getParam(name, val))
-    {
-        ROS_ERROR_STREAM("missing parameter '" << name << "'");
-    }
-    return val;
-}
-
-#endif
-- 
GitLab


From 7bbbb117832b4fdb9b69cecba0dc32cf71274d93 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 12:00:10 +0100
Subject: [PATCH 61/87] Small changes to header files to get ROS compilation
 working after removing the command all buttons

---
 .../dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h | 11 +++++++++++
 .../dfall_pkg/include/nodes/CentralManagerService.h | 13 -------------
 2 files changed, 11 insertions(+), 13 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
index 679f7303..fe7ec9b6 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
@@ -38,17 +38,28 @@
 #include <QGraphicsSvgItem>
 #include <QSvgRenderer>
 
+
 #ifdef CATKIN_MAKE
+// Include the Crazyflie Data Struct
 #include "dfall_pkg/CrazyflieData.h"
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+#else
+// Include the shared definitions
+#include "include/constants_for_qt_compile.h"
 #endif
 
+
+
 #ifdef CATKIN_MAKE
 using namespace dfall_pkg;
 #endif
 
+
 #define DRONE_HEIGHT         100 * FROM_MILIMETERS_TO_UNITS * 1.2
 #define DRONE_WIDTH          100 * FROM_MILIMETERS_TO_UNITS * 1.2
 
+
 class crazyFly : public QGraphicsSvgItem
 {
 public:
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h b/dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h
index 0c02248e..5079edfe 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/CentralManagerService.h
@@ -82,19 +82,6 @@
 #define ENTRY_INSERT_OR_UPDATE  1
 #define ENTRY_REMOVE            2
 
-// For which controller parameters to load
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT          1
-#define LOAD_YAML_DEMO_CONTROLLER_AGENT        2
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR    3
-#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR  4
-
-// For which controller parameters and from where to fetch
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT        1
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      3
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR    4
-
-
 using namespace dfall_pkg;
 using namespace std;
 
-- 
GitLab


From 1181582691cc6d4886fcafb1940ca5be338d5da0 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 12:50:03 +0100
Subject: [PATCH 62/87] Changed name of my_GUI (aka. CrazyFlyGUI) to
 SystemConfigGUI

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         | 83 +++++++++----------
 .../{CrazyFlyGUI.pro => SystemConfigGUI.pro}  |  4 +-
 .../{CrazyFlyGUI.qrc => SystemConfigGUI.qrc}  |  0
 .../GUI_Qt/CrazyFlyGUI/include/CFLinker.h     |  2 +-
 .../CrazyFlyGUI/include/mainguiwindow.h       |  2 +-
 ....h => rosNodeThread_for_systemConfigGUI.h} |  4 +-
 .../GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp  |  4 +-
 ... => rosNodeThread_for_systemConfigGUI.cpp} |  6 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  3 +-
 .../src/rosNodeThread_for_flyingAgentGUI.cpp  |  4 +-
 dfall_ws/src/dfall_pkg/launch/Agent.launch    |  4 +-
 .../src/dfall_pkg/launch/Coordinator.launch   |  4 +-
 12 files changed, 60 insertions(+), 60 deletions(-)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/{CrazyFlyGUI.pro => SystemConfigGUI.pro} (95%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/{CrazyFlyGUI.qrc => SystemConfigGUI.qrc} (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/{rosNodeThread_for_managerGUI.h => rosNodeThread_for_systemConfigGUI.h} (96%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/{rosNodeThread_for_managerGUI.cpp => rosNodeThread_for_systemConfigGUI.cpp} (95%)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index 9071a97a..6df6018d 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -57,10 +57,10 @@ find_package(Qt5Svg REQUIRED)
 
 
 # GUI -- Add src, includes, and resources
-set(MY_GUI_LIB_PATH_SRC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/src)
-set(MY_GUI_LIB_PATH_INC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/include)
-set(MY_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/forms)
-set(MY_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_SRC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/src)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_INC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/include)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/forms)
+set(SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc)
 
 
 
@@ -92,18 +92,18 @@ add_definitions(-std=c++11)
 # GUI -- Special Qt sources that need to be wrapped before being compiled
 # they have the Qt macro QOBJECT inside, the MOC cpp file needs to be done manually
 set(SRC_HDRS_QOBJECT_GUI
-  ${MY_GUI_LIB_PATH_INC}/crazyFlyZoneTab.h
-  ${MY_GUI_LIB_PATH_INC}/myGraphicsScene.h
-  ${MY_GUI_LIB_PATH_INC}/myGraphicsView.h
-  ${MY_GUI_LIB_PATH_INC}/mainguiwindow.h
-  ${MY_GUI_LIB_PATH_INC}/rosNodeThread_for_managerGUI.h
-  ${MY_GUI_LIB_PATH_INC}/CFLinker.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/crazyFlyZoneTab.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/myGraphicsScene.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/myGraphicsView.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/mainguiwindow.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/rosNodeThread_for_systemConfigGUI.h
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}/CFLinker.h
   )
 # GUI -- wrap UI file and QOBJECT files
-qt5_wrap_ui(UIS_HDRS_GUI ${MY_GUI_LIB_PATH_FORMS}/mainguiwindow.ui)
+qt5_wrap_ui(UIS_HDRS_GUI ${SYSTEM_CONFIG_GUI_LIB_PATH_FORMS}/mainguiwindow.ui)
 qt5_wrap_cpp(SRC_MOC_HDRS_GUI ${SRC_HDRS_QOBJECT_GUI})
 # GUI -- wrap resource file qrc->rcc
-qt5_add_resources(MY_RESOURCE_FILE_RCC ${MY_RESOURCE_FILE_QRC})
+qt5_add_resources(SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC})
 
 
 
@@ -285,7 +285,7 @@ generate_messages(
 ## CATKIN_DEPENDS: catkin_packages dependent projects also need
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
-  INCLUDE_DIRS include ${MY_GUI_LIB_PATH_INC}            # GUI -- include headers from GUI in package
+  INCLUDE_DIRS include ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}            # GUI -- include headers from GUI in package
   INCLUDE_DIRS include ${STUDENT_GUI_LIB_PATH_INC}       # StudentGUI -- include headers from GUI in package
   INCLUDE_DIRS include ${FLYING_AGENT_GUI_LIB_PATH_INC}  # FlyingAgentGUI -- include headers from GUI in package
   LIBRARIES
@@ -301,7 +301,7 @@ catkin_package(
 ## Your package locations should be listed before other locations
 # include_directories(include)
 include_directories(
-  ${MY_GUI_LIB_PATH_INC}            # GUI -- include directory inside GUI folder
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}            # GUI -- include directory inside GUI folder
   ${STUDENT_GUI_LIB_PATH_INC}       # StudentGUI -- include directory inside GUI folder
   ${FLYING_AGENT_GUI_LIB_PATH_INC}  # FlyingAgentGUI -- include directory inside GUI folder
   ${catkin_INCLUDE_DIRS}
@@ -351,28 +351,28 @@ add_executable(ParameterService          src/nodes/ParameterService.cpp)
 
 
 # GUI -- Add sources here
-set(MY_CPP_SOURCES_GUI              # compilation of sources
-    ${MY_GUI_LIB_PATH_SRC}/mainguiwindow.cpp
-    ${MY_GUI_LIB_PATH_SRC}/main.cpp
-    ${MY_GUI_LIB_PATH_SRC}/cornergrabber.cpp
-    ${MY_GUI_LIB_PATH_SRC}/crazyFlyZone.cpp
-    ${MY_GUI_LIB_PATH_SRC}/crazyFlyZoneTab.cpp
-    ${MY_GUI_LIB_PATH_SRC}/myGraphicsRectItem.cpp
-    ${MY_GUI_LIB_PATH_SRC}/myGraphicsScene.cpp
-    ${MY_GUI_LIB_PATH_SRC}/myGraphicsView.cpp
-    ${MY_GUI_LIB_PATH_SRC}/tablePiece.cpp
-    ${MY_GUI_LIB_PATH_SRC}/marker.cpp
-    ${MY_GUI_LIB_PATH_SRC}/rosNodeThread_for_managerGUI.cpp
-    ${MY_GUI_LIB_PATH_SRC}/crazyFly.cpp
-    ${MY_GUI_LIB_PATH_SRC}/CFLinker.cpp
-    ${MY_GUI_LIB_PATH_SRC}/channelLUT.cpp
-    ${MY_GUI_LIB_PATH_SRC}/centerMarker.cpp
+set(SYSTEM_CONFIG_GUI_CPP_SOURCES              # compilation of sources
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/mainguiwindow.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/main.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/cornergrabber.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFlyZone.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFlyZoneTab.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsRectItem.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsScene.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/myGraphicsView.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/tablePiece.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/marker.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/rosNodeThread_for_systemConfigGUI.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/crazyFly.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/CFLinker.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/channelLUT.cpp
+    ${SYSTEM_CONFIG_GUI_LIB_PATH_SRC}/centerMarker.cpp
     )
 
 
 
 # StudentGUI -- Add sources here
-set(MY_CPP_SOURCES_STUDENT_GUI              # compilation of sources
+set(STUDENT_GUI_CPP_SOURCES              # compilation of sources
     ${STUDENT_GUI_LIB_PATH_SRC}/MainWindow.cpp
     ${STUDENT_GUI_LIB_PATH_SRC}/main.cpp
     ${STUDENT_GUI_LIB_PATH_SRC}/rosNodeThread_for_studentGUI.cpp
@@ -381,7 +381,7 @@ set(MY_CPP_SOURCES_STUDENT_GUI              # compilation of sources
 
 
 # FLYING AGENT GUI -- Add sources here
-set(MY_CPP_SOURCES_FLYING_AGENT_GUI         # compilation of sources
+set(FLYING_AGENT_GUI_CPP_SOURCES         # compilation of sources
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/mainwindow.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/main.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/rosNodeThread_for_flyingAgentGUI.cpp
@@ -401,18 +401,18 @@ set(MY_CPP_SOURCES_FLYING_AGENT_GUI         # compilation of sources
 
 
 # GUI -- Add executables here
-add_executable(my_GUI ${MY_CPP_SOURCES_GUI} ${UIS_HDRS_GUI} ${SRC_MOC_HDRS_GUI} ${MY_RESOURCE_FILE_RCC})
-qt5_use_modules(my_GUI Widgets)
+add_executable(systemConfigGUI ${SYSTEM_CONFIG_GUI_CPP_SOURCES} ${UIS_HDRS_GUI} ${SRC_MOC_HDRS_GUI} ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC})
+qt5_use_modules(systemConfigGUI Widgets)
 
 
 
 # StudentGUI -- Add executables here
-add_executable(student_GUI ${MY_CPP_SOURCES_STUDENT_GUI} ${UIS_HDRS_STUDENT_GUI} ${SRC_MOC_HDRS_STUDENT_GUI} ${STUDENT_RESOURCE_FILE_RCC})
+add_executable(student_GUI ${STUDENT_GUI_CPP_SOURCES} ${UIS_HDRS_STUDENT_GUI} ${SRC_MOC_HDRS_STUDENT_GUI} ${STUDENT_RESOURCE_FILE_RCC})
 qt5_use_modules(student_GUI Widgets)
 
 
 # FLYING AGENT GUI -- Add executables here
-add_executable(flyingAgentGUI ${MY_CPP_SOURCES_FLYING_AGENT_GUI} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
+add_executable(flyingAgentGUI ${FLYING_AGENT_GUI_CPP_SOURCES} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
 qt5_use_modules(flyingAgentGUI Widgets)
 
 
@@ -437,7 +437,7 @@ add_dependencies(ParameterService          dfall_pkg_generate_messages_cpp ${cat
 
 
 # GUI-- dependencies
-add_dependencies(my_GUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(systemConfigGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
@@ -493,12 +493,9 @@ target_link_libraries(ParameterService          ${catkin_LIBRARIES})
 
 
 # GUI -- link libraries
-target_link_libraries(my_GUI Qt5::Widgets) # GUI -- let my_GUI have acesss to Qt stuff
-target_link_libraries(my_GUI Qt5::Svg)
-
-# target_link_libraries(my_library Qt5::Widgets) # GUI -- let my_library have access to Qt stuff
-# target_link_libraries(my_GUI my_library)
-target_link_libraries(my_GUI ${catkin_LIBRARIES})
+target_link_libraries(systemConfigGUI Qt5::Widgets) # GUI -- let systemConfigGUI have acesss to Qt stuff
+target_link_libraries(systemConfigGUI Qt5::Svg)
+target_link_libraries(systemConfigGUI ${catkin_LIBRARIES})
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.pro
similarity index 95%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.pro
index 0175414f..f338a455 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.pro
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.pro
@@ -8,13 +8,13 @@ QT       += core gui
 
 greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
 
-TARGET = CrazyFlyGUI
+TARGET = SystemConfigGUI
 TEMPLATE = app
 
 INCLUDEPATH += $$PWD/include
 CONFIG += c++11
 
-RESOURCES = CrazyFlyGUI.qrc
+RESOURCES = SystemConfigGUI.qrc
 
 QT+= svg
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.qrc
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.qrc
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
index a0a9f568..b0eb2064 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
@@ -38,7 +38,7 @@
 #include "crazyFlyZone.h"
 #include "ui_mainguiwindow.h"
 
-#include "rosNodeThread_for_managerGUI.h"
+#include "rosNodeThread_for_systemConfigGUI.h"
 
 #include <QObject>
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
index e9fa1320..abe9d659 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
@@ -41,7 +41,7 @@
 
 
 #ifdef CATKIN_MAKE
-#include "rosNodeThread_for_managerGUI.h"
+#include "rosNodeThread_for_systemConfigGUI.h"
 
 // Include the standard message types
 #include "std_msgs/Int32.h"
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_systemConfigGUI.h
similarity index 96%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_systemConfigGUI.h
index 65c516e2..1a4f037c 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_managerGUI.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_systemConfigGUI.h
@@ -30,8 +30,8 @@
 //    ----------------------------------------------------------------------------------
 
 
-#ifndef ___ROSNODETHREAD_FOR_MANAGERGUI_H___
-#define ___ROSNODETHREAD_FOR_MANAGERGUI_H___
+#ifndef ___ROSNODETHREAD_FOR_SYSTEMCONFIGGUI_H___
+#define ___ROSNODETHREAD_FOR_SYSTEMCONFIGGUI_H___
 
 #include <QtCore>
 #include <QThread>
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 3b495f9f..b8615d17 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
@@ -73,7 +73,7 @@ MainGUIWindow::MainGUIWindow(int argc, char **argv, QWidget *parent) :
     ui(new Ui::MainGUIWindow)
 {
     #ifdef CATKIN_MAKE
-    _rosNodeThread = new rosNodeThread(argc, argv, "my_GUI");
+    _rosNodeThread = new rosNodeThread(argc, argv, "SystemConfigGUI");
     #endif
     ui->setupUi(this);
     _init();
@@ -274,7 +274,7 @@ void MainGUIWindow::_init()
 
     ros_namespace = ros::this_node::getNamespace();
 
-    ros::NodeHandle nodeHandle("~");
+    //ros::NodeHandle nodeHandle("~");
     //DBChangedPublisher = nodeHandle.advertise<std_msgs::Int32>("DBChanged", 1);
 
     // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_systemConfigGUI.cpp
similarity index 95%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_systemConfigGUI.cpp
index bbb3f6c1..847e8616 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_managerGUI.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_systemConfigGUI.cpp
@@ -30,7 +30,7 @@
 //    ----------------------------------------------------------------------------------
 
 
-#include "rosNodeThread_for_managerGUI.h"
+#include "rosNodeThread_for_systemConfigGUI.h"
 
 #include "dfall_pkg/CMRead.h"
 #include "dfall_pkg/CMUpdate.h"
@@ -63,7 +63,9 @@ bool rosNodeThread::init()
     this->moveToThread(m_pThread); // QObject method
 
     connect(m_pThread, SIGNAL(started()), this, SLOT(run()));
-    ros::init(m_Init_argc, m_pInit_argv, m_node_name); // my_GUI is the name of this node
+    ros::init(m_Init_argc, m_pInit_argv, m_node_name);
+    // Note that the variable "m_node_name" should be the
+    // string "SystemConfigGUI" in this case
 
     if (!ros::master::check())
     {
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 2ca4c562..45c3fee7 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -37,8 +37,7 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     ui(new Ui::MainWindow)
 {
 #ifdef CATKIN_MAKE
-    //ROS_INFO("[flyingAgentGUI] Debug Point 5");
-    m_rosNodeThread = new rosNodeThread(argc, argv, "flyingAgentGUI");
+    m_rosNodeThread = new rosNodeThread(argc, argv, "FlyingAgentGUI");
 #endif
 
 #ifdef CATKIN_MAKE
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
index 5072e14e..b9704007 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
@@ -65,7 +65,9 @@ bool rosNodeThread::init()
     this->moveToThread(m_pThread); // QObject method
 
     connect(m_pThread, SIGNAL(started()), this, SLOT(run()));
-    ros::init(m_Init_argc, m_pInit_argv, m_node_name); // flyingAgentGUI is the name of this node
+    ros::init(m_Init_argc, m_pInit_argv, m_node_name);
+    // Note that the variable "m_node_name" should be the
+    // string "FlyingAgentGUI" in this case
 
     if (!ros::master::check())
     {
diff --git a/dfall_ws/src/dfall_pkg/launch/Agent.launch b/dfall_ws/src/dfall_pkg/launch/Agent.launch
index 0eca8749..33b24834 100755
--- a/dfall_ws/src/dfall_pkg/launch/Agent.launch
+++ b/dfall_ws/src/dfall_pkg/launch/Agent.launch
@@ -156,9 +156,9 @@
 		<group if="$(arg withGUI)">
 			<node
 				pkg    = "dfall_pkg"
-				name   = "flyingAgentGUI"
+				name   = "FlyingAgentGUI"
 				output = "screen"
-				type   = "flyingAgentGUI"
+				type   = "FlyingAgentGUI"
 				>
 				<param name="type"     type="str"  value="agent" />
 				<param name="agentID"  value="$(arg agentID)" />
diff --git a/dfall_ws/src/dfall_pkg/launch/Coordinator.launch b/dfall_ws/src/dfall_pkg/launch/Coordinator.launch
index 61dacd38..9d10deaf 100755
--- a/dfall_ws/src/dfall_pkg/launch/Coordinator.launch
+++ b/dfall_ws/src/dfall_pkg/launch/Coordinator.launch
@@ -18,9 +18,9 @@
 		<group if="$(arg withGUI)">
 			<node
 				pkg="dfall_pkg"
-				name="flyingAgentGUI"
+				name="FlyingAgentGUI"
 				output="screen"
-				type="flyingAgentGUI"
+				type="FlyingAgentGUI"
 				>
 				<param name="type"     type="str"  value="coordinator" />
 				<param name="coordID"  value="$(arg coordID)" />
-- 
GitLab


From 76f18aae12994024508af9b21cc119f164242969 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 12:53:28 +0100
Subject: [PATCH 63/87] Change folder name from CrazyFlyGUI to systemConfigGUI

---
 .../SystemConfigGUI.pro                             |   0
 .../SystemConfigGUI.qrc                             |   0
 .../forms/mainguiwindow.ui                          |   0
 .../images/center_rect.svg                          |   0
 .../images/drone.png                                | Bin
 .../images/drone.svg                                |   0
 .../images/drone_fixed_01.svg                       |   0
 .../images/drone_fixed_02.svg                       |   0
 .../images/drone_fixed_03.svg                       |   0
 .../images/drone_fixed_04.svg                       |   0
 .../images/drone_fixed_05.svg                       |   0
 .../images/drone_fixed_06.svg                       |   0
 .../images/drone_fixed_07.svg                       |   0
 .../images/drone_fixed_08.svg                       |   0
 .../images/drone_fixed_09.svg                       |   0
 .../images/drone_fixed_unk.svg                      |   0
 .../include/CFLinker.h                              |   0
 .../include/centerMarker.h                          |   0
 .../include/channelLUT.h                            |   0
 .../include/constants_for_qt_compile.h              |   0
 .../include/cornergrabber.h                         |   0
 .../include/crazyFly.h                              |   0
 .../include/crazyFlyZone.h                          |   0
 .../include/crazyFlyZoneTab.h                       |   0
 .../include/globalDefinitions.h                     |   0
 .../include/mainguiwindow.h                         |   0
 .../include/marker.h                                |   0
 .../include/myGraphicsRectItem.h                    |   0
 .../include/myGraphicsScene.h                       |   0
 .../include/myGraphicsView.h                        |   0
 .../include/rosNodeThread_for_systemConfigGUI.h     |   0
 .../include/tablePiece.h                            |   0
 .../src/CFLinker.cpp                                |   0
 .../src/centerMarker.cpp                            |   0
 .../src/channelLUT.cpp                              |   0
 .../src/cornergrabber.cpp                           |   0
 .../src/crazyFly.cpp                                |   0
 .../src/crazyFlyZone.cpp                            |   0
 .../src/crazyFlyZoneTab.cpp                         |   0
 .../{CrazyFlyGUI => systemConfigGUI}/src/main.cpp   |   0
 .../src/mainguiwindow.cpp                           |   0
 .../{CrazyFlyGUI => systemConfigGUI}/src/marker.cpp |   0
 .../src/myGraphicsRectItem.cpp                      |   0
 .../src/myGraphicsScene.cpp                         |   0
 .../src/myGraphicsView.cpp                          |   0
 .../src/rosNodeThread_for_systemConfigGUI.cpp       |   0
 .../src/tablePiece.cpp                              |   0
 47 files changed, 0 insertions(+), 0 deletions(-)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/SystemConfigGUI.pro (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/SystemConfigGUI.qrc (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/forms/mainguiwindow.ui (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/center_rect.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone.png (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_01.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_02.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_03.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_04.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_05.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_06.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_07.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_08.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_09.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/images/drone_fixed_unk.svg (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/CFLinker.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/centerMarker.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/channelLUT.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/constants_for_qt_compile.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/cornergrabber.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/crazyFly.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/crazyFlyZone.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/crazyFlyZoneTab.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/globalDefinitions.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/mainguiwindow.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/marker.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/myGraphicsRectItem.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/myGraphicsScene.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/myGraphicsView.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/rosNodeThread_for_systemConfigGUI.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/include/tablePiece.h (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/CFLinker.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/centerMarker.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/channelLUT.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/cornergrabber.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/crazyFly.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/crazyFlyZone.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/crazyFlyZoneTab.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/main.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/mainguiwindow.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/marker.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/myGraphicsRectItem.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/myGraphicsScene.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/myGraphicsView.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/rosNodeThread_for_systemConfigGUI.cpp (100%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/{CrazyFlyGUI => systemConfigGUI}/src/tablePiece.cpp (100%)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.pro
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.pro
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.qrc
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/SystemConfigGUI.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.qrc
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/forms/mainguiwindow.ui
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/forms/mainguiwindow.ui
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/forms/mainguiwindow.ui
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/center_rect.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/center_rect.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/center_rect.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/center_rect.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.png b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone.png
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.png
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone.png
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_01.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_01.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_01.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_02.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_02.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_02.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_03.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_03.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_03.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_04.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_04.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_04.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_05.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_05.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_05.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_06.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_06.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_06.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_07.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_07.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_07.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_08.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_08.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_08.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_09.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_09.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_09.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_unk.svg
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/images/drone_fixed_unk.svg
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/images/drone_fixed_unk.svg
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/CFLinker.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/CFLinker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/CFLinker.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/centerMarker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/centerMarker.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/centerMarker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/centerMarker.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/channelLUT.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/channelLUT.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/channelLUT.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/channelLUT.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/constants_for_qt_compile.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/cornergrabber.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/cornergrabber.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/cornergrabber.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFly.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFly.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFlyZone.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZone.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFlyZone.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFlyZoneTab.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/crazyFlyZoneTab.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/crazyFlyZoneTab.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/globalDefinitions.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/globalDefinitions.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/globalDefinitions.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/mainguiwindow.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/mainguiwindow.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/mainguiwindow.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/marker.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/marker.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/marker.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/marker.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsRectItem.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsRectItem.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsRectItem.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsScene.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsScene.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsScene.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsView.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/myGraphicsView.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/myGraphicsView.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_systemConfigGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/rosNodeThread_for_systemConfigGUI.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/rosNodeThread_for_systemConfigGUI.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/tablePiece.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/tablePiece.h
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/include/tablePiece.h
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/tablePiece.h
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/CFLinker.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/CFLinker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/CFLinker.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/centerMarker.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/centerMarker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/centerMarker.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/channelLUT.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/channelLUT.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/cornergrabber.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/cornergrabber.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/cornergrabber.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFly.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFly.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFlyZone.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZone.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFlyZone.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFlyZoneTab.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/crazyFlyZoneTab.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/crazyFlyZoneTab.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/main.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/main.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/main.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/mainguiwindow.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/marker.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/marker.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/marker.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/marker.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsRectItem.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsRectItem.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsRectItem.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsScene.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsScene.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsScene.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsView.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/myGraphicsView.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/myGraphicsView.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_systemConfigGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/rosNodeThread_for_systemConfigGUI.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/rosNodeThread_for_systemConfigGUI.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/rosNodeThread_for_systemConfigGUI.cpp
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/tablePiece.cpp
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/tablePiece.cpp
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/src/tablePiece.cpp
-- 
GitLab


From 2b5e9da29f45cce688b02ae54cd66fdc13136b0b Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 12:59:56 +0100
Subject: [PATCH 64/87] Changed file names for the System Config GUI

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt                     | 8 ++++----
 .../{SystemConfigGUI.pro => systemConfigGUI.pro}          | 4 ++--
 .../{SystemConfigGUI.qrc => systemconfiggui.qrc}          | 0
 dfall_ws/src/dfall_pkg/launch/Teacher.launch              | 4 ++--
 dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp    | 3 ---
 5 files changed, 8 insertions(+), 11 deletions(-)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/{SystemConfigGUI.pro => systemConfigGUI.pro} (95%)
 rename dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/{SystemConfigGUI.qrc => systemconfiggui.qrc} (100%)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index 6df6018d..dcbc0a05 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -57,10 +57,10 @@ find_package(Qt5Svg REQUIRED)
 
 
 # GUI -- Add src, includes, and resources
-set(SYSTEM_CONFIG_GUI_LIB_PATH_SRC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/src)
-set(SYSTEM_CONFIG_GUI_LIB_PATH_INC   ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/include)
-set(SYSTEM_CONFIG_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/forms)
-set(SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/CrazyFlyGUI/CrazyFlyGUI.qrc)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_SRC   ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/src)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_INC   ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/include)
+set(SYSTEM_CONFIG_GUI_LIB_PATH_FORMS ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/forms)
+set(SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConfigGUI/systemconfiggui.qrc)
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/systemConfigGUI.pro
similarity index 95%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.pro
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/systemConfigGUI.pro
index f338a455..4c480d64 100755
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.pro
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/systemConfigGUI.pro
@@ -8,13 +8,13 @@ QT       += core gui
 
 greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
 
-TARGET = SystemConfigGUI
+TARGET = systemConfigGUI
 TEMPLATE = app
 
 INCLUDEPATH += $$PWD/include
 CONFIG += c++11
 
-RESOURCES = SystemConfigGUI.qrc
+RESOURCES = systemconfiggui.qrc
 
 QT+= svg
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/systemconfiggui.qrc
similarity index 100%
rename from dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/SystemConfigGUI.qrc
rename to dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/systemconfiggui.qrc
diff --git a/dfall_ws/src/dfall_pkg/launch/Teacher.launch b/dfall_ws/src/dfall_pkg/launch/Teacher.launch
index b093995b..a9235436 100755
--- a/dfall_ws/src/dfall_pkg/launch/Teacher.launch
+++ b/dfall_ws/src/dfall_pkg/launch/Teacher.launch
@@ -22,9 +22,9 @@
 	<!-- TEACHER GUI -->
 	<node
 		pkg="dfall_pkg"
-		name="my_GUI"
+		name="SystemConfigGUI"
 		output="screen"
-		type="my_GUI"
+		type="SystemConfigGUI"
 		>
 	</node>
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 72859686..eadb4743 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -1380,9 +1380,6 @@ int main(int argc, char* argv[])
     
 
     
-    // Subscriber for "commandAllAgents" commands that are sent from the coordinator node
-    //ros::Subscriber commandAllAgentsSubscriber = namespaceNodeHandle.subscribe("/my_GUI/commandAllAgents", 1, commandAllAgentsCallback);
-
     // crazyradio status. Connected, connecting or disconnected
     ros::Subscriber crazyRadioStatusSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
-- 
GitLab


From a549188caeaf16793f2f53d990b98bc945c80af3 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 13:05:27 +0100
Subject: [PATCH 65/87] Remove the StudentGUI because it is was not updated to
 the new node naming convention and because it was re-factored as the
 FlyingAgentGUI

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         |   49 +-
 .../GUI_Qt/studentGUI/images/battery_20.png   |  Bin 2099 -> 0 bytes
 .../GUI_Qt/studentGUI/images/battery_40.png   |  Bin 2147 -> 0 bytes
 .../GUI_Qt/studentGUI/images/battery_60.png   |  Bin 2232 -> 0 bytes
 .../GUI_Qt/studentGUI/images/battery_80.png   |  Bin 2252 -> 0 bytes
 .../studentGUI/images/battery_empty.png       |  Bin 3379 -> 0 bytes
 .../GUI_Qt/studentGUI/images/battery_full.png |  Bin 2152 -> 0 bytes
 .../studentGUI/images/battery_unknown.png     |  Bin 3138 -> 0 bytes
 .../images/flying_state_disabling.png         |  Bin 3303 -> 0 bytes
 .../images/flying_state_enabling.png          |  Bin 3512 -> 0 bytes
 .../studentGUI/images/flying_state_flying.png |  Bin 3001 -> 0 bytes
 .../studentGUI/images/flying_state_off.png    |  Bin 3106 -> 0 bytes
 .../images/flying_state_unknown.png           |  Bin 3868 -> 0 bytes
 .../GUI_Qt/studentGUI/images/rf_connected.png |  Bin 6410 -> 0 bytes
 .../studentGUI/images/rf_connecting.png       |  Bin 5679 -> 0 bytes
 .../studentGUI/images/rf_disconnected.png     |  Bin 5321 -> 0 bytes
 .../GUI_Qt/studentGUI/include/MainWindow.h    |  433 --
 .../include/rosNodeThread_for_studentGUI.h    |   93 -
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      | 2181 -------
 .../GUI_Qt/studentGUI/src/MainWindow.ui       | 5238 -----------------
 .../dfall_pkg/GUI_Qt/studentGUI/src/main.cpp  |   42 -
 .../src/rosNodeThread_for_studentGUI.cpp      |  114 -
 .../GUI_Qt/studentGUI/studentGUI.pro          |   28 -
 .../GUI_Qt/studentGUI/studentgui.qrc          |   19 -
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp |    3 +-
 25 files changed, 4 insertions(+), 8196 deletions(-)
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_20.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_40.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_60.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_80.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_empty.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_full.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_unknown.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_disabling.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_enabling.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_flying.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_off.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_unknown.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connected.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connecting.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_disconnected.png
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro
 delete mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index dcbc0a05..5e4e44e1 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -64,13 +64,6 @@ set(SYSTEM_CONFIG_GUI_RESOURCE_FILE_QRC  ${PROJECT_SOURCE_DIR}/GUI_Qt/systemConf
 
 
 
-# StudentGUI -- Add src, includes, and resources
-set(STUDENT_GUI_LIB_PATH_SRC ${PROJECT_SOURCE_DIR}/GUI_Qt/studentGUI/src)
-set(STUDENT_GUI_LIB_PATH_INC ${PROJECT_SOURCE_DIR}/GUI_Qt/studentGUI/include)
-set(STUDENT_RESOURCE_FILE_QRC ${PROJECT_SOURCE_DIR}/GUI_Qt/studentGUI/studentgui.qrc)
-
-
-
 # Flying Agent GUI -- Add src, includes, forms, and resources
 set(FLYING_AGENT_GUI_LIB_PATH_SRC      ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/src)
 set(FLYING_AGENT_GUI_LIB_PATH_INC      ${PROJECT_SOURCE_DIR}/GUI_Qt/flyingAgentGUI/include)
@@ -107,18 +100,6 @@ qt5_add_resources(SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC ${SYSTEM_CONFIG_GUI_RESOUR
 
 
 
-# StudentGUI -- Special Qt sources that need to be wrapped before being compiled
-set(SRC_HDRS_QOBJECT_STUDENT_GUI
-  ${STUDENT_GUI_LIB_PATH_INC}/MainWindow.h
-  ${STUDENT_GUI_LIB_PATH_INC}/rosNodeThread_for_studentGUI.h
-  )
-# StudentGUI -- wrap UI file and QOBJECT files
-qt5_wrap_ui(UIS_HDRS_STUDENT_GUI ${STUDENT_GUI_LIB_PATH_SRC}/MainWindow.ui)
-qt5_wrap_cpp(SRC_MOC_HDRS_STUDENT_GUI ${SRC_HDRS_QOBJECT_STUDENT_GUI})
-# GUI -- wrap resource file qrc->rcc
-qt5_add_resources(STUDENT_RESOURCE_FILE_RCC ${STUDENT_RESOURCE_FILE_QRC})
-
-
 
 # Flying Agent GUI
 # - Special Qt sources that need to be wrapped before being compiled
@@ -286,7 +267,6 @@ generate_messages(
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
   INCLUDE_DIRS include ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}            # GUI -- include headers from GUI in package
-  INCLUDE_DIRS include ${STUDENT_GUI_LIB_PATH_INC}       # StudentGUI -- include headers from GUI in package
   INCLUDE_DIRS include ${FLYING_AGENT_GUI_LIB_PATH_INC}  # FlyingAgentGUI -- include headers from GUI in package
   LIBRARIES
   CATKIN_DEPENDS roscpp rospy std_msgs rosbag roslib
@@ -301,9 +281,8 @@ catkin_package(
 ## Your package locations should be listed before other locations
 # include_directories(include)
 include_directories(
-  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}            # GUI -- include directory inside GUI folder
-  ${STUDENT_GUI_LIB_PATH_INC}       # StudentGUI -- include directory inside GUI folder
-  ${FLYING_AGENT_GUI_LIB_PATH_INC}  # FlyingAgentGUI -- include directory inside GUI folder
+  ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}    # SystemConfigGUI -- include directory inside GUI folder
+  ${FLYING_AGENT_GUI_LIB_PATH_INC}     # FlyingAgentGUI  -- include directory inside GUI folder
   ${catkin_INCLUDE_DIRS}
   include
   include/nodes
@@ -371,14 +350,6 @@ set(SYSTEM_CONFIG_GUI_CPP_SOURCES              # compilation of sources
 
 
 
-# StudentGUI -- Add sources here
-set(STUDENT_GUI_CPP_SOURCES              # compilation of sources
-    ${STUDENT_GUI_LIB_PATH_SRC}/MainWindow.cpp
-    ${STUDENT_GUI_LIB_PATH_SRC}/main.cpp
-    ${STUDENT_GUI_LIB_PATH_SRC}/rosNodeThread_for_studentGUI.cpp
-    )
-
-
 
 # FLYING AGENT GUI -- Add sources here
 set(FLYING_AGENT_GUI_CPP_SOURCES         # compilation of sources
@@ -406,11 +377,6 @@ qt5_use_modules(systemConfigGUI Widgets)
 
 
 
-# StudentGUI -- Add executables here
-add_executable(student_GUI ${STUDENT_GUI_CPP_SOURCES} ${UIS_HDRS_STUDENT_GUI} ${SRC_MOC_HDRS_STUDENT_GUI} ${STUDENT_RESOURCE_FILE_RCC})
-qt5_use_modules(student_GUI Widgets)
-
-
 # FLYING AGENT GUI -- Add executables here
 add_executable(flyingAgentGUI ${FLYING_AGENT_GUI_CPP_SOURCES} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
 qt5_use_modules(flyingAgentGUI Widgets)
@@ -441,11 +407,6 @@ add_dependencies(systemConfigGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORT
 
 
 
-# StudentGUI-- dependencies
-add_dependencies(student_GUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-
-
-
 # FLYING AGENT GUI-- dependencies
 add_dependencies(flyingAgentGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
@@ -499,12 +460,6 @@ target_link_libraries(systemConfigGUI ${catkin_LIBRARIES})
 
 
 
-# StudentGUI -- link libraries
-target_link_libraries(student_GUI Qt5::Widgets) # GUI -- let student_GUI have acesss to Qt stuff
-target_link_libraries(student_GUI ${catkin_LIBRARIES})
-
-
-
 # Flying Agent GUI -- link libraries
 target_link_libraries(flyingAgentGUI Qt5::Widgets) # GUI -- let flyingAgentGUI have acesss to Qt stuff
 target_link_libraries(flyingAgentGUI ${catkin_LIBRARIES})
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_20.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_20.png
deleted file mode 100644
index cc7ae62ab7c662f7cf3e098e713232d2d6e0ae14..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 2099
zcmeHI`8OMg77kuZqm)t^s-ude#h_0~F;T=$EUn5=lA=P%&_26ZDz-Ke%b3PmYir+w
z8mXPq67*RbQnfFQB`6Y9Oy+-hKfWKn`<;8wx#ynq-Fv?K!p_D_1SkUp001Hu=Eiq<
z?94;F&{<w&bh0=+;tRNIW(24imi@*{&OI@A3IG5=7ykjDSN?x_ErN6lV?&2fzRej|
z>w8F9z;?i3;&UOPWjLrQVW*I&7;E6YFuJCpI98Tg@Cc)5zW*T+mbul((U5RcZ~yqv
z$yx(@vo4D?^yb`@hJClO$F1oi<Cy2#j)n79LUMYEuMs##IO}xwz;XH%k^L37bs9Yk
z>%iS^WA8qB^YY~-Q!CDyz<GbXvl#!ssz2Sn>W!Z?Hz>w<8%s2r^2=z!6`U2;LP^u-
z=tCPD*xk-fgTvn5-jZjAh8qJkTBNJ9vu<W)W{a4yR#z$EGTA(WOeP1?Xf%wd#t2S+
zE4%x^0)YrZwT18JnD32EV2o2u7FUN~9n0soaGCA@S^g-E>~G>G3+=@UULYu0I3Fa6
z4>v3=ElDT#q?Kzmc&lFvXzX(@Um#h@1_jLrT-VH@sX`$A_a*nB`Psjr(Q?$lZx?g&
zK@<s(1@_!z^#imlEPRh$a2enzCcc)ImbO{5Xl-lj^|{8?BjV?vOYs}jva;vDsHrs&
zLF%pRdsv2RS(jz6I*ULg_TV=f7!<D*U#+59@x){zQCP*GWgUsz7Eg4<75Ku`)^v`z
zC&&5hgM%$l!0gh}qgENQsMxzDU^UsBSFT(^Ul0`~D^JjB366W=Z9NY)-j&tVv}fh#
zpE}%Fg&%(!otc@@S{=zh<?bx@Q}xF?`<q!?GgQw70ay)zK;V+eQURWxo^rR4y|JaD
zrDIvaYompCe0_bXlQRE4JMeOBb{1V9!ulGG0N-PDcN-N|x@<y)j+O^A@_!<|*Mq@e
z=<?sMPA^O|7&#Rc6{=%nV>eRU%ky+G7>u^8egr24Vw<<|Csa&MZp6~klD<OA$+8jD
z4Z(h{*&hD&@#DuE^m>n7xZ@WT3WW)#zM7$ir0j@qTpIC@Q(j+R*Yp3<@-&W({4%es
z_D2iMfs(5qdDP$BteyTV*;b)41f7+Ywd-nMPm7+LiWdga_t!s19`(o(BKuk14<dp&
zH|);PMtm%soTj3GsNzJBPjQUV(Yey;H5De4>Fza>x6k~|((>cp=%^jvsa4c+Q_n~O
zC^!G4(j-G2&2>z6K_Wq#1N<?k9Ll{?n=tVgVXaL~`$<T*XCi&#C%nbHuBxhn=B0Op
zs&%QS{dA|8uYxq}?$^cX>tue}WV*Sz71Df~r2c9ah*U{l<IRg?zED-xeKKb-Bu|Wj
zC@IzdbA$KU?vyFu>dML_RhYl(x=~7UvS0eD-%RU$l%ytu(R}!%uD<@JiI|BuS2g67
zi@nQmAM=mY)VZ;sn{7vuAAypEo;!^%B(Hia%HARs6uJ+D;!V2^$An~*6OthRFaGZZ
z5!uhXa8ilHRy0k_OzsYye-OdVt={(M7Cj9)%toatf_I>hzRTyW-@3(8RiulHw}J+M
zKwU3vk`9$BziEuX+DLPj^C}}t%i+cH2BUJCd#!)zkVILFzTlV+K2b`6X`phnuV<Co
zIs|OzYGw!-_}WGA2_u2~6poYe$=O!7dq0rHbgrEdBw<y_V?xfwloWg(x|XwIOA<vN
zV^&~W7v-yq3%sCyagE~l>nS<fg-5Y?(<aG93!dWw?BXWB1rEww8O-*6KTEODG9`>Y
zXvRus2)`qe%?fvu%jpLp=(Q1Z)XQsuDAd=wA4&W4&E0T!%yCK2{KV&>p`o|Z($cJV
zz!U6sBckQOCWD>gwS`_>+(6i;dD&Z6buij;P7e0Uk!W8Z9|u?_GES-~+qy)%cKXn?
znD(B$A0GB}+^_bL7sa%4qBI(TKy2#AM*$rS<?clNKo)-r?bn<gmIF=hmWE2`g@j9)
zEw`qpEVY*3(AI}-PIRP0Y=i&I$hZ)C=`20f(Scj%R6Thu2BxEvrB+)R<AL;gRM+@M
zsbulgmzZGU;(B{=fj(;kIX;|+=c`GdPXGxB2rN4}Ir&EfAE}6q`rMHsE)Twbt++Fe
zmNgrS;;<$eW+^{MmQ4O0qyfj9Y-}>#lBTAn78(@5g~C7}77m9W+Ce9Zrzq~!nY<Y~
zos+I;v48=CJ0&C}R%w`k@8jbRgwpuwpoxH6g8NPhiHYBJ_4L+pI2=1ADGAGlMjtCy
z7xK5ESUmUZ|IYKG9EeRWM+pjLYaMLI;@@k_5W_0eSnlHB@ksER9r0{gN`XLUTx(_l
z{1=%5eY_|@g6WPIZSsD0B%}+lE+d}P9WUZz9?Qj%+tKnLWLUh%53n$?F|ILsi2oa<
C)C#=-

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_40.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_40.png
deleted file mode 100644
index cea5ab35b9605910112dd8a7e2eda371c430894b..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 2147
zcmdT``#Td18y+o2&8tyt$XO0=2Zu;P%VEfALl}(_Hg8UeLdf|gq@;3~O$zTf46QlL
z%K6aHzNj{boLL#0oW08D{Rh75`hNU=xS#vEuj_g4-|pvnGMya}U~!l@0002n+E}6v
z7=3^=kjOzDYvXSpkWeHFaRpF2B>(L|h=tpDMgjmbkbfW)MErQL0s`4u!d>qQEl>E^
zySU4X3WkN>s0d$yha;7<&GppfjtXa5RK8Hlx7UUD57<ku_h*<sU+LaHCxtz0rrpu-
z+?Rbt>0*?=va+0-ovh8C6!3|C_yn%{qc!RDp_aJ5tmP02<DKG9{m?`sd@TPPKhE((
z<(J{Fk39-Hr+ul1F_#s#m2to`ms#+Ozk!NKDQc20vD|D8u96rKFMF{(1*iah8KIU@
zSXh|3vb=n{sHDXElqWS?6oo=*h>MHwo`((c^jbU<p7_+I&KR1TQ)<cN;Uj=(?1{a9
zY56v?*&fVKWcPPRyDt&^(}9J*B`gdSh8@aWs^K%Aoh9CKyu{v8PD&6=!AtF4p#|y3
z`e<A(7oXq%ME2$lGmOn=Zf<U_9yYw-eoK?sADY8U8#jOMZVXifOdh!^we<bFpUfF=
z-)Ivbg6u3`bYfzHD1RY*YPUfY5G@Je*4Nh$4lP0z6+hHor}v~rjd11~|1K$!H#9Qp
z9U_{)8>w7kU(JED#ddn>t*x#1l}wgtVUsK4;BWDLWvVJF!s3$LU-M==c^1t07dnhk
z&L8V-ZEXkwfk59L4KggAoxcx~(M-GbT^Kn$KE7v_n3$MEd7I{BB|&fuvb%aU4uioY
zoYL1{`-?I_KZ&qtY;1HdHI3UWZf|cNzXKK|##K`&l)OpO2Xa$WQ{~&Y7#}ox^zh)1
zSiwhZy~oTZe=>22Rb~;Q1BM=&8(3dom*%tUXB$UHM|(IN&z#rSS4=^pzUNxqQK(z|
z&E+v-zrtmFl!JrA`G9}`1s4|=-Mr?0%*Bez$}g_2uH*N9%=MpG1w4B6=y!8-;;V`Z
zy*IG+(faZ6w%SV(5fQwp_LP}Q-r8L(HVK+z9lif6UZbQvbfY8986OoD#mtd2GLu<g
zQo`dywG(1AgG^$6%oX(X^q?bZ>au^w#H(v)WGSM$>IEVnh6pCTXfH3*1=V|6n{UFc
zy!fm4pNV*~I><#n9v<6tfi|5`yZ2+0UGI-+al^QHdC8f??^4IQ{QUeXtgWpZQWN_V
z>84ZjZQvp1>;ngxvzR@*Y;QNW<A#0m@Vje4ryNVdRcDrNTUc~zHCksLA_h?h1BW%#
z)fu<1@9k_sIuL3atuG)G+OIw9d^<9dy5Ec$ck+0=>9Vpi`NjGX#s~df&g&pPU1cpd
zn*UWHy6@gsbj{P{3HmesnUK!TPR=!Q)CMZ0E7ys;y1MEx!|TbB>vq6Kw&L?eMdMay
z(wroTtd2X)<gTo}S?{J$BocYjWsylnlvlN%qE?kkJQ4=xq^9(MVA|=`r*LZW2G%TR
z-5aKG)oGG$a(b5Xk{C=(H0PLs>rqc9mdyoRHmS_7FE-h_1MUw5AGi1{WdM<Ysp6_+
z8%jx!!dbF#i|)LQ{}0QmeY-%pxUQQHM3oG0PJPX$!3fZqg%0$WU|tArD>#WhUXWcR
zd|E-%@a~_a>A)%=yqrCyoSa@<1_9>yrDT9$q3L##23g>fD!3-7Hk|dp41zXfPSCZB
zIDYz5<yuPE*Ru(6B8Nk4Gy|dujzTvDTA+8fs;LP=qDU6GM&#++o_QJFg?+3<ahmQl
z2I*xf?Sh|`m0BT;ahc`>Iw?;2_V)qRr@8`DoYE`lv2rtOhqSLpkv9dB@XkSJF=^^k
zPh^Ug^2-Re^YCRj#XoSw*A7$@HMNkN{Q2D0q_3MWY24V-I6M*oXU3!6SLbiZF=m>j
zs2*yUdw~i{9ubY2IGxC5ZRxElfj>DI9GtGn)uNp^{~U6~<$F{Wo<u^brp5e8O1Uk(
zoqCP@=?FabjE<jdnBvNu>`v;}I&7zppU`l2<8+tX`%4L?v&Lt`tY@@|EGQIOKI6`d
zB_hY2*z)@Zf{!7!nVFds2n2$mpN};bhz*)>nj;q}wVdL3kwDfBx?x)PFUxhq&!ay_
zLTU>N3YJ5`5K*(Tm|7Z*hAg497z`{>r`Hy%ceppMMd6(X+Jb|Fi!Q+!27Sq9_qGKO
z)z#Ivyw{`xb;gDTMNs#!h>&Y@Z?z8O7aUeZYCmpzY?=G-@<A&rD@K^t%Pm)lj8-Gs
zKWWSjIk=?V6Q6j@fa8i9b*XMg>|a65Tl5|_zkg|(JQ0h-x+f%Xbu+0{>LP=|u(Gwa
zU3ox5%qN27(JM9O<^B(^k>@9O*A|b_jHct4KF#(%G|yY2-PN<miaE&hovV-Y^LKi4
z>r#i_zlWWKLi<x&`pt^3n;61!`g<QL?mNChtv)EM1AM_5L^CixTML85vhGKk|8Dq#
z6B_ZCQ&1Sh;qia1@Ob0r4Gn3WvEAikXgK&HVdzO|=`Tb~%nm^nk-L}o__1D6{4O)O
zM*@~>?5W7_IMy>6sewy;V7HE7LC*aO{qOzOS@+8Bik9j%)q_U?U~A=QS$oAd`9BRO
B4M+e0

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_60.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_60.png
deleted file mode 100644
index 1f75257c3c1f44fc10f318274741942916b47b70..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 2232
zcmbW3`8N~{7ssa>nGv!NLOdp937MjhXY3=(Ok}G;*`}<8G$u>KDA|TKuXSu=3(?re
zmPf>p>}Hr`r?I@&WaypVKjHb|-h1vj_xm~b+;h)8Hx6lS#>XSc0{{T{5az}=IMJD7
z1kg#2XSA*V<b-2EH_QwH75!4noCF+b?i2(7K!pC-G4Gr~js%287{l!zA6uPrwX}5*
z2W(VwS*U>$-WW8N=zPk_Z3jJVpBY%z@US4K6?=Fo@cf$Vkm1E?UZWY0cXTs7-m5C;
z)QWd!25HL6@e7%VNSv9?A;y7v{?5I(??6~{Nj=`&yu;jjz!=>18Kms}*zXVRuN(_n
zS97~*UnaV=5O%EQ$8{u^OB88}a#jEaZ$h+Ld18_kFxuey65iFX{&@aiTj?TCGMOB#
zrl$6v+1c3u9X|>la@XBGr?9A~?mkSim#5JQs~p)r6L&B<nb}C8P-0G`&3m=GUTR>;
zh>3YopX_gXXQvgFlg)_xGu~ga4|`tM-wk(d3|^-A&8$UigMx85T&YE2I;11e)3RvD
zDk(8>c`A`Mw$&|(c6H6^6?J$}d`jD&kC2)w^gJ%EieS&~R<jxy9|u9yU1BDjB0`Q&
zCv#g_S)G;A37lROg}AZW<OfciIFaEyoACU3l!`+Ipe~7S_(ESnQL&@Up>p~o;Z%J1
zh012};11#B9A+Vz+z6cTs&nt+XV@lR3zNDkE8A8Gs91Ado7U%73nej`{+&L-w{9_Z
zV`F2d*mP}8O+h*Cn5Mr!6Nmam{YuNq4E+53tlq9<=&Dpp^2S!x*Vmh2u~=<kAt4!y
zdFomSEEtVOw>JbWwy;<%ODy{7$S(cxU{C9(?vMKF>gx2~o*s*b4<AZ81?}(Bu0Q*V
z;r-Sc`MdHNzjW!&We;AWT2Vv86`#fatVj_E#KBorEK%*kUJ5u2gIVh15OuZvC&v}*
zqAF|3N=ub{`ufVXGx~B>gI+cVTUuMk&MhvwuCJ_wIXKE{Xb21r4!TV>hLG&FnnQ`H
zGxXPrdU{g)GI~l<)pNUSwq8O)LR&QV=_p3@Dm@5dc!fY9TpFuDAH-y+M-o)9w*P(m
z?4f^=b=I$1PUnu}Z*G~2RkUn}HE*2D8DHSv2s~nA>%(?RJD${^?rfQ^!1PMF2!Ols
z3(OG;2aTI-@~vyyd|TI*d=|1ix@TBZQxmvAlW2+~#Kxv`RzbKS^0UpVi@?PDXkl!)
zoSloyQG>w##`lhhXqtQ=cccz>vp`y~)!M<%F0=O3)d}KczPFbb1%*Q8_d+6%g1~Dc
z;QG*EL|u!-f@+kmgrj4VpO&SC#me&9nsu$8F7DN2{=u(bOs6DTD8>7WOsmntV)@AZ
zJL}A5_E6_78ylO!?d|RK&Zw7)sRPMp4VX%_srPrHHRiM#XSA;dwoOlypwFSOJtzP7
z$P|ODt+883B(Y<7e||(x31n_~iaw-pBZ`y~`0gICPdV1tX24u$6o&T_HL6v_K&5;n
z;U8YeF@#}4NtY5yPMyS6uq3!E-E`pH-R@mrVvM_$JjPzr1BW;LSVb0um5EpD!{xs_
z4uR5d@=j#`J8ZFQo>oah;37h}x*)VDu_I_0h#UxqqmkQ;y<$8wn<C9LvU>W4U*rr<
z2>u}>_aaEL^Ha9*0L!bG7jIfsr6>q%l2DE&p?p~gV4r_%k1Xcjlp+m!EJl3^$--MG
zu4esv7&mdrY5px3av*>!0Iy*S4bpTqNBX4w7VaY4%O_>@C2CY0e1S}+Et0gmE-r3>
zl`tPhfWO5V|5xjpA5~t<vn`0uRf^w)<L#Mt6f?Y-C+eE{Ku^YtUGsrF)gErJGuHO2
z4A}XV$-XRHB|w=j509@_It#_jTbbaX7?jw2G_agnf=LFd_2fMvl3r_zuBMPooL-$4
zqHL1$^o1yY;KMeK!OGH9=~NOMLnU<)OKOTyd8BWr4+VJdoV0@n*jy~@3zUxV&OXT#
z_IMY(G<qT2=eZ~IIN3>_nu+_Y7d4V8AR+*~(=I4b;PT6Y_#I+{G%|&UI@7;DWAgj~
z<Qbq`=GSGjLh6_K4B=mj$&)bZh=bQjGAh~-er9C0_-+f)BL+OonU(s@-EZwLN?C;n
zu{4uJDK0-Q>^IwZ$&_S;TvGV($HJk%FmE?6ge2idozJ!I2bJKH^@re~`=&}uNFVXi
zG<B#6U=6Z?8fXD5tX&bHWc+h3cjW#KHRIEaw5M^u@4Ps|u+p_P!cj>hK&(W;cP^hX
zdj53>?Vp60L})JO{vQz5$A_BoKSr><aC6MGsoOhYhg;p<-H=D{6g~u|<t4i5(Ufzx
z?&H1l&|=#+&)75A7hY$!Cs*n+eBf|+7P{?oEEJaGaQpV{^R(Yh)YIGTM_aS+l>B(v
zH;<6r0233FoBZ&UDAgr-vn2MbtSrC1#k`?etqs->ggGz$ufg&F!VL<;Z9C(<Mq>J^
z!Xwsr)e4P96Kf*9<a<4$yxulCHI+qkx3RP|1|85F)g^eB1>MkE+@yzkjvxlE^YWsQ
zhA>E-Zn?3jF3oS06d#Wp9vn=S5EVVQ9@S~o+dMWl7FjTIf8VBMKeQ`gee%H%teIJt
zScCs5U9IcxEvu`Hx)1sJ`DSd<tD2fsMRj%BPe-hFnN;d*N=nL-u%h*oq8lYY<0V?h
zKU|XR^F<&KC7(Tb(Ef6J4XjJ)Cqn9X_V&8QhKEHi!(c2Kaq)3zZG<iqi)wSzNbqA)
z_rFo8)C{v^nM2LXmv<!|{Zzq!65Hw0b1Diw0_AUKf}QW76b}U{!s3M;z;a6Q%OemS
voG^F?Z|^*ehy<<zO_w#`DrzeQt-p^Mk|&4+UHA^?`v4$Jtc@!S-SGbdq})sh

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_80.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_80.png
deleted file mode 100644
index 8224e7e1e2ed8e251f37f802b14ce4ebd9027f35..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 2252
zcmcIm`#Tc~AD<a*qgQKtDYul+If}-J6*lBjY({Q-mCHd(?vq?1Gnd>FxlS@?36=X@
zInBzeA|^()&Arqt&XI8%<6VEj`_uV8&*yu2p3nDrzR&ad;q%RM!P)PHszLz(z+OiO
zTUTi%N|6qhmu4<=^>1mBA-mdJ0~$xvze)#4q=PpZ08rWg6Ec^p-bq)$QI59Q3vn{v
zDz7>rJQ0JV2F;BMz@XAh;=j+wBl7GZ2-U|PIXdochqCe~CT+1+Kl+t2l99=ES!|S!
zL^r^yj1=}8s$=qHQJPmMf^dPD-FyxKD^5MbYCVJKG=A_{D12hPDHQUj$^(tbqr6@7
zrJa>eBfQEW&!tGS6w?_vd&?4Zb{}LP3Ad1ffs=3`v-E11Gu<3Ei^#A;>9Gs$&BrPJ
z*2Q%eiA3>9Nl6j$PZkHVii(OZo12^Om8bd-E1a4>KOmQ5b!lN?LEPHf>MFymV?(1j
zi*25vp+aUBT<?!{`_q+33D8?Hd6r3uxB>AT*&JioZ=%&k5?58&d3kv`F=&38x}xt#
zC*5%uJU+ktR3P%c@8>T9fx!B3H!cO;10f$PDk-s!j&2=a6kRH#(K|bpZ>yUF8H{-$
zNb8bPqfgJ;T*h9t<iF4WhV1i{@Q8@2rD0=BOHEuQT8?!_fV$E-`sPh)si7}x?nS2W
zk9(?H#RV@YGZCxGCy0yiSGd@rk`rW2@wL_KY#0n?DK~p{H{|Z-X;Md)e4<6u(id)5
zgkgPsy|>Otl0+i;D<lQ1P~>AGx<Oc4e0{g-6biL??1%D7wz_gojh=~#$e%zMt65)P
zPdrCERcTMPyuQMFNZq59%;)j$Nge_yu`8e7R`ks0m^5u~Z}+aPt-bp+R65lfG9Vsy
z8)Pyuyxwce$=ql0-#_?Kb7dAMCODi=O<pbY`Gtjrk6K!g)bYmHQBZGN8#xw>?eEA@
zF>G{K)0z-ySS3H}Zf<V=7~D3{-0m!zK%!8HzGR75;ri-y5?)oy$Y_6w!9}R?<q=Td
z{rXj{)7&m&ypNB1D6gA9YYm7G2mto>_RdZ={6{O-uT;#kCjHp>#>H1z-P|#*?wf~t
zMvZ3;*_d$eTO{6gcXuy#ScZ<jS`-Y0nx4m}+j@61UsT&<&JLFwhkt`jBeu?Yjg>sD
zyo0O*o>&*W<MDWE)`m|NJ)`2El9zA?yQ(jv6E}_vxm}|*{zxR!^f8Bacw5Knn)zY3
zNEtnH^1BNJLW?gnUMh~itaqB0&$j>O3g6(?%lO{b*6603F&k`@ZGLX<0XQ7~v=+BB
zzqOxrVn5hI&>u#k$ti2`6rD!+Bg(<S!JVD$?SbY)_cyY&#XFL%Rb2XUG_fz?+Iy@r
zHw>lf|CVMlKliwyqr-$87Z)eir)J8YW#?;J(DXSY<;M0Q(26x)Pq-PK!LWhdIzpQ3
z<6Uvhp8w|49Znz+!ktxWJx?)S(!oU6s%!@!NELG1-Hz^^b$A(0I%?)|kP@tu@dQsV
znDq*(+iKra;PKwKA>`9*8lE{dm~1U8*Xui@a9wjk?hL~BXg6ruzNe;MHa+j6E&W4z
zH3Fpi&$M;+-uetHieaz{11SHruC_}pWLA}I>_Y#xV8gQ4=SXS+WIGvyW;{5|KJ*w{
zq<xcxT<*FR*>6~#*(Nic8G~G$z=CKP@)71Qig_g9+blrsN!0HUlpgRNi+xL%eGeQ7
zwbA}R1ZqN2agZ0dD)`A#QGj3i*U+1+)j1(|{4-YQXYB`@Ey|l_ZtL8>TV8D!Q`w*_
zcG`^&A^N2wxvnmdY7AGM`sXM{`&Yl_oRXCJF7YeVf)#XN3n}6#`=fEO$bla85B0Vd
z{>ZORf8t_#H$H$UgQP9R3nj<chhE+Qm3S%qJSQ|k%_n81yn+Ih1g;~?f}ibh?zChf
z52$OTs4N(k!NGyp3$}=txSY&mlI1E;{JX6K#YWJW?_S#5qy}3##aNgmCpu+Qi+?Rr
zpoRDXtE_ZOpr{0cG6;^<7^N>;F8$V66hKlJOvgND_w2~){~CQK`@epOVsmJ_EbBY>
zvP;^oN;M`Ce$uA{L~|QuVAM3SpKrhZC27asX<r^R8>q2x>#UrD9O2BYWlBC!1Imo+
zqDaMT1QVO4@R4tH%vi5@A0GKX04Gd7@y0&@>4qAOJt($r7d9{Rh`NIgL`PT*kw~m)
zAH08QwL}c5h@Q&REbXMd{k#N$K>7^q%2SV!#$LZE);Gj+VtsBxzlw$R51Y+KOpj+w
z4uu(n@!PMAo2yVWr8I)4tE;OHXZK>%q2Y1XQk2K<$b&nNy7dMC0|Ntt{9Ge>cY0Si
zUrfegDMQzP{A)9h*|wUYr5!@a<+6=})KqLXH)9V7J9|)}gSR#GzOStbF6L@N(U~^<
z^oE)mo%3n@nVCa|qK?QgWv}S@eq@q5W+}Pl&ZJUyD^n-n=>CKVC03<x1<w`d?40D~
z>swV?R#vx?s*~!m^{BCN=RFCPy?P_358i1w*DHEfUw?%{48Kb)uW9w#6mTBPIXXIC
zoP(mZwHcg{j)!g0ZWgp!^ol@m?qkQ*DJ66z&SyAn;FakCMMh0cO%RnzMY?&{S$J63
zD`5DY(r6#A#YZ$r{e?3<ZHW)xiG|A*^ar%84_8_3Vt;x`7`IbWR9LvCSn-D^y#@P%
zP%GFlQ12)4gMkeu1f?Bt`<|1;3P}5;t;OHkY)vL9OqWfBi)QmNi2z1NIp(VK1oinY
ZV8c+LNiLl1kbWcp$Fn%wMr*&+{{e&KMh*Y~

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_empty.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_empty.png
deleted file mode 100644
index 0bf35549aab7c7c0247cebd69a176d68ea67387c..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3379
zcmV-34b1Y1P)<h;3K|Lk000e1NJLTq003G5004yu1^@s6+raPm00001b5ch_0Itp)
z=>Px#32;bRa{vGr5&!@f5&>tQ(oz5b4A@CTK~#7F?Oj`JRL2>f^{&BQ8w|!ac#Us(
zZ5$^?1Z>j)?L$-qa*G-o9;o^hsZ|qIeW==~eQVWLs+x!Pr7vxxJXB2tZ37036o>>Z
zQ27EVf)I0AFLqsf*EV(lU)Ptl`~An9&Dr&?&)IXEiG6<S_{^EhKQrH%{pbJZa>li|
zxX2u`9)S$&vv6`C1RS7kY6lL`4$w9sU{f|ui*|sv2?3k3aay!ZKznS;CuKJC^Yh-}
z;o+v4nVHQgBN+(rdcA`M1qHX<ZuhJKHinaO0~&@>#_ij;-@bYC=C2kO7S<WA$qEcI
zGc(5y960c!nwpxwt`N=AAQvyou)V$gojZ5#ylrXi5||%6c<{}-y1G9lc-!*GMMjT~
zj_v};KeeTXicIiwe;<iNwkW)8b8-<K0|NtxP(zno%c7zp*4Ws{a&mHHFT;0;Bi7&F
z&u-kf!J^Tq#E<%e!NI|=R#a597|tL~23&w1A0IE5%ej92de+?B%+{?lUrguc=Q9$G
z9UUEVc1)Rf%+m%37tx`t7c>G(K$i3H`FygI>zzB$85!0V!D{|m-=4L#)LM!)5YMoT
z9vK;VITQ-LO0sWuc6O5%%wV82YKdn>oIoJ(U6gsR2HuNVSy>|+Hf-oEEiL^hFE1~k
zAx+9Cx`FQL>G?K#^j|-H`m`=3cL4(cawA>o77dzF`@VhqepXyud^O#)6hCdC(Q5N9
zU%vc)Utixh^kn#DO@m+ISI(b5|L@w`+IL}P{xDsWJ}ntNIXPL<($dnl)<9M^j{EoT
zfA7MD3m?zT&E+cn)!dp*a4^m}ckbLZSamNaGNqoKj1Dq5T&|cMk{B)NGwHg!ckfOb
zW`-yF4#{Xqmlx^ZQ&UrHXlRI$@smhpWo5004<G&(>bpEJF*2St1AX=C)j#8Hem{}N
zjvYG~eo8DmJ3BFGRXk%<k+rq8v4;;IE~`&dQ`67UNPf30Ac==2pwW5kIeq%{4Wy3~
zH5jB}7^F$UcJ+BdTVYqOT#2ig$K#neapFV`hGN5U0ZAS-b%q!K`Z3bRfs7$XT_8gQ
zNk2*YInvLQ?((I4PS>5tFI9S|X>9LaE!tf?TGiFn?D6Br?C#yWu>g#n<aTv+{h*<t
z;g>Pb6b@CO!7Qt{xA!$=dK#D5zkk2dOSAi6Lj$|{>8H#MS)PH5{xTre$-VTP#0~DT
zc;uq^&(l$lKrKK@FU3=YVQrAoe|~X+J%A{f!lj2GD%hh(kEDhorw;~$Crkl)Y;4R=
zZ%$@RcXR~0$0s)D=Cb#hn;pl+<V8~QU75+sfpIalKHLS+uWiv}Qzc~yQNhZ~%h|nq
z_hRACo;}+Me6kTX9rH}$h!Y1%!r8>cL|LLgtffRR&CmXqUSi!b5H%+=B_at@-_{~S
zypq)&7?r9qRRtPjx$6^|q^rUy(^sSO?9R$kdfDa<;RXA)t75WZd6ErM0VCB4sRF%X
zt~vt!em@Ils&)-JIIAZK1L)$4a`lK7#IPM`>b<+?_)JKLJ(;YeqQU|g)mhpObOkCp
z9Eq?=4$Fl@>(?<}69KjZO{!s8K_Lrr=n%uuBi9Vj^ds}{sN@24XnuZ;0sZ2OEWn{f
z56wi@7SJ`&rGuFLwv$Gl_X(Re={H!6l-G6{O@$>DuX|mlk#eV<mUQTnEnL>lNM+>)
zbZ~wyZLo|aSh5PY8ew55Ef=6^3_CnM&8BTs@g%FT)R<Lh1Zgfn)9R!W%&gd{;z>YP
zRvN*|P+BfPQ;Gekw4Fc?W@a)UMjd$(H=wJb;@LTh$I~jLm&*@mQt>QU*qExthA~^f
z%PQmww4~x;?7=PyLCaaYK*J=qgJ}M62m@Jb66mU`DmE}Z#b#_!@gC!CdfaZdapOii
z-fPl4xXEZ*2U5IgGkavim<MmGkdWsFG-d9`Y=<2x9?h)yw(_$I`2%f}iWfpneH^Vq
z?m$<QiU&i&YT|7batE4Jyg-)q!=+*9>m^u^!IQYkXqu=EMy*%z!Wfdp0&<=>^X&{t
z#rq$Y#?D!+;_<c$xr+{3PhAMzw#Q->FNB4aJdG9ZKvMzy<rS8ycnkQo3`eHdw&;+6
zu6x1KiP|A#l8w$V*_t`Z-!9_X8B!&y>+4w%t2C`5X&D$M8F&+aplOMig({w86>i(c
z8)v>+2i0C$^oVuKR*_^Ca-3O_>&3lA6VSbrlWg816)z0FK8|yR!T?R3R6ceA^vWeN
z`5uB;Dsfu$5~}_(>qhaySc}cuDx_L+7adfHYN&WtP1J_5n~1luA`Z~IcCnz_ns+XO
zRVWP5(nPHVJ8z?86=Fq{BRc3+gRD~V2Els+HYS<*Q7oyzI{sPndrh+-1a!~TB%>B+
zCP@SS_-2y`Bm~g3W_hF6%lb@4WDui*#asDXg;XsefTn`@F{fwtMD3DQ$ZrKH)k`LE
zfUd1IUB#2ELM#y$fy4pY0u@iP3OUby%P(0NplSXvkgdAYS1z}vdkAxdA{Z-FSYd!(
zQt`~yItHP|h@e9Y1vItjM_7wTQ%`152wS0@7M*}5eZ<O(Ef@U>{(2v2*mWc_<Fx2x
z0Gg@d(Jrh!Z?-TW)e=TV6Y&0>J58IYm8`-oVpxS#H?e>w6^}l!WCBT6p#XD*a#e%^
zn!Y^NZPF;7WEGb4+l3_qEZ>C!T2k>`=4c(#?6)9RA%QI(&=^0aJtsyfgyGSW?c0sA
zF)h7NKo=GkvP>+dp`X1`3Sq8L6djuCA{5Y6AU|568S{tIfRZ5J_ZJfAYN&Xo01c~9
z6!Tk1p#7xc(Kj&-&@5#9DE1XPK(7E|HK}-BW21Ov73O2@HGM@v6cSHHWB$-+ixz3F
zP=3)u0^N;KJR>CO&;oUYR2SiZ-UhSTg-_X&)}WV2bQB9Rvm)0)IH0LuMpZll+J}uu
zB9WLtqeC<@BOc1e3eu7ik#H7IbPzgADxQ9vLa;7HvI?mtLbhm9@d6mM*GpmSAaH=z
zfZoz5o_?bxJS&z}NL3cIMbic%><!dI5ojw<a9Dy!R-v#!6G%~%ZdiwkM;b=~wrb$y
zWIgZ6vNS@rXgWin%2%Rma7nTXG2AK|S+|qYU`=aYsAX>q53@~ZnK&9p+AU5d%mV(=
zoqTB1oaDwoInE?Lh}9s#F091r3k&og-+NCwpNdY2pcYP-R`+&+W>#dtg$0`Av}hfg
z44R(1kTP0NMMO{I0BzG75>|BJEL(Q=>{)3>oMy$7U4&6Ge_9`M=+GgXAk>zPus{>Y
zzj*U4*61O9co8RD;siJti_-mh-CX1kx9msmDVX2y<mRydLSqq$ga!KisZ;DHGjr^%
z+4R4Bu){UUIyyQSPCXU|YawMc9WMDXPQz^0IYMxJHp>3~!3V;COa&1V=xf)mu~LYP
za*`D~==JCV`=<l6I&!ToEvy-f$o0}b7upX#^G4!B6cVyUw|@8`YmSm}t)E^OOne9j
zba!_*8yOvCuSoiY0iYp1{vnX~5Dw_p)>d{n!y_I3s~={@NPM^i5+C9Lee$Fs`K)|7
zB8d;7fF2(oXaBi%iybye89FYI_)rBJ!;|S-49aGehWpZ`OROQ=%kp)qb%|Lu*(5%+
zV5DjpdcEFd>%yn8D&GnsZKHl-lHEp&rngJeS#&Agq>Fsvzo>A3;jc_n7MYif7qhIy
zWOYx55sDc{szBqUhagf=U1P0(U|=AQiCGVy;b8N}1^Mh!hMT$ZjU^iBchiLvCziS4
z7xS0g9+rVL<R@KN+mQi2K98GuOgva8vF=#0I+~T0^|=}bsz4JHtdaOvC=_~CW;Ql9
z#=5$?SRKyzHj_F(`NT|irt^|i&ykThzLk}gr{g?QJj7aQig3xhwzl>!iQ(<-?d-{u
zCyCyx_L&;j_3PJ{)eqRbyUa6*hbEx$<?>TSMMZ7O^z)bmZGovA2n3YgtJ2-m)5Ff3
zIm2eLFh@yP=<_$=(y8=I<#uV^YKDRMS^(RI%$6P6N=t3aaaaL;jf*BxR|63)Q!se?
z`uZ5e=CUf~=H~VuJ9exI2lvpyMXID3XyVl0-~aWC7cZWVMx(~|KByK;><H)pKR<f(
z=-2Q?hR?K?G%cWs>Cn*7D*(GC5{VRP&15yj%gf7qc;v{DZ{nVo%uE|-0u8!kQD<l8
zZy!8(@CF`NhpbR(4Nxy<>+9?PuxHPn-(b1fgi7>f!McE!xu7Smg39w9QvF~)mnW0o
za@;TD9jfgJKD*pgT3Y%M6oQj5Oz7i~y2udFx^i5ji8QHqYZMz(tL*@7Dx9gAIY6hz
z#?%l8Xj9=#&CCHhH8!S(I6#{UXKH2+(5bO8HN*khR5(*J`#(wEYSiHa7uNs)002ov
JPDHLkV1lbxPcZ-h

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_full.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_full.png
deleted file mode 100644
index 495383be5e346e624d7a92670fcf9ddb053f99ef..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 2152
zcmb_eYd8}O8y;=UYEu$96e*O$oTX(>Er)lSQ(lxgWEinwDC9Uoq(+<9au`x7=9J`=
ztb}6Dq?~(=vGmGez0KkE{r#@*y52wEkNdf==ee)v=Y2m<x;@4U3Xz2X005|sHOg_1
zuk0ZOEV5U>y!rlfkAz5$Ru%vzTb{euh=o|YkpKW`iT^;zzi4o81q`)8nP0vs^sT_t
z*2zV_vrp3zQQouKH}{xzQ2Xkpod_An(5XJSpi35S%H*{tm<YU@q>DC%V|2zh6Uf0j
zCkA|F*g-1rh@S4-6|kd+q2bz~&V%N~lK3;h-`O3LHZjlng-*ZJgX2{L2z`xwzMyb=
zVaupBo`p<0eFupCDYnScN`y!V0ih2>!LsK24gs>;GcEhgfC)J5(nPbWeS=YtdRQ!r
z+L1ubyu!k`C5mWD^;?|o<QX-!rP1Y$m4g$>1T}0mYVPYsbOaO%^@Dg(EKgt!QoiNT
z>4ByZOT#ggG^f!_FwSP{Q;m<p?ZX7^=}VU`S^fE@xZ#k{<k%R$L=pVjOPe)L%g;A9
zH87yUpl*X1UGl*-uFuL}nH9rxll{RuJQb9yRzn4g1}k0AvT!%G_be3Mc{EMV%F6l?
zE7**!gFtNIO2W}N9Par9dRENBG4KqIJW(6{CHd~KG-##Pc)ih4;C=mP+r_PQ_=)qz
z_kF{c!{&*UNlW?gPsHmNO<41XJWfug1-&#cPc^pUZ*IOGoSJ%ll`in}^E1SA^;^x(
zjE1=zWd#HW$2K%KH(U3fMXF2a>FPcX3kxGSySR9E_4VyK^>RW5Anq{v$&32>5qZ<N
zEwbEMf^nyh)|ZMen=_sE%&N`NnAH1?kNaC`G+LyAp&?yeO%1+w)29%@ixlL<@K?48
zyF1&SsgS%UZz;9hr6sk=M$&@a#>Pf3q2X%ZXK|H&A0HpPTq+fNE`De0VTDCa*ex^~
zjdgaW`Vt82E{Pn@Q=hmvld_hUmJ9TpBf{aY9%aC=YLjcbzG-vi3@9R+dHp7Gk?9<;
z-n(^UfVFg&U2Y<JVyf+Fu}gr)wsX<>8!N#D7**`-GpSyNxPr-60EtA3Wpttt7v%79
z%Z|eQcb3?2iMbZDF2^F><IzsM*t+qF@`=)*0btXUC;nEUp{veCeG6wttP^sSB6k=E
zRPr?mkk3)0p6z&j_IS|CBp#0!x{LfkS1_7i5!F=1<QvI?&#lh?Ow@4bZ$p_@{e3u_
z!_85(JHASUdN}psb3gia_4MSgKiuNRrVp2fBQTH^{ok*4C|k%Y49G2nuh7um-m^1r
z-n@xy+$paNv=oOzgV)HmNM%l^0#1x^-`YoO-Rhi?k?UeOf?HYBDec@}T3UKl7`v#C
z-349gutd7@8i><V6;cIiiya*o=Yhq6Wh!zVg2NADb053-K95HmpIlQt#F0&c>3NMK
zlV~={Q5lT42V5ijB1{qLBPc`FJe)#k{V}_OQ)j!6l6u@3H-e(5Je!ydHw~!+aTC#$
zq@6qGB;ozBq&A9R=xfil8ZYe?hMj~FM0(Li*PO>}mJb^s&duIZN-@1{=5vp6NdKUa
zqD&7S2t@&`MfCpLp#LH#nvswno>?<bQQe4uh|u8ft)Mnrb~Z8Zd<W=rjXwH4l6P++
zFQ!2R>W7SEdW0sfU~99N`Bh<JmdzA@%J*qdXqJd<6!0!15e(?|vOI}b6gJcSV*o6h
z2DpE~Pd`aS32=%m^Di<KNMCjst+Oy0CtQwghT4Oxb>B954_;vEW&B9QoKd7MbJbaM
z)u)bXu@ZMW1~AOYZ3CFj5I>&{59#Qo4q)1CT0Eq4y<W&g(WJ+`?g_^q7|#oJQ^doA
zc$Q##flMwaiNktNNM`)s#vw>=8;Ol~<!FvXW@IU7P6=i)7I96(o$+zZg@Tm(y1qS7
zC*3Vm&bOMra#Sgo^V(m2=#$Ycd?B$I!^}MX1DfrSs%hAzV>!Dz*LGS@iHwx*LnPcJ
zCDNo8?tEbxj1Q(5L?wu=M)@^l{$`IoqHg41(r+%sfvlKpUID?c<;(OoB@k_A{oGqz
zvkFMJaHNSq<pf53He}TZ-d}PaHFDZ;;ckKW`ZdWMNX@d6KhK?Ufp^`VeiF~{b^%om
zac`N$ro-|S`43)bJAzsRh91WYi>0k4YOXr*HBZ}!`bb)%j)Z%7Oohy(HSXHq0U@$R
zehnJzb`1^<eJ?93o8%LnM=zVBF_GUsM+B5{9ZgS6aetD()n~lh7W^iWJUl%7;_n7v
z)zc(e&(iYp!+pKSJkwBrwul{HRF_>Uu{)L3NA2E=#IcgHUAmcqQOL~4+S*!m^<#JH
zl0TVBrR#sF@o0fjdg3e&tIu3)uCK4JR9060U2}DR$@?;-sEEi*bhZCp>;e&^xe_Ju
z=87N1-=8Bk0e`vgk5Jg2zI4O10FI!xc6WC-`qp1T>+0#LQe((3tQqxj8dB)8cCY(|
z_2>Zk28CbE5mjw%yHS-Bw4A(oFYYHcn_XK`QIUQVgtfQV#@CJiaBB=;bEsLWDk`<G
zV~F)UMetyUtvl|eN0q1k!(J#X_3f+dl+o|>1w7=k!|l}6HB6DoHYO%UutK3wD%&~4
z6bDIzy|ZIG&*4l}FqyAI{+emmQ^`puI)uoQtQn<gZtt3(ao6E<t(l21MLfeC)&D;o
bw6(vwhAXL2?5wx<EdXpTVo*#AucUtf=a~RS

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/battery_unknown.png
deleted file mode 100644
index e20348f65a39bac7c0e40a2a4c0b338ef018dc03..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3138
zcmV-I488M-P)<h;3K|Lk000e1NJLTq003G5004yu1^@s6+raPm00001b5ch_0Itp)
z=>Px#32;bRa{vGr5&!@f5&>tQ(oz5b3+G8hK~#7F?VV?A6+0GyPpAn52mwM9y)2@K
zC4r?00*Ky)04;3=D;BMm{<Mf9x>g_oLi9%vqO5=)KxiU}_TV8UR0$+PhtOMilt6$$
zV9y!k?A*C?=Xx@8J>%T56lPrJ*#55Z*vH47h#x<GfagL_ph)Pm@Nysm9%w=Bzys}p
z7DPZ$HeQSNKno%uC>yUu3j$qCP(A^(`S$Hwsh2NbCVu(yrF_6d79vWOD)qc##fq1T
z7A=}<L5$@`9RrOMr6O0ZT>0hV#fuBSfB#;>a!m{b6fa)<ef#$9|JATz!)*r1LK+p}
z)XXqFJ$>2Lt5<&sY3($^J9OyqkH(D~Z`1?}@jB8+zkdC?IYOQxq=u?Y@W);8`Sa%r
zsvu#vj&vPQo;>M}HH=`jjEjqdgoFerUAi<2vV6tv2p&Iv3>Pk3fV{jsMIOBmo<D!y
zv3Bj+DV8%ZDZmlX+1c5(SUF3UED61P_l6QB?C+*yV`G83#&hS+vFt#dcYdIN8%Meh
zb-i#z5E95Nk80Jbv0F#4j)N{zB(y~cwS3-RFSNDfEkzilv)o5#Wo5-befl(s`o7%U
z+!!8aI6+C^Nf(MVw{PG6E0+1s9I}5zMn-0pDN`o1MvWS&<;s=2&GAgYBn1Y2|Ni~K
z_(os!_U+ro0j0Yz0wE{RpV^|}$SA!{n>PQhTD9sKv(Hj`)1a}{mOFX!<bNMNeAuTT
z8Or(${x58M@ZiDIjT$vd##!b+%}(h}_0b<ceypC7l9Co~kkyUj#*G`}4<9~!?CaOB
z(dzJE_uNx(6kPhifdjwetS(+Fl-}$#>7WTmL`42PM4L?4Ph;JdEnDiw*%65E4rS6}
zRu+xFb8>Rv#fuj}lOL_CS+nM$9zA*t!20?}Y7?WM8}ykoXMV+B^Y2<2b?epz{I3L2
zQBm5cLg7cPBBZ6I!L3`j{OXgKm^c#~$x^=vod7P-`0{AAckkW{_`FY7gGw4eC5?{Q
z!WV?26*zV3luyNq6)W~(`0(KkQ5E~lCql>L15PJi2|@+XRJ`#?iz>&kflLq@G-v=#
zn>JN=uzyf@5}lEeF@gDwu0HVe5~8rk%*@Pz>NwI%v}@N+9TXP#*i`_wUZ1+&y?b}K
zPe1@qP|)w+zpqcfoceiu5rkAfq0Y-q_t;fHty=l|Fr{ek-o5)1@(KEa3JUtehYvNi
zmBrbTHYjZTdUZ!eHG%;M3L15}CAC7#4&k)V%k0-vQX!+rV08)#I+y@2o{xYBnvav^
zR32!{2>Aqfp!qmiPUV5NjF3-&2bzzQ<y0PM%Lw@dc%b<>Sx#kog~f7?CIz5s79Ko!
z0H{HPSFc_HE<OOR-$D8E<@5jQ)Tskis#Gy4S!{CGfku-p*u8r<q^71SYDrSO^Ejp#
zCuP@w0RsTn_IMr>mc})pagi6+tXZS{so_RPM??Mk^_3P&trpknl$K4cn_4=qz$>us
z-Ma_$w|)C|m^5h;3>!8KrcRv-ty;Ab2Gb}bSAfRFUKl-kG@wnMQdVk>0|yR-{{8zy
zmo8m^%*Fya)RhA+vBA1^>)_e5pZa%Pc7q)|b|`-%MvQ<B8#X}MvSkB_5EAbA%W&Sj
zdC;v}Hw7{QB|n-nDBybb>}d#@2sLls9OlfK1J|!#hw<ab`$5~eb0@^d$HS#dm;B;H
z1~>|O!GZ;_aN$D55V3RT&Oohm{`~nt;pzdR7v!c*n_$8O{{;`~Qs~E|AHyl<80alq
zwkS}k;?zAHJ9Z3cdCaP#ejaTv{KU{ZpiiGZ%IL)}Qb2$spy_2dZQ3-YdbAd|XU`s>
z)eAcu$(b=j-^QJ~B<h-+aE^eUHER}73yX<~fkTH5DdS-~D^J6_K#sZ>0xsGK2Tc<W
z8Yhz@*v*<XQ&yL$g_GY7M>f|qiP3X3BH6ZWn_g5%!-Rw0zkk0nyJNLNTRymU?Ha6H
zxf0s8ZL5rpS)7$?g$jYUsvJ3T#ER$wJu4hEZg~q>(3>}J!sgAJ1IC+)Fd8@0P*3!3
zG~uApK+=%ci4!Lb<9Q>EHXfmQfbh|WaL~B9(vX#1FDf(vFwBR#ERjw)Xqw3xxh74T
z7)5i(q19`^v@`@1t#lF&dg#!hhI$852-)F`K;u>k(6i65Bi}$Wgo7rNs;yhM`i-5b
zl`UGd2>SKw7pSb<;b^9%*fj@wfXs|VJA0;MCQD74xsDw>0`49FG!g`|<s)5(-qhKo
zXeBvK=jnwP$c-I4Hc(W^!W{ukwV`qDxN+k`Qn7ve_63w%uU<V!N=gbCAF2r9T}P-Y
z!sOzy6tHX8F6Q;SZrr%h^!5)wAq5C1RG`tsSovR~x95b|Oq@6ox_0ea08G{&DKwy|
zPo}<~blQ4u<j9e*di83(C?R2m2K3yybN%+1FoLA8B1ICdH#+4Udl}kU;p4}T!?I<|
z{6vz`I4v*?88XB#PIQ3uplLOH)TmK@djUyJN{hDI4L+g)v;3q6O&Yi{W5xiUD#Pld
zTxl`(=+UE4sZu4Ma3?)d_tB)o*6NnYfQI%1x(PD<z|yv8G7%#)1GS^A&eW30=*DeM
z+7`Wb?OOQs=~F&WQWW84cvnKELP`mm0265D@BkA9vRlqiV&zg_r36jdKN@W?w`9o@
zWs#Tp-FTG_G)=EptXPrHlC*$RrcBBAyY)so(9{ppNdx3)rk9+YEL@3SkRMYz&}4AK
z9GT|YVMfN}h4LyLXm(}>ZIhlodv++<*eY8p&~(-)>o)rK?JL!JAyR=RgLUQx4<5{J
zrMOB3THS5*>eWjMz^sr`foA4pv@fM{<;tuMQe341%{CEr>eNXJxavYm1DaH#Y&PiT
zskR!f`d%8)Z{EBCvTY_O+MG)btf2SOfX1^y^XusLU9$NFRozGfns(GO=QgE2E0@t#
z8qn%WIJugwE{B<WDM6d5pj*;P30lVE;G_YqhHJDx#VsvZTMlVJ)0Q@JbS^5p*H*^O
zerZ<0t5>fMr%#^-vOc0ULfM=&pb4yuQ*YKFr0F_Xfn~jVpauPM9%v7=AOeE2@mjP8
zS`Yz2*+|i%X(K+ZdXsvT_9T)8|K-b<1tGF08`py-)7<XeyDLVFw3PMe(Idcb!T^3C
z4A!q-Zx00lQd|w1PIDv!M!mB&XcyMx$&-OC*a~1}DGOJFUb=LtVdZFPYx(l!hH2aq
z=~~caHOg}+AnlZu!MPT+4Dig9(Y2uIJPn=$TwAwpZKl4CrFAW6A~JL4OhYhqY|!-S
z(+$(OCDPTP=@3{l%~h|iFmQB`%BoeXphb%oEXdVYSA!;Uix)3e&Ml>LMakZdc3+Vt
zX?l9Pa$13_>8c7Rh2o!%esJpe2Nf$zx2|u|mTKpshdt1Oehd$^2U-vTLD_gM+5;_!
zfS_!=7VUu+L_knBL0dFVf4>VVi?rGBFbWD9KREvL8%Zh*>H|qs!C`T$S9d)|S{Ok=
zqlxTYe8{I&vrjE)g@uD(TX*~#(rYxj{3BT1gMua@xZUhGwIDj0G9x2H9TXP#ckbNr
zJF*^+ecQ`Z`JkXl2p%`QNh^%BXS5|PTpTs7vuDrxRTtSL`vvL*aDm37fOp5m#igmA
zr&VY=|CyaOppGkS_w?NXIx1QFT>$+2-wxz*o~OPMdQ16w58}sY8X?#;%q&J5PlhdY
z(m8!8LQhGrO)rC=xa8#I0DWbHeKS#AZanfWbI_nciBVBe|3BPGoj`NX4Vs?A^D?^O
zxpD{d^77;}xz|+OiWgsif8Y`Monm8Sukp$;1)7ASwa{M>b_#B=jN{FuFr~xK`Q5@L
zw!V1%d9V{_<xGPnxj2@LJAeNCfAC8{e?xBsXI@e#!&UiQ{I1tZT$x{ti^9eqdC{q9
zfj~1k_$IE0L!J@Xhb3iaXV=o}zgb!tuQ;^L!p%wdah)<12L!utV&Z$+tcgll0&OCn
zuusZ0ybF6uHURKI+W?VAga?|3k_~A*&^AEi5#fR6p=3iE53~&sc|>@ic_`VC#sh5w
cL>>|U1A{WS@`N`;j{pDw07*qoM6N<$f>IsmaR2}S

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_disabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_disabling.png
deleted file mode 100644
index 667c8027f2b902f08f8e81d3120599a5ed151d48..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3303
zcmb_f`8O2q_n)!U#7qg<vW`KC$&!65hFR<tkp_c?WXrxa+0w{9q$ES7C`&V=NwzSA
zv1Ava(jehIMH6Fr>oec~;QKk}^TU1abI-l^oafwopVz%N!^r^&5t0!C000m)3UQvt
zi+Pj?I>0;QCqy%O3>a}9X$h$NAp3(S9126ZM*sklqW?!g|FTh@3pfjnICn7?_z%|K
z?jlyk-23nNG1w_}DQ-}g=$y4ihM=#3k3kWAPis|SO><JOh%S~Tqen$%Yi@e_C`)9)
zG2<w4YlL%$i^f#crfH0vPQ-W5kYba8f#NND8@Acj_;*wC4tYypI!NEf5)><%?Cogd
za6^pmY!b@G^p_zYLMPYC?vMzR$S;pfLM`1Oo&-XrZ?v;OB23f6+A2<;upq9nhm))8
zWZCrew6ma~pc1<qIp3Ol_Qm;UgvlCr-G-34reY-}CBcyIpiC;B@XD+0aEVdG5@UIJ
zS%ZA2W_i?63v4(|h-A-h54^j%yHhexG|M`f5<EqjFMIs>aVXI(`M1I;bMt*4JRUD+
zawBU`4?$C~AQWQk?5<cX2+4*UO-8x7O|9DAhtqW}wYU(5Mf_FH^2qhcI&4YRQrnfr
za1Fx;OQL~XZszV#nZ<NN=oj&N530|5Mqy!LG?hxdc2~Yo_76=I3p?^thyBv|X?pPQ
zr9pjj8<ulEF{QoUe<%ozM!&(_Q*RuPLm;~94MIPsZO~R$4n@T=6uqv2i}Lck`-g@k
z1uv=J;p0n`#b;(_MksxHpzZ7GfzcU&F4npgsM-g4y-RfNl`zUkZ?C@eDrn-RO9WH~
zPi~=S4qKfW1d8Xv0=|DJ{TsFx7{`~@tew??>Ov-oWv$PXE}YwbTRToROE_R;^s*&@
z1QxD!B%5YLgTFksIyhP7tc+BPmyk{NY>lT@Rh_6jPqw)AF0~-FFH@CCA)P)l^ZMF_
zMzPj|0KP=x!bOZqh+!P}-zR9DXSGoCY?r&4vjWJoo<A|OPAO*#{4mMA*&<pgfcyc_
z<%N&pyb`!TaaL63Wjw3gnqaSV7N#qBTu|qKVqgc<tUJ{Awy%*PdHs>8bc3GJYyF}m
zHED;Xipt9RsMSg8eCM5d<ERzN%0zX2!WP>-{mi8uzdZ`%xN+nO*1=GzkGTyRA-9OV
z!McL`PAIx*xLni$K|8`m_j_TBCqKX8yKxJ>`9b|fn)nnUG1YPpT85aKx@e8%ZK150
zl(1$}<BIXjo8S^#Q^UlgC{YT`Bw<s7r7thODpTv`<dpZ#Kskr!?7N(^XbCG&hJH11
zKuQ|GX-}%V7I3SRwR}(fTTsAh(t5$jT1V=^mjUkQXva>uY7yWr+K@n|IPPdqei;QP
zEcva5*7Vkv7W4Bny55B@PV@`x1${HeF$6Y$j8*#BvfxbKXX*UhcFQYBCYhsM-qc^9
z=18-;bNJfiD-+o6-nOnsWB66-H78qF4b%PI_0^BBg4U*}4+WEc-0tl~+20D3rz}6b
zf4_3mNO6w;xrztP?@$6~IUld`u?{=)I$JLUmZ$0U?ust&RcDkoERN(VSl|_l<!@A0
z&(g0;c6M3X68$cNw&%BQu)1Hs)p|31i~JNnj6Snn9Qi@$Az^U1$02|B7o555joy6a
zHSRjAX|+p(nV0j~K1xKiZG8NqzHc{pl7h365EJW^H&3iGDdU+hL&66*-MI>(RptYv
zp!IL>o5p~R6oZ|O#r`K+T6j@;c~1^}G<8^W`iXU>)Ob)9QJREpiOt8h5wI~jQ{mw-
zDLWk{)A1yPI1Zg&ha9pSqMq+BJjwD|9$at!RG;rUpnce_1`!j->V`bd7807l`q+c7
z``V;^sbe^;+rTt6vrCO4x=|v`(;6<8Lp5=~m(n|TJOE1QH@E&0qIWpgI-{Ild75Ey
z!-BqB0E>{(^OvNWD`{8zF}0Egn*+aOK~PyH1q`@~(0!sWZ<X158g&BdYGadLyzI^^
zjp^t1C24G#dr3!g{DdVmyp4>EFjprcBVffX^l*Pjb@*Z*Y3X3w$a_vm3V!M4RH_rq
zO1R+Bqac}(0j{e3Lm1r+?{O;b+sz#gj)w}-*DWr}SGKhZTk8Zg6aMbcMap?IJJnyf
zR7-f!1CQ}D`LJp3jIWZCl!)&i;#$plpf~v3u9(68(&i|zi#=}n+E2keF|WxeRJSI0
z=1ta@Cp|I-A#4BCa4+ugbUaw|ZES4x<d^V3%ru1F$Co3tJ_i2UEdrN}UVd0r_x??{
z;OZ4Oc(GZ6KI_t^yV#2)DmU0Roqj6dQkIl<$~kvR#k0^a??{t^oN=P}`=>uIX-Yc)
zlih~LdIEQQauqU9mmYlQGkd$WZ?e`SK`~nUDJPE98oQn%XP)>#&NMa;`!=kjRz;}Z
zh4}A49k!XqEKt*(%|rTtfn_l1*NBnJ$!<=`>*-B8MbK|7)^rk(->r@CuM|5GrhO;L
zF%JxDiu;W}N~Lr!KswI8^X<tIrN(cu2N?`TOFm?Nlq19R&gGj^XtJz=Tin{8J@u85
z;>hbk6_YRhhsZTN2=`>(>CGrIWah}5^+m5ubvTq7FVZhePEj0Cs666CYeI}_TaWXC
z(3Z_KCd-f4EASZ^8Ec>D*FT@A9RD+am$m=zZavQljekluzZvL;9ywLK^&4TE<`=`B
z&BtHmMMu;5Ek!gJ5-3vbQte7QsTMh=xI@8pR<wAxLez(0WUF=-EOkC#-YlL%f=W3g
z`RWrDh*u5pcdRd%6zhk~o@n%Cob%Nh%I}x2??LNFty~<#q;1*-{`;QrxYUgTtcET2
z-#;CmUdAgJ+TLE`wIEkcvb<?ZQV%NKm2bzL2M!IUtbo$XuLGPB8pv!{dRN$8S>y-r
zX=6CtVeoik0sxqs2i|Nua72DUtKc<;V)&^JYm(t6<!_BZNZmCyG<*P&In(PTwGjm2
zD=HW;KhT`GO`9=7NPc`~E15nRFaWN0tzC(JBz}&m?0u3sZ2iqrAO<8MDhjn1KdYfZ
z8kKQn7BE)CHC3c@668#x2g2m3<4M7?BGor{H^FL+=&p0^=Sk936QHfWqC}BMd9GgI
zcvX_on)>0JoO@m8NjNznU)o%AjBP)Ej(dB1t9^++csEtb3uhC%*msNx*)OlOxVaPA
zqsY+!@fDH4EHzpFRLE{~%ukF#E$(>+3#SECRPZvY!y1_jr)VBy8StzIa?}g=#wD!(
zA^d7^ug9-J4VncmV1{R)N5y#Y7yw;#0>h3T2ez4^pwV=qi!rp=?az;bXG)}PKRWT=
z$^Tv)8J#+^C}p39!i!S@o4I3Nc;5AZo{%pHI0)IOsi_Hw%TjZAls6u`z~->A0_84i
z=wOK}4yz|-J!idSzf6$z(A^VZSJ*wBw=Zz>xe|O%;6E^CIcf34l}o>l^u*BpSKt$Q
zN-_N+iX`^~D%KV0fP6cMba(?8IH)b%pwIP+3*==ok3Cq_Jk}g@v>nn;7T=x^B*0mj
zWX>6M_mL#OK4lrhFvSv+n7Y~G&w@xrRn_hnX}rlx(BZK9>2d5!fYpaOP{s4-O~xx>
zN~9lvjFvqG;Dg6n$_O3ZDrYGx-edsouqF>GmZNpdpT;WZN~sE>_>KU#^{jX!g{5_Y
z-^j>_;{tGObacUi12^Q8%AIS9>VHv)nGM_cwae2xJ3CMRS^aqHtCXRNignYuu90l=
zdmDgF<bq^;82@em$a^y2iJieRi@#o`I(C|O36EmmFc_Bdg@{Oj@bK`UMEja5b_YMf
zdiY~YOH11Z?fM3Cj31heLB_^%ZIPt;;u$JsU04#)V_4pQpG*#6y;*n!N^dID5B?--
zCXiaDxc3yf$(}RGJH9!mywxuapSvPl;;SVA=5L4XX9M6b7UR=MrHvI8uykQP+1oQk
z{R^!6wg}ek9k}d7zYVuU@A_n0oDaN4wV}NuZH9BRBtQSCZ<;|<lWjs8559yR>iT~$
zg}Qvr>!a2wD=SCD3U3;iC~)@m5IPAJ2M^0GX9~#ao*nWL%l*QoSr`~Jq?hvB>_3D`
zi+<JZw;&Z1sC9RD@81Ebs&>5Hp2)RI2TwC=aoxw2?#;epCtIkIUjCZ)zqhuwR+W;H
zBI4r6=?E41y5x3i13eq@*~5(W{Q%)@$qif7Qi$q_mMPG1eCpJnRk3Hvq-}&AvGfqM
d`2Qj9DuCWlOl7MoB6-US0B!AnsI&A=`47K?BXj@&

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_enabling.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_enabling.png
deleted file mode 100644
index ef2dc5bffa6d27edbb6c6ff1171cd77a5af5c20a..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3512
zcmai1=U)>_(@jD#v?!fG6fqQ$UX&)ihHAKg^aKc13{{#41O)`7B?J-#LN9{!-UJb)
zNmYt;Fqfc!R|G)>ee?VU?}yp*+Yhrlb9Q$2Z1NpTV-8k9RsaCNfiN+!rX!hd(O_o!
z81<1Wl@7oVYhyh?-2`lhK4A$oaR>nb___XPKyS(n-G##iVW4Xh0o-#5_y1_lMVZnl
z=60lAjp7IGqylg{JV0S*+J6_gY?X1DaSWGXfi}|*zxA3GWvr&EzMz4@2-;^oInYn9
zXz#-ml>fKpwU9Hfa{i^Siz|z3f86WCy}e7HT<XVhHgMzE!@MRUl|WAbglCax4UoCw
zlE}Xx5@sB@#EHf)LKOJ>MLi%3=>Wob*wfB9^8vlMEq`Q&u(m8AGxO5(ygb3n{xSJl
zXJE`Y>AQEM`%ocK4)w<^G&Iz2N^lxoJO1tca}}ny&!9@3p*u4fNEX3qDrHPwr|H~h
zwdWT~BW(BNpG3Hypk%xZs;?)YFZ!1?$v*2x1}{H<_~yo764hptq?UJWk-noM1g07&
zLXZj`rY_DgvGPQO9DE+p9>4SqQ%cL2miL(|N=W6C5fm`dx;IywDZ&tI#`s#I_s!q4
zU)+7Mf9tBT6ZvY|1?msJWYEodnrA9SdDJw@&^_u^%w2QyXZEdr#C|P7ub}}Mu&9_=
zGFizx#kn*1S8L?=%^`xdwe^9U3r8;t2MbaHRdaE!!b0f#>CwIR_0gj#9l&q564&0S
z7z3f(5&uP-A&gL2eO8TvH~pU0qh9${4I#1m>(sH_lE97Et_G!YR?(k$RrHisAUs}N
zt-iAr*ur{8X@ESW>f+mhbMVyxK)0DI?@)}>+m}x5Zyy>mcT9;vIa;(L56W7+Pb(~*
z>wSD-t66%oOa-^xn}@i2c=Y;3?k+S|xN-tzLlH*sUwyuG3U-8s<~id4VOc$X)k7R|
zxW6bG-u&JRu(n6*!KP|1e0^!(ad|3UCl}+GteVa#|CoNp?2gh>2>^mQ>n%$RGf<oi
zZLzmwr6Z4j{xCbeIFx)EYkBA>xuBW_Wh7y|rraGQ>1f>$bWI5?KQdl4)MQP^GW3>#
z*CjNbtefgtPDjMR+vM@9{h~^b`Nm8|`b7!xY20MpID{9oOb$^m4k6AYB%%2K2f%5p
zcxcWjtQ}*stV9B)cv3mRpJq#<r{^l7kG}AlKflF+UF~6!bM1*UCo2Ng*^qo?|4veb
zrz#no`=X&H>3aLioy8Bn&dCRVHmP!IuWKC*#JYkz5;3!tR!NJ^-VbflWi2UMd;G?n
z!dlUBGEQv(+14b>0`-A11fj^f+%&HV28Ds@B3(-6MI=Rs-G+beE%COqJ^KAK;msR^
z>gd;5*VWXZg_;lf(n~CeJA(M5{S~3$&%<sn4hmm?KDkdFCEh94V-nDcRxL7<o?J>-
zjXgb-^j~NI(kQq?X=KThgTn%iaM`odqcKi(zZ=Edr{42*E|=wtbC-%(xW&<m+X>}n
zxlubiHSOek!GCUHmsN3Q-v{lGp<(d3S_k;);SPK>Taw_l@@2kWuFkdBucpqWEA;ye
z5K;J)>C0)yEU$@`DEx_W#+5y$Cs23ak<EMd<^}4u(Wi$abIfJqBO5R+3&Y7mO~Y#I
za`Slx?XWjh$Ws4VBH~|NT;z{`lcgP+NLW!Be07jv3J+)YxAuUw+or7hhpW90-4~lY
zOPt!VAQy~diCj$2Q;qO_#!CCR59W%(XzX%_h+~_-FJiFTpcJm@W>;%364>*;(%^h-
zsXc%#bXR(FYs+xD#875FZ8!z>{xrqJRDJ{m2tPXsnr?8@9}{YEA4&lw=`e<M+%&6*
zfHiZo@kw7&HQ3yS%n~{V3cbg2Ebhd9*zXse)s3JhP~zC?mqXyV3`#lweav>I&Pykf
z`=ne#J(PBJYP*-}>6^v*N|6}+;6=d5eQ`2SAQ}91zMkK6ET=UeKre>&+g38xk#DE(
z9n<}p{jh0IrAM5VEECtiGJhH_p%WN*yzgS)gkeE@JE^20adN0W0bUNrbeNvUnkBih
zXh)$k>FG7{CjojVNsKu^mHa_&_Ie+$m%v)x4vUq(TL;V6j=jRnF0dZqV#@@_WBjO%
zgY0mlXL0nkB|~!QWZMR)9V~Q)cy|O-SwGadEM=WCS>Gr@RK)Ae395EoRDBKUP+&e$
zU$>>ce(**?o1`79<-gR%LGO#)vNy}dJn@k_#)Mshgq2;Pzj7?Xsw?oqnF%grdjg16
z;>OyRjd|mJb&NFvGZ!x{79D+C6Rx_*pFY*-VN5+Dt?sRmFun~*eOml-uI$I()-L3i
zF@M^Z;K8|Og#0^>qnBy??C)fw|Im1-4oiD~;>Vi143=!bbY5K>n{1p-@HLw`dgf@_
zRB<p=Ri2kHZcw^z!{xu)1Fb{7g6u7|t7OfPuBSy_Ru2VF`M<M|54|=dO7N-r^08)c
zf2Esvli{UfD}Gp4gN6Krdtj;synAKYa8_&xz?BBh*7aQ$nC~09sk)I_Vc`(fEYa)*
z8giEPo-E|;2q`R|H5D_<;rTlEl1&vDU^(~~L7)x~JicIfyuZQ(nLXJtOU&Sxbq14K
zcU!FU7zbzK5PX+HUI}&Fr1&g%G@`aPLd?`5$ESSR0rDF&<!0`~nIehOx(%-+1DSHY
zf|^9P=F5LRH@ne>Ac&h*UZ(Kn9M$+dq5R~(ztkpEq)_74`@w<T5%;l3mqF+8*xDFy
zc9ij@anap+SKnk(-#bwy4ss0W%l7&#!_WN{HoHBJsP%qe(Yd(qgtd#tmzoj!g&-#X
zFiH~yz7I+l)^>%)d?&Jnx-_75Rih5C-=WNo_KP-iSx|a>+MS%2i={hjtjkj-U4G=Y
zoEFp?kLJo<{HMYksRf}i;3}S1)sjd80?Iy_ia6}8@TmC9YQY8~O^YpE2PX#>&8WAJ
z6yNVB@0c`sE_DQzUQKoM=P`>hxq%BI>ux7V?Q%f1f+^<5Ymz-6%vj>BlhHU?j@_Aj
zOvA>nAKP(8sk)x}vM?I2@5g&CX3!WHzhZX}n1#jBfaDG5YR0i#x#OkVt8Yuro5bU%
zrJC$sI>sE=K11Ujk}HyXhDF$4GFC<+^Mr?j6u7G&^NXbt29qu(y}6Z!;ER69L}ai?
zB$Quph(=R5Xk*!6AMZOXi5`Jrd_Ob-#1{juzkaBPDb*56Ys?acT!XzdZuq2pTV35T
zGCpA@dU!RK{9l_>mrTJ^ohPNjkIuLBJo}Nc<&R^&e2^U4Bbrl({hzvK6^jb&j94j>
z=UCkY6{Sk#w3|MZ0~fQic{(D#UmGVW=#!a>?oy_8u88{*xg#&IdZO_OT=&^VOa2I2
zaAzeA(;Gi9?SK%D5G*U-xhh!2!85GM$3e*)nQ3qv1WmvgP343pMG1xzB0DrhlGGMa
zEau*PUBZQnSNiGP5G7?Cd1h-JlwJ)<(3F{nE1?#e$hFD+{zr=4oDls#Ek?KsGR+tV
z`#gPz<=1#QOL%A{pdGtny*r$z5`gVa{GVEb!~&I<?sNuwQjJly#gMZu_M4lW_E!kf
zAR)~UwqE!I!S7({3<Mu8?aG%MN+Wt{5sW$SL{s~XE<PZVF~vr=L1P|xLv(3U*Qj~Z
z9rzU-Rbk{>!?eDOr?^8EXGZ@43B$QSE3Rwe8S!Z%GQiP1KuP?Dmz~iMZ#5%8sKuix
zc&INbe^@>}KXrkZPuAIIwDYM;RAApKI8!svJK}i1K;-Unm#Ds!*{gRsD^6Sl8I4HT
z=XHNZt=K>QJ~f!?`SRwPiBD=Abe%El_$J|0e#Cj9%CZKJrLdpd^&Z*g<(Dr)r^G6@
z+6o(+`*y?v9KVsXvk#qImK&*GzojZ$h9VN5hiM&Jpj!QG*RGq@`%>VL3H>5E)1yC=
zUU+phsM=~;eZ79vRVKm?c@~FcEHm*szLbchI><h{deyM$5P5TMMv^XD@@KeY=k#+i
zv;&2q_CGC}Y)QlVaXp|&W*Kb6>fOl)h{Wz3O=QAH_^*G~FFAlSDayh8-=HlW8<8l@
zc`*lne}7PyU{}3(5nRpvM}hQF&*b*LK6)%iCNn>O*S3*Q#_^2G%SnqDcyat(HE459
zp*Qzc#DQ^!Mw**71Z#X%K>@i=BHjI6`g=N{L&;R6wp%tfl<7LR;*O3`6MvsUYHBJs
zt#xuwz&P|gFu)4eT^+&sEJ8l&kQNIS5g0L;7KQ`c?S45$N1xfD9D*ef@Wan+scrv=
zs~Ey&R6s4gkWZX9N`EVPPcR1OZ9}J?Z|Uz+K28v&a*uQ4Dl@k`k+<;63ymIslYP(a
z-v?zqW>L5JGr7_oE=Ar*E1oaU6N%bQeO>VG&p=rU%sR5|K{A&Z*LM~>GwS2%Qb~L@
zd8WeErl=AWy^q~|u)7c>VJY#p3ML<teGSSRhssg&qCd;9@YWL*?(qV~L76h`66#O|
zw}j;zvIw!hb|YPzOA_5*KiR{=!qQk>T|Es<I5Fzd1*kxOCkqFSoV1zh<?d_8+b(nA
znQ9m-!&N}HSJ(G{J}}rLVbXn=!=(m9L&ATnmxP%s8Y@5UCZh43-H$FKHN?sAynz+E
inpj@xORrjq1>Qfo`)&~W8BG6u0T70k26cMq`2Pd29)ke@

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_flying.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_flying.png
deleted file mode 100644
index b0b51f3d42edbfad9f875c1faa413391c4f21de9..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3001
zcmds(`8O2q9>-^_Wrz?nC`+XnrVLpsge1#Eh^#ZrlrMvs$P&hGY*S<xMJ8(#nIV(x
zJCVJ_SRxW5+gK`er+e<X_kXxQe4fvFp67g?&w0*yf6n_AZ*jv&fKP%C000OWU%zU}
z&e`k;ImE+WgGPlD*$L=tX`~M*{~-09y*Z4(Zs!XChztJ>pj+M$y9DHHd{xgn5V-Qx
z-AweoSh!$hTqIvXK_qbVw&<+S&4Qbpu*YEWg3IYBM!~s`l~{*UN1v@9y|BuwBHxcC
zNuU{#9mVnz7j|Mn2kWu=W+U|cLvegCaZx<y!f1AY+tB2&>f~_mmAq$G#uHA(FU!oI
zZVoyTYCZU=pFNx6m1oRBtTneehPnelxhYwNH?#&|un-`!$qk0zZCVvWb?te(HUJDd
z_;)8c__L=Gz2b+yQx0FvRW2zj^SJ8g=NE!TqcLt1bH65W5i>J0+b*rddW4x7g+wBG
zGOMnENf)Suy<L@{Zy%lpiwFysMGJ!m=lfjMg<e<pJ-M))1QLhsO&&V==pqqtDTuYG
zTToD-qk21HGd4Xv-R~Whx`8`_ulpR#ZRg<NutpS+40WS(@WM(f$Yiqa)LY*(!;(#}
zJ%tX)8eR<g`i?>D5ih)LgKdTL0GYSZlui>o_8>U;(%#-rt6P(6Yik))Dz%rzV)=}6
zc<9$#&z`g#34jC$9KSf?zqflY2TYDH(zI*mz)jUvrl+Ni$;rt%hMbU;{JpUGt^a00
zMeVcbTD~tbNH2bM+|=cXSV3uutL=~21nxG?UUioiF7W|%uW^=io<0%xxaZwimI~T)
zx-rc5W}=}D?FxZV@3l753?EqQvtq2cZiN?Vg$qCAda51lU&^`(g#q+=G<oJ;^mEJ#
z4jqgP*p53Ea-n31rtrcxy7DgLt?vW)^Bj^q2K*0U|Ce86)d2~jDx<87P@F{ziqZX+
z#o{WV(M00-4!ZME43p`3`;8|gSMy$r0b(<^r@K31cQ-IwUjsLlD=R|p{^#1BN=gMK
z@!BlAq1%Vth|!m}m!>~XHHHb&wT6ZYsj<-po;~$oxrmwO(i{oN52-1feV4Mwi{;iO
zpze`^lXj@-2Eyx*pFU?$Jw9_C52Lhv7tXd9^+ET`JBUv<o&><FO_Vl0fk&%&j#l|Y
zI?rN{iHRv1X7s9Jbo{ZtzN$)gRIYMl<B!Vu$0v>Sy}ipj;Wk>`$v+2DSEuTu-uiyi
zH#Cg7`%+Fx^gPlC3`a<@js@=RRuV#PSy_?oT-xG}Cg<f<*nLoBOI12h*g$l5QH0aQ
z>D4h&(JR;ER?W^eoN0~X70gFAh7Q!=kiT{0<vR|Bo}0?*if=fX?^8<ba%_obt5~Ab
z`>4^fTlVeu^K?UY&&S1sVDsWiw^0&ZY6f7~IIYPY$bS=cWpt9n?WWh=yuC6(*e-lg
zRb_qbd>x}D26WnXWy+u-74o`qN+^c<T`!8KdAu5%?rQK8`>DJ+;TSZZOl~dI(MkB$
zpSLQv3IiG}6wYrE&yGBqq}~Csz7HF%q}fv61+2Cd7$(kqsz8=)wJF&M(e7IJ`^6^9
zZni8<MW0RUOW=lhOMCTDpKX9oG`}0E!A&#7RENpJ>6k7?tx0H0j!;b9!XIDPgY^AZ
z<}10*pV^9a*=Bwo7#aEc#>B!xXeNK!ES~q^VqJu6La9}8<TG%Vz3*-xZgZi}qxk-N
z4=h%XA{9v_@+A4e;c&n-sxJ);7r^D}5XM7y1|&JHu-=okellV%B~OP=i_nr*!oNo_
zJd;eAG6oCHeZf0Fwlou43~qf>$Q^s@HKFb{H4$|V*)S#>w$02gFS{E}>cl9Pt4b7D
zxbuCa*rD@EO8jq_5~G5pzGh}FJAl<ZM$TS0HXihN^S)md!<UMVb6uZp$Io>Lv_n>D
z;EM4|bnMPCLjkViZoYBzZneuf>o8)EDn?k`U;e7Bd&h$~Bxjmc#?v#}QZuupbf|3$
zThZESKHBZcZ^zrP##k&=>T;kE%&C^kbuvO59G_^9*Q-P)b?!<e<*>$NH>)aMzKk-@
z(|PbJ^Bo^p@{&Ij932y*r6EOjpRe(r^gx!(l{;Pdx%Q=1Psz#Z(&!2t9zccKmN)&{
zS_bOnryP;e9Jo`qy*e$OkeIj<c6+yTer#=cI9b-9)=aP(lzjrer(WaMe`2gYSmX2Q
zJ08THYUUu>C_G1Pi}`t2N5D~W`4M_ppV(})zR8PU8c_)Rxp608jL5o>nwko93yI5v
zEN+Kp9f3Q-Y^<%h&X_;D{~Ji3cy(8wd#yYMc^bbZas$|jC)%Zy%CxqN)1!Mcqi{6v
zxOC8rtLWZHG$^JRk#jfUU533bf)jG!c(kL~-rjzMg~@(>#nDk}W{JSK`yto8-|9Tc
zU8Ys2ZE=wNWvV_{l=<=WMLBCt4JB1oks|ZFBgV$YPCiaZWSd&DOD7E3!2jUE1DVji
z{!jaAgkW%^DFPAGoqDD<O~HzZ`cftjJ!PdwgnHub1#T$o_<W5cB<0ysvd#x4=vsvX
zN8&}!w7f7*1)!a5%!(rU1xR6oyZ+IVp)#QxU*q?Ubnult9I<E(#`#cUPVsbS%l2B`
z<LDsGlsWKD4?5P&YxPjv#cj<k`@Q>GsKDm3D_WlNlQ~D=r9Sn+JH++5&Iygu+$49q
z@NcPu8{)=Z5O|6=xlqmE+I!@w>N{Q6YaeC|@k5lu9*<<mp8T$EZ=#B++B39tAd+58
z{G-s9{C`^{phx^e02MdU00)99*HUD=*dtGJOk5VK0UX4l{~nMW<CeL~xxv(?Ekfp&
zqX@OEtc<Hr{hV{1MS`X@KrC=;DV>suKp^%p92yWr*V6JbI?a#m2`@$O=>U{uZYOV1
ztE+E)lFXOKP;InY#m=LE#NO~hdO`r3D(YzBnd&GYqN{*y;|deUHSzhDZ9f68o5F#d
zn0kH?=r`=IN$F>#rCFC!axyZC{{3olN{Za_9cycAve}G0`Ea(qcIZ26TEf<yo*L77
zZFMe4XE*D~C;R!dd+_>tRj%x*j<-_(1)Fer%<RKinq^`IvQg16R}cVF)6jSyRN6tL
zG$GkP5Ed48hC(wkGogmLHFR!IbxC%kuK(T7&dt4Kk7AxFG&4QDdH?rLp`6YeI=6|b
z>GSgP8z0{@nM_>_M*!rMH5Lkk9Tb<~QoT7YJD8d#mh^NliIu#1RUMy|)%)l9^XIw}
z5)wS|4cHB`9YC^K;kb&5%4%WqmwPrg8Lx_pI+oOrEFNfw><(l+d7{Y4Pe58&tl_l7
zU9x5NjLa{F9qgsl)z$g-P$ThY6%`|MbEV=QK8!h`t(Mo+Bd>{rgQ}{lBeIMR?Zzo7
zC`3r>hIXl$v58D{jyBB(ny)wxs$~kvS)$U>#pTP1o1-xv8QhN$awkvz3HilxPtag2
z2031oU@k5mV*A*qMsQhEgvrt}oldvE$1C}5MsIZr+9mbSxi0XYtg}TKK-xjFj=^C3
zNx*$HIL;qP)8K+QU#YX({@fV$CxeYzy!=@gfFMCZ+=u>t-QeHbD@wS0%ZyR&HF24@
zh}jid*nc4M#e{xHB#ApRDr%zL)bVMcef{CXhuxPcvpNwJnhBnObqJpm__$r65Y(BR
z-6HVOCQ_F6CJZrniP$UZ{rZhCe|GggHepHyQ-qJIPDgc7R*+V#A7OL)KPpfZjb%1|
O1B?xCTrJl}Mg9v7cDHr_

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_off.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_off.png
deleted file mode 100644
index 70669664f07c12ef27a41f5b5fb918aff93da688..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3106
zcmd^B`#Tf<7avi}{gz8sZK%jdL-|U%&*mDUkV{OI+ayGck4x^FVLrs%BF5Y|<d!5E
zAJ*JbO|jgPF_%8B^WFFF`2KLtdEU=?&UxO?bI$9$UMaV%&4dL`3jhEBVI;!DjvMp2
z76m-c^^p@2Y23gQVrOOqs2c$-a~~(s2&WJLKt|$!#^X~==avW#AWaN!Kjm3<_45~I
zoOUBwd@6G&worAJGNjYBSP!djf3wSD5`eRkd5#HfA?TkVcKHFg_#EGClFK&^whg{-
zmdre@VCOtl;t=}UdA~Niko^x~<aa*#&&=xY=~43sqt1Ra;jV=3-%frr<Vnkf0p@+Q
z0r+pA$#Ko#SHgTi9;}caP?s0%M1#POgXMI@p70qol^CZB8NkrsC15PdFiBQUYfFYV
z&?ik<MP+&G=V10LDwTRSW-K0as7Na@j4wz?NXS!BQR#1NY|O>vC8syS%pxKp4hppW
zIN61T_udH_O1py8`(m?6x)(1lerxm^;6VDs9n4ZaI>OgDn(FFxyzd2y^&K4@C+Fwp
z=F~3*n~WGK)zsAmHlSzU^%&HxL-HsjCX+cNC@83D3WPU_Z+T74&(9x{Ll#F8A8gp#
z+CpIxqY@8x63nBltb}WbL>M&i$&;<cva+(_t*tHj=e+Q&Fejv|(p0@R>(Te_E}ylT
zuCq7cOk{66|6hxv#m@u;1oW<4xkCQJ_3Q{!Q&UiV4T(U*iwSRJeDLu4kj~D@&28tu
zGu{W_xhb-VLZQYLoG}<qW-Kn9ps*d@I6i)Rv^D6vP->!bD`b6d+t23Z)qu`qxDDYT
zFwZy17k^BdfOy{<f8w=YhckhP8JzyX1I;pvl}u;P;_jI4wvl?X6wNB1nilXuk?`k}
zbUGbH!i0rgU74uKyDEUmQ^dY}IfTREIv+(W(<}Vzf!VR=2S4KKr>rb2#>^m~<G^(Y
z?v7eU+wA%EBW^0aGIhtR*48;W<UhQ7Vb|uKi}T@?H0_K)Vq%5>B}qfUCOhtY?HUY`
zd^}i7KDCeL5C9I@d;GjOp8-s~1+1C~KwRLL&oL1L44Tm5YNdF=`BMJ3B>pdp->!)=
z(ooWMP2p=Z-jWwAJ@hdL9$QzSx?d;(HHG`zD+3=g<QE_L8Z?2gt@WqLoQjLySvMR^
ziFxr+b-*}DBqEU^YY;B?-jUH0qc8uT$4d4mD@TcbQ+59ISI9lzsYJsju=aAL)yvPd
zPR%*$bZDAGjpLQQu&S?T-V6a+(V?N*FRuliWq$YmH~;ZK=9%eqIn5|)+q?oo`Yrxo
zhpqThCs^TnIIGZ`sOnhjk#SnPDJLWzfRHY6jAGC6%ioC9>WJQ_c&Dy@A$x@^3^(S4
zq;a#ccqPgHD%*0|qxBBbI9}bATA=mN(_%7{R&D?KGs&g(Zkn{(-OYu6azj=oNz)DY
z`+irQa6PWHDe2jj^6pZ*BgwguUr_pP%5=9iU%7fg%+nbQpZCe)nGiXGdRGA)>fv3c
zVIIJq>xW*r@L>su28l=g8m}e;;U_cB>AUH4d8ovqa38;1v0ciptn>d=X1eEFy-xO<
z%E^yg``$A}f03S!YHx2R&#kEPGAh6uVOCP`!G-zx#<n({atov2e_0Is^v>d&(XerO
z4G%zhlHh9{tYyi06HBQ*6c>P0Jk+V|g|tXsPENyYUs7{ws(`)g#n9Z_2<&i6b?4>e
zzm+?+V-goeifSyA<z1WQ|NS+giqFpObL);;w(ox^$pYt(F6@Qcj+>O)GzBw1`0sAa
z@A;Olb5B>!_0Q#IFQR@`R8}^ryS~}Usa{Ew-Eje1+o0o5h*AQMX_^Nv4CmK!#}Ci*
z?~mpjI9=J2m?jmDy)nOZ8L?14Ap+9*5ppU~bmDuSFK^U5HMgg)j6ft_>IVhSQ%|`N
ztyeBp)4=)2v8<FhmO%@RcJ5lh7p-Mhno#Z7Ya1W#-D-76urAVVoauV@6-Tmwqz^vv
z-S;Y^o$psrQ26|7qGtOOrLU!cxx;2s=8K-nl)sBd6<pXFFeybYwB~&<yYcML!5L{b
z)P<71I^Aq$(r@dC3FtLWMd`<IP)VZa9%#AWadsv?@zz>^2)0IE&}SGf(e@^Enl%S+
zK3$JJB_rd<W)BtP@s-g1l+;wa3-2G=6^fK=<XVJs*Y$x*YoJ3sWuzs@gG&??)QYn*
z3IQKe9*?FyioX>sf7QRi^)@V|iVv!)+Dv*aKvzH%SXAhz{Q>s{L`8L8a=g5V1y6TJ
z@8{$S!Z)96$2p6^DqbUWQH<@Csp;R-&0XUu{#+h#3*Ht-LkE4`SWBPEsXfhARaG||
zPA==YQ2eVcz4$%r#@)dnGZ;)yT1u*6^=s>XVew|`T;RA35@{=KLl<B`jGt@#iYxj7
zGKIaFAKO!|sg}G5SWJM?7>|}{rPL>q8C``}i(YyDl*MJuW;up%zvQSUKcdUG)EkRu
zqkMc+Yuxt#tjbHc`~n%nV1~5GXzcHx2U*qeZeG~@{OWIw$3;N0v@V{QMX7tmUI_Sv
zUc`oy{PnO}&w7DCa#4Pyzdv;4dryz&nu4czZ?bPG3uM|9$atd?rU7&M{e_&y=#0=D
zXKSnJ3sWCn1uH5VLnIj$ky}fpvRPKSMq6>^2)Ha=Kb&*0OJ(n{y}}kp&cH9LK;$L<
zQKf&*5NYC!?GEK#PIoMd)H{1VlMdEDLv&{YIlgM^ME4@Kl2_fBLn@cBD`jt1-}_nh
zn<!L7hTCprM;RIMmh0PdQP$Xg$B;yb(G6z}FKL8qRbdu}<>33Wrmyc0(_18M@CRxx
zl!n?`D8*|)#Jfu_>rF!gc6)hjz*^$|c}Y1UxuRoWy4fdpjtkW{)-|OIX0P6$XX7>|
z&lcQE`t-R?4%%VS9Sm`*HxC!RXnBXGv%p1bYP7PxzPtNyNn-U-x%N>DW`%ROPi5d)
zsFufM^&#;VfdVDVFiX<2BTlqnz~}M$O!wiDgMP3}8%!9D1{}LAf^HrY)tvEV8dEy7
z4yS&^F}Yj@no?q^iXj%duZG^sfS%w)^}3J-O<<>~>Z)NNUS(_mU!7amFS0gvv;xyy
z?vI3VHoiHpWL>l&3||fW=6f;vV;hj?ON8mrcZY!~q5~1*?(-zCo7PK?1p{#Wd~l^X
zK_2X|jBcB>7*|WhzD+iXf_QMdWR5vsepeQu+qQ0Oa74eM7${rniER4$^QT?cT!#F$
zEn8p*h^OEJy?#xT%hf`7B@1)&$ahovH^wiGJvw%Xs{W&Uz%q`tlxa~mSlL-PwNmei
zjSEv48y@|R-n5aJI9vGiY<F}<&D-`ffBB3OBHFBmYYum*GiyOJoxAZ<44g5ZHwUP;
z{Ntsb+e0KA)9pLDxwUNH>IItIX1d>HuTP)39B2D=GrTUK(O3hQQgZHk=Gp>5&zqW~
z80qw-v@?*QJD)p~l9EEjd36cBD@_Eb0V`y{_A*F$(sq5)kC(}5yF0a_M`!<Hue5GY
zkcZ$nmyWR2o_36yqoR70#_V<C47>GQsLX5ziDhSn4Vp>5+k-jmF(9r(aw(+UXF<j6
z>vw~4MZ-pol<XyM1kb&HO1<R**kM@dafG*-2NSGS2a)8$3Itqk{o>Gruap269D%@b
z7aK0(OUumUyuafH>Wtcbj0aY4HBnA*3K5l=`q7l1&lIySsj7NeC88lHu^)c_`t2Bh
z6P$6m5%jrXw%)1&lXDZSw5b?V^_+(nFMXu(7T_QR<4R&I4}4?iE}zb=6TlzVjwirL
y&!oXlZJH$_zeI5pJRfHX{0M25P*wcik*KFIy~XNbjS^Sq1CXZHCUr(0asLHS{L!BP

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_unknown.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/flying_state_unknown.png
deleted file mode 100644
index 5c0c7337a103e5726af53def62e37ad22209c972..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 3868
zcmZ`+byyQ#)Fw7UQji$!7y}8}2<em<W27{S<UkNqN=ljmBA}b3gdphX(K0|9orIvY
z0-_)wqoiaK-+s^Y{rP==oZIK#^W5{E=RGIY(%hKsg1`kD8X7hegn>1+&!b8d69cu4
znB+>McC<m(#`-k1qeAP{3G;n~V-O7uAJ>0E>s|brs>0r5VxVUeM!R_{{K+Llz8IEX
zuvEJY{(EWr2ax5K4yzHb9ut~}r}y9i^eMk%0-XR8U0}XN0{=1-U;+<_`v78+k~V%T
zPdiVDt|iwJSft*U4qa{-weQLnA$k)diIEYZXySrt1hKt#i!ynyvhsFkC6XCH*Wb(3
z&lTrek1F_r2E@|fo`iD-0dhUz$+@E45D)f#AzG;8@a12OFj6i(+&I>RHz?(p_Mst5
z+*o7zB_1B-t5>d&q~+x;GOuZ6h{gaa?dx2Q$F6f^Df`bg!L+nGHGiwbD@=_%Sn5rR
zz(LLO3kwTxL0sqrZfQqh;>5nzh-gJbov!5EJ`Cx*sGK1aFL#R=Y-40JC;`pZjHxat
zC=gCcN;0$gp{k|<o~?0it<0oqT*jG-1l}1Ux^zbHg>HSD9boR^yav<>m5`Uew^VAF
zX7nP-!pyAPck-`uFKe;qgSzVKvKK1%1l|P{s)y8W%{5n<CbJ7?2r$3`n}(1|&%n_R
zT~%&<n7B-xGgUE)5BLgim)QMZ!+G5WYC&{I--0Y0^1RXLqPF05Ys`nLn(Q$<vEV=H
z6xUB$M>oG8Eyf(N)E02i0}OOz$0}~Tft7Yrepl^jNr2vgulv<s^Pd9*e0%G*<3wIo
z0gM*wh=zTSV+=Ov%Xx#}RM_N{b7w?Cunq15kI#KxIPKDK1te<or=4Hq1c;B{`s`)1
z|FyEtso6JnbbJ{KCcX5LyLxqWYH)k1MzA?x-f5$MTHE;L!|jFVSy|;nD-RbRO`EN{
z268|199vEv^#9u8kLO-Ajg4IcuLs`gXS)^qRpp`yTFC~Y?UDZ3U8Pu@(`n1-8!TQ7
zOnL&Y7Zm>vpoQjfH>p<3P+?H(`V(Q!>55g;OY0-*$C~`Qa4lo`|34t+D;Q&MVOEL&
z0)Y^vuMk-)ghRpDWR?9DIl1&iTjY+<x3_R*pE0r2K-=cJj}Vp~XNT;k{C~@-j{SVN
z`PIZhEHM%G?$Q3Z@j6MexNNjg;|q&?hi>oasOrnaT2#Z=q^lT&PftAXV~IpIY)%~R
zXIxQX>D)sHR2E>LxbNlVg}m^_ybvr@9CN0Y4pPK0u=4AAyw8wu)04hjv+sz;GHWI(
z)3OO(dxA7I<q5WA>HPa64KS4OrZ{@;bJ==-DtFU^pGI8h_25IYqr}-_%(>Z6j=X(_
zUIN4TkAbv`fO%rXvKKMUGq@#mb1nxUqMp#)x)|+ju$PP~R9AkA#g;Bx%)AFaRZ$tt
zErqf^5l}`Z;~u~8LDDC4h?+-qGq4Nchi<<zN;gkK88+2sQ#JxA`|C;`gRH=^+FR{h
zzU6nmymp+riRR(dW^kQ3`ZFY-4AfJk3@d&bBjF_bPCV~F&Gsyg`je_Jbx9$=pXy+%
zy<a1*t_JOIIJMjbWwTSF+S=Ma+WY3d`6OHh0jVGU98ACQxW%y%-Gm+yAZ}c}M|^`=
zO;=ffm8BCDpyNV<l;c?|BsMh_o|tb~y{G%)n!ok_Ef-z|8-8>=l*bciQYH?1UNM%S
zr`z;iG^Ri#k_<0L_jU4FcSS#nkDo&9tQ^mJ7lXo&r_9u`{xbx<@wqCA$9bQRkB|3z
z7)8gpEi_Bk-r02djJhMc?(EAsx8zce$FHkng>|C8H3`K~)+H%xuQE}mg<%fs0~tbU
zKOhxl95TYB=+guHA^m@cU+>ACZbo3tiDQG@EYoA6F()M<e-4_1AyrndFkW#HlUM5S
zctR9=3N#I2+%VRbPy*bXEL%zAlgB`XJCgJ1?SvXqf*~8zb;T>HV20LCP8qD$$xa^x
z)6fxyvM#$UOoC0GeX-DCt1_`{A1+YC6~&w#<5{*oX31nj^<m6dlMbsONsv2%5ca#`
zjn66NV1G!yYfL;-Q=h+GNq{{Nr_5^Qc+h6_gntP-Tb3>^L9%oj^GFv`Q-A_n1LoDg
z1iw(aqwhd4f<CKldlIsA0Vm?r7FfRSkuB>8wvA!cg^^I}-@nll<tH-EPxdn1mhD}_
zlZX$u1J+i(jiGtQ<!Rddln8=}BKGoi%-G5CUV2B=_8?>rpYjHkSBlbvBiYf0{FmOJ
z(0~l*GP-h-PDfN0$0D~o`LdTgj}}Z}8RW06_i~F-?5GAQQ^Ce;47;$v6h}e@2Q;_)
z2_n=DYuH1BD&^OXQZ3YYXr6=oceuG;Rrjv+-*(sS)vFt9N2F4z@R^rMa~QWkc_>h^
zXNzV?c~)3f=$6}TJQbN6Kbrie%`19fmvdLx>2BiYdwRzwdy`n!DF+)ps{H#49pQ@b
zp7^H#`CLyuDe~>un__v=&AyY?Owem!+rq!qda)+2Y5TS$s#SMvD?XBE8?%_N{MITy
zV1kkM!wfq5o{oQO3rbjW9oeO9)G=-!ga4x@RcQ9rwTGuCd!LZ}K07&b&V!LrPT)cM
z<%{2$j|M$mZ3&vs`Ah}z>&FMf%6Wa*Bz9K1z4g|Gh#|MTY6*%Yq37*0i|`qn$825|
zwpDiQ?n8plO@6&3*E<wRKcehg$sY^RQlA0DHZ9D({zFCiWW;VWkPfB5a$mo5LV}&Z
zPEO#^=Kno%1f|-EiiHQ-@yTv|E>C-=(w-;Q4N;_pPJqx_mD$C~nfl}P@4T^&Ke_ii
zqmC8a{NYS><D!WJQ$XA>FUp|n^w1dw+1BPt?ET-BnF<4*YY3ZXgokMCY@Z1qa>~(I
zom1!=j3g90pf`WH8xj=v0yU)F7Aq-x0Vm7K<-sUdUp<weoFUgLgBwO4d&~wSM)H+S
zI$J=t6jx1W5)`PQsCZ{}v@p?eiLmZnpGkuo*0$^KGhy%k3|RSPP0w)KN&Mwzj#Ki)
zKLzTq?-VlA&79K&na(q*<OEpaWZ9vkuC2VS${-v{p;wi3Rn{W<WcNM(=tX59wkMxf
zW5(TwVJP1tnX{mtPT6Ajp?=&9X5iy9<4loB5X0L??pav!C!O=M1V#=9Gjx;ueAAs9
zn{v0`U!>)y7g7&SA&AEDS$hee`%Tx5$I&ygGGkUoOO{bKJ+EDI3jy4s6K@^VE}jSK
zTu5n-JPP>4#PFoD4BA(O70aEvY2>V%dbc=frDP#|RapPrAnVH;3z;gZ=)X(Ji99u@
zVDC>w<=b87+IJ^E`0VlR<+J*0Fkys)Mj%!uEg>6rz3$RZ@fG2^?_44`m8~Un@LQya
zK|aXgl9IECc7D{rbI&lhyG5>(EpN)p$LAj|3Y&?z^Bz$L%_zZNGt`UUdF2`$RaaNr
z<VWMBz$U#Fu$^t=$uu738i<u2{6vpTCZy?DHC&i-OtWDQd)AtJK%&~ls4pmL!j<Lu
zY(Zo8v;;}lb4CSsuD1kq#7j?))^H93QtRXWNbp4%RM^!BxN+TstWQ+jC=+8|%~aN+
zGN!!*;QB8uNl?q7jI3-E@NVg}JGZ2H(=g*D($Dvqt*kgi(OU0II@M6J14{ibI{e_d
zr-X#W<7<m#x00<?^9E`Lb!F%}C?pJygx_1x^rfZ?J}q2-M1-UE;hT0eF6drGY{>;9
zo#EQD*RQQ3B8c<fAF!zSP098`EB>Py3Ln9s`?2=FqiqWTVbDG<@@R|g>qKd#?m^kl
zOm^)`SIKy%VLawO*2p$#;4qFvOcHA`?zb$;19wQng3T0~wk;9vkC^b%1;|pBEc3me
z*EECu2L=WnS2Bu=ck{$(ALtV2bY4Z&6iu%BZZ}V_tgK`^+g9y*gohd`R0HFH5w9*P
z)&0l&T+&ihcZe$cPDtf@;-s%q2x}=-es>|0LmFX@_K+JUOW)Pp^h`}n`@VVR`C`mf
z$xSc@>4dl7yy<S;+nBlWn((^mZSJal*Hk+965i>6JnpJh2_*5sWzfDUY`f>gP}YSG
zd+g{c6kD&?9Ql2<Ltv!_iD0lU=>obh={Bwz;{2YM7zADKlF`xWLS_}GV)Rf524Q|g
zxro9uq;vP*hM-c7iNS*}&61G5zaB<LMo(>;{iYAOjcWJebp!`>J=|WcP|AOBj`NVl
z;{3-;lS=Cu+hF~@Tp2XvW%W=pUaIo6_BGR|Q{kKxGN;)>xkk@<XD^?1BYH%?@OXiS
zR(4>a+0Wj~2_$>tM@6_wn3l15$<zonxkJLhq=v@EwCm!O5H3R>?M|X`V`}=lo%hvv
zyx8zue5mM%l+wxXxK+JmOe6}_uO<Meyj2M5YuvdTRi+2aPvAugo>BQ^qBG;7N-%A}
zq5;Iw&dx5CW-UfPzlxbW*K7(8Gc|ISR_54Mebqe{quf}MKzo@m02;Y#ThqW6zd75O
zyi*cik?QjcuEJX>L0)BUc(gmf_i-(ex3x$sGP<TyrM<-~3GVsf>B<~nheJp+3|4Y)
z@P{xRe#ypk5`o@W&^lOjVgV$4Z~Gk$^bsjh!u(OC)*VL(c+xKV{Or_zLue$R`v)R9
zm&w|GUv4y2$ufp9lUhK;u6d`d$-0P%opr=fV*`)~veH$ma)I2@U~{`G!1+s;R*w)X
zRuCxX+Zdah&coTh1RT04ch1ZWJ+X&~Jkwyp#fxe*L>&A+bLSqnEpgioNo`B*j68zM
zUP`tI&0aR5Ijt`(1yku<VkA#d(xJVwjmylpgwSzEK06C<IWPMubT;KaRo4+*53_50
zp_$8c{mW2qU|ACP!c67X1i&z)NFn6+#5zhk98oUk=Y|P!nsD8;(Vo%L0O#ee%{BYo
z?xk;*@18z`7QxhRi!=NctQ5K*NDTl@-Kg-1B8`Vz4sd@m6Zdd2fLr>>V`{EiGgI$j
zoWX6KglV4N<ug#=**(aER<kwq+nfCO#0nn)M&g;64DXl!O_AZLnFN)Hx0e&!wIcNu
zS~*t30>!#13~C?MYTG=q13b}cBBK!8tAd~TrclS5OF2K6PzwLY=FmC43r|LoH&avr
QwZf$_F*G-*)pw2mACB2W-2eap

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connected.png
deleted file mode 100644
index f9f3580113053f71fe86344e6f34a74e98c17b70..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 6410
zcmV+l8TICgP)<h;3K|Lk000e1NJLTq006fD004#v1^@s6pGX^*00001b5ch_0Itp)
z=>Px#32;bRa{vGr5&!@f5&>tQ(oz5b7_Ui0K~#7F?OhAF4OJVSgK`h0kW@q$q{tJg
zQ^J#6lKNAq(4AE1u7oa1%BA~5D%G#j4JC;Z$t~%Iaw@r%Bqu`0NzD4+cm99&KWE#Q
znLTS}&&*!ydFGkfd(X^X>-*kW^R4fiCxp;cQxu3I1xiJ6P-;wy0;GTfx57bWDWJd|
zS=Oq7DR3(cM3w>y+>vFi8khpN!a!sxpuinj)~bP(Q6!K<f#Txga)18$XBBhXwQE<U
zy?ghT*|%?BX<gS#anG$xnKFATRH#r?zI^%J+<45bdiCmC%atovET=c>E~J10w+$R@
z-MY2<>eZ`{U$bV-F~9usOYQaR*Vo;!VM9F}AMxw2zt-5keS1X$*~YC>o&t~;1LWJW
z{c+e~hi$G?r_Q<t4H~SjSFher=2oRjl|NJ7MEw|}K%TNt#%Q7K+_|&z^5x4<;r7ip
z-!%K~yYCwR@WT)F0NzUfKP$UORjXFrb^P(i|In;iv!zX&HeG(wNhf{XxN+l^d<$f^
zXTkgToCP;Ug)hJSvgyKw3r}CNWJ&(grAu4>^wUqZ!J@q2u_<+r^78WZ`t|E?JoC&m
zKjwDE8E1UTnLhPZ(f>7Pz>POl-l|or8qJ+Mx6SO?vpX+Xu%OkB9Xl#UmBkcqPCxzh
zMIAeKoPO@P=gvCv$RjsIb*#z86=`sDk@w+;AGUkzt+y_I_uY596c!d%Nk)jMe-GJx
zL+8$&rvmIVFuQ+p;DHD3iTao|%G^=fwr$&1b<(6sy}`&?&_4VP2GZ?OZ5A3-s#K|{
zXV0EfX3Ut;Y0sWL2Skbg*0Dqa*ksW3>C?M(?b>z50S6rLj{>v(hq-d)%70yc`Q?*m
z&6?F7s>)JUaD@Fh)ZkvWY+3W`uDfmmGzdEtpzQ-X8Lev7s`dNOp+oP3s`JRO1DpL1
z9k?M!mwoZY7kfbswlW!$)c5XyPVGyZHf<KX`R1Gd`sbg2%7hi@p#e8%liP2<eH3Qt
z9SXee!0Uv5haZ0UmPa3b^cGlN4+<N|0}t+Rzy0<EE`CavF1^nQQ`EU~AApJ#D;5nL
zIB;B;M3%s+0>Aj;i)Q!Tci;V3D0To)17%n_=%9nN+O=zIM;vj4vFCBMYSlED#!GBa
zw`q7NjjdFvQpO&OUv2m9-C9vmQEU$lkG5sY7VY=ne>e6#-nen2wr<@z4PqFEADo8q
z=skM$m~!vE_YMiVp(t?RCa58PjQ!}NkIu{{O9{qfk3Cjv*s!4nbGNY_cieFrH-gxY
zMloR1rcD|wr^W_%0PX9qzt-RyV0`aKACmnCLEfuZuYV68KK!1*8i;}-N5LtnUbk-D
z-UcysY`*KIk3RZnamgi@h({iIM9iBvPr!N!(ge3*mKQKki3cBiP;~0lN#M=lJI%-^
zdO1R4^(-F3TA)^-#N4cR2285nzkmOyNhCi(4N*cszbl@9{&|7de{fN3vuE&?5i3`&
z6ywK_7nmdj7T&&s9gbVY_uqg25Qtpmf&%iafg3KOrALn*J%|exKR^vJL$qquN{k#i
zQsDJ&6EfjF4fGYCe)_4n`|i61JP3UQI@TeZ-+1GVi-G{~tbiMyc&#AIe(yD?As31c
z9Xg1K6DNwzn>U9SsS<k5x6`OmqeS!O&3ys-X{VjG4C{j?*#x<-;HC(|MF>Fcsa(yO
zYV6ptIS=S$&ji*t;-QBg5?C;M3Uo{^dj}65Jd%dDY=GQ1aKG}(D?OlP@XSok1=TIL
z+#;YCPsUUAeF6&1pFdw*cG+bDGP7quKjxTY)_?NJC;5H@+;ebqwuVE~yIzSPFvA;S
z2lU1XSf{?SO9ANG#bb{>CZN0a3gr4V*Ie@)v{04(0=cK)o;r1E*Mko}c)M(1!}mep
zff111?eb2YXOjZ(3>5Gw5s;ZZ0XcNyn-(u#+|mz#djf96B36RQ{59F2<^u83OD{E4
zUN(89PIEzlMT-`R^Uga@I>^DteXwv2^V-E$I=EM?SkV|V);gKMCaABz`f9<2kZS%@
z;Iq#@69`q44)T^QTQ2j`S4AqgpL_1PE6SEF%kU*>gt*{>3vxm)?LTCl|0BgfxWY=~
zEpftN2}T5=H&U_4`$@UsUw{2o0W0oTWr7+J+=8z~)q+O>#G}eqBkJ%`84fF};p;?T
z%Gg}r1j%XYz#vl~3)nP^zyA8`!Q-gvQ3(pbyHUWxETG<%Hj~3gW|mC9aaUe}$o0{J
z9YR!jRe;-7gKvp8V88$k53q&+R#*4R#>GgVrhyKI8!KH}6K#M0{kJhTdKJR=!|*ON
z_hB3}=?qn`cITaUYVgsKLUydzHb6{i4^Pb1Zf}?|xF=7Z-1EvSuY3_tu<JBp`T6<U
z(@#IGA#;-3@pyJUd^HRo>$Pjw8t$j&p6;kTCX?MXESe3l*Q{C7aH~DxgcD+}wsg6L
zZ0hFro?nZ6Fxs`(UaMiz@A|(m)}nXbd8bqB)~)Bcx>+W&&0Tlh^$`Bl_3MaMv2o+Z
z33{{ztsw`XK)w@k^UXJl7A;x`MAf?<uN#_CTx;95t+?Ta8w9MqfpjgPA?>!?ZWGjQ
zxfv_3rI#os&>orK)4ax!%uP=|xQWs?#C7MP1`-7Y1%be{)m;?6F9NSd*W;5xqjdMc
zTE_tU+i$-u{`ljMK+uw%`26$F1%f(c&`^gD%wXKo5l+qXZC^y^7bx^+rXzT|-#G))
zX@@SE*=z(fT|#fV=_Y|7SQ(7S>OJVvONX&rZ@pD~{PD+Ge;Y!BCSY!tLX*CI`%cKj
z;A0Eiv^XLK*P?X5P51jzM;#@w2+bO%323Sp5$G!Tnorl?F#nG9#{wRCS$8C(Xa^Sz
z*R<~5z5DBw9L!nS&OR-;@w%&a^2sN!aLec}UAkoL)ydc7ph1HK8SZu*VZ8p7Q%*6~
zHoyJ$TUI8PpMU<@2o!Nky9+P8aJrK`Drvz@aRd(Tn=<Vf76t-&FMKB|9f07tC1?!F
zwC_>7j=W&JC1+F8$InK+c)x!AT=RmWG45q6zhPQ%g8)p*UZqKsCWTI!&DRm-KR+8~
zy(gc1QXpToYeG65Z<x;Kf)5Ep1!h7&*(2bhA>g9niZ}3cnPVpa!WOtOdJUGNLmD+|
zw9PI9p_>(`O5hve5PdD6qLd=v*&SmP&f_}hsi&S2Fgp3hD>`DiS@U3`-OP0$ahYmM
z`D6TrkiTo-iBFr(?3{DX5h%6c3$X}ldJG}~j;q-~Hc+V*Lh>F_qeczEv=K1M2rxy|
zty|Z40A=WcW%e1yBO|Q^K;sMFkaS4EXy=$`lpr|K#$z+lXU7&w6hEpBNA}e}{`g};
z8#!`VXqX9%>`EZMXN{)pF=NJP$lIaO^zBzepoE5Os2U<xGyrwKJ<aJbPT3ki`;AF}
zZ$)Fz1Ux7#729A3&>&{{H8kUYAWCX5#Aq;HY0Q}AW#hQv^{GL0we>epb#6siTz$AI
z*eiOK2=VE@gZ1ucFqTv=@#Ik~@S`DhfH51!|GyWXQB}-{`eCvjsuBHseN%M_e`oQ*
z2Ok&#&lg>EkvQa#LrT!xi!t+_l*yU&$LoekN+7T$?U+tI_0-LH&>e-SITA}S(AfD<
z@6<=g5G!a2hJDdP%<F~%P2#Mx&Pq!NHw@=Olw!^cFT5bW|NeWghvfMF1pHTDeI@YL
z5~v<wh(2z{o9<fZmjy*XFB`{1+e5OxAm7X{SU{FXA7c2kbL{Bk_!}Y@MnmY1iwOiT
z8xlhrfTI;I83EjUPeAjnL(qh+(b9`*Y+}feA%;Bfh7QTDg(H*k=J498j2w~s@fVZX
zdd%(_rG{_?ZUBKEa;@PB=9%Zy`|rPREXtA*KGW~%KLS@xfyA3(!*kO9at1^S1;gy^
zMLIRqy!1RM`<{F5i2=M_yLM~r>a>Z)_-(&0;!m*i8H>w~YuB!o3UIuJ1pK=Vktb6C
z$6rT{N}oP`1j>zISkZ2zAJ--f@RjM&ND-8te_raxk#mrl!U~+4+riNicrNiF{zoUD
zv9iAa>K!QnXF^A+&EmnC>1P^~D0X-)I|lV}q5Cc!s-R_%MpM+d6jbMV(eSn|gay@g
z$eA>7^Fctir|zhS?h4>ED4@ii6eduXrnQn*OVxxxq>vakY?!ok$0+0~C^pJ$@4ffl
z7Tiw?E~VVW+8HE9zXC}o9Rr+;My~!dot>@M!IEnDmH6#HA(P2o-ix`%AAa~@DQg*u
zDSRu+SZpHjm}(hmn3Q%SYp0-fxDH`gwgHZ8psviZCa|dk=FBgH&|ZQoDEFq$o{>;8
zf_$l>btCp6tZai7Lo$v%0XI9geEIT$ux6$OI1L3fQ=0(IWKVB5E<S@4jS>_9+vx|>
zJ2M$(CbYL+LxUH!HBK9Vy%yI<$D;HbT04orggcR7F)6@bdg&$CD|zPM&V^+1P63n2
z`7D>h&^0SyogQ<&#JnbU8wz@@#<`y0(36{5I}4NbF!&Jc2k-|Tc)%4A85)Mghg}+~
z^K4Rpe%F-8QSl;U{_suu^2;x${YL<M1y1q|gPz^k+UW%g7L0_qnE`Oh!$<*;G2u9q
zFvS`~p0vbMCuB|mBwI47QaGKt&GWg?eEjjp6LtW`CLO@0^~_WJd3tke=i$vY78((q
zksu}kobD@Bs9+Q{N=PyFrF06=;>j99oQa+C$~>Q{M{6UnA!9Gbcb;R<^FOc-;)y4o
zn2IQjj7o+u$$S`PYkIxWx1EbNY7^k*YUOn(j`8MorOmqW#v6@je5hu1$m8>@nDFx0
zu|GGSNLLMM9cCkCT06*gwyFZ-^=9}M({I~r|6(TtgZWv5*PxMY%FH^&JvRV3mQD>5
z)qc0dOjsh7+M$OYYGj#WW+^k%6f;i+sWGD#G%DKc*|Rh17W2WN&gYzt9Xqzq=mwcw
z<mHo-?A}N`J|7HDJA*SL6@z?((5Pla4m%@V0@7S~T0;hWG<44lZf2=HR8#iVk31Q@
zDW=fx!)X)|&evh+`8*jOy!zf(vBWwExM(inpvlNY8%?_?FOiJSzI@LdD=Z>K^%xgO
ziTdf+cT};RefHS~xEO<&&E~{50jDi}=+L38@8UbweE&o1An&;2jxXS&y&u5oj+(7N
z0eTG5>y2@begQX=|6!Ru&Z6+f%nHuwDomqIs=h;v)S>eI$jWm+kFyGH4ivF^t1v6Z
z0FH1XK|d2e8!LHHx69z&RLlzEZ+xR5ORktOVS<1?!B4UoxgHUXm5^q5)99e-O!7Ee
zTh{*AI$*4(Sxs1HRw_R|_^|jh%=R)}L9_V)&_{$$Oj!K+26DQ+GP2(~Zm4W^guzX-
z@;DpEfdDrL4t?lGzZ{+@OEcKk>B7j$z#t#f9>ADHrZMxQ@nJH{Zeya*;b#15HozSJ
zpMe24JBGZ|+q`53Bgq-?8f0L~>>DGGXbontg4d01v@p==<HwJG0sj>UTm_;NR${#N
z+G{&xGlHTHWAnT$0WA}hvhPK&OI8Q=^34cUDGf9%W)v7q1*RibqM+cDl+YRKW$D1<
zCUuu=pk?!Z$kywLdX=utaAJGO%EKTW`);8Gb8R)0Xx<IExSXw%6P$!}y;|?yy)`7X
zN${)uub|S@@DRnaP|@nh%v0Q;IWYG8S8IkTW?W)FnPm#$dGb4z;EuHTA}@;upAn7O
zrQ9}Zwh){$9x3$txxJV4>x1xwCF=vqVHD#x$BmXmfXg%4nzAg*p3uO<k{v96LLU-0
zjWR2ZGxTxieOV>Jt2`|Lk&&z1ZJkfZ@;VGUk73+_lmG(RDJ!wy8o9?VXc#udf=FbZ
z?2YNgD7Q1x#IKZUH2L%4;h4Ng$xLs*OmnA06Qd)z;Xx~}f_5BuaFbwIsH9CIy=v8}
zjIxHNdI%acXkhquFvc?ojqV87Uw^&ye1T4@UclE|$3s3eXkd=-Pbk2RRes*gnKP4C
zh+=|!89}ZDIz@r=&p$t-SU|rX07lEup{#xT_R`)^bT?pmm2?d$^mL?eyEz_6LHryF
zaFcKZI2MQd0h~1%DFdgPf$jW8!w1V+WXq=|9jKE1PC%koj1<Q%T59LanUn0V1k>i>
z|N4<1Vc0^^Nt2M6u@1xnCRWUaQ6g@=^(c4JnLg}cYZS{E!R~eu%87zCbK)BwdL3DI
zdzril!#-5tCPA^7t4M%T_Ovr2r#c6<RkB{nE*?Z~KU3qv>Sd|Mo$fcfB}|++G1e7C
zK<O)1thj{q57QQ^&YFaU7NHg#`D31h>6jJ&I~R&kj+|$vEhZ;&o9UGa_mQ_z2e><%
zv=7rhl;9?TVLUhr<x3m`9A!;>^*lshv({L5^5Tmx&Uh9-@x&8#h&vrIfKcKjl$|z-
z4R_0i@c*_2aHd)dO30euXn*FJXB?NuLoRL|vvymP)?wU-8r&o}R8uFxnwJvbZQHgL
zFmL;fsX+Z7BWD=l6fdGB`b>JF%;ITb1hlo!p$9hyLq>3>NyI2FJXN;W|2}7o)S=oi
z5uMEM_$K6pVFgK8k0SwY5}&V7%7`YDs3N4QP_>d2pr<5NpC+BGd#+(9>XDvN*dj3q
zlM#6Jc15JRPF*dHJE|q805d^Zflcib7wNbnGMI?WKuo5<|DyZk$&-z|gvnW}ejx>z
z%a3n3<YCdNUd30D!b4#FxiPC`+yL-_$a^vd`fOWStup>22Nx1J^ra43WBt&+efw5H
zR@a?D>zmvDL=xO23i8_xM)1H0l(F^&QHamf7A{<<K`$Iju?G27D=I27Qmet=TeGH7
z!^5W`_lU+6YTV!-t|2Y6TYfsa9;wj;Dk4-s{>EZQ7l!5JsJ)7;<C!~m?g)CZ;XCP#
z2`#5gnPLPS%L-$o&p4g8;KS}Z_#xeZ;bo~K-=Q(N;oL}xBj$J_IVf{*+{2S_9Q}`R
zETypyd$(@g1ic6`fqAyEydZ(j>cFxa{Np1JY|sqciRe>n9T%86k&z>rf`lPtECCKx
zqi0}F^`NlkBWBu6yI<nEY15|Bt1>6}o)d#4Gr`o!jQK0UX&WC9s2rFyYmBResAZ$q
ziBEwmYt8^06v&O4n*-$r=1zk%ku88Tv<!=_tjyG@W^w-3vu97oiFQybJEwr1bKvHH
zkrQQRsuF^<;L+7nMs!a)kh=MuiFOz%Z>J&A5o1tu<}GcGHRlG*fx~(^pBa+kfx)sK
z?b@{q<ZPYnLAdIws|3`I@k5DyhCz$j19FnjIXP%D8%$q<1UWH)Be9HN`M+c!3i9_&
znluqmdBy;39w6Hmld0q^k8^h5WIA5!Um+QePGd&p%9TS2Z1bU`uAOm|Y!Iz<jBPi^
zn9EyE51x!iI937DLd3iYO|XP<&wvcL9_W)MO=7Oaoab%M6M!H<nUGDa1Q13*Tl<X2
zcO5B<bAHA)A8ZBg|IKhHU-BC?B%uX3i)SG|RL$6yH<kjog%|?{3@BvvE$eI;hGUjJ
zM8pyEnk#-<XrPE;AqK(GzkmPjsY(b24eWf|AhL!PDHJc`XrKrZM-YMp4okZzzXlD+
z@%>?`@j-(IZB@Wd{9r3^Cjd9Wf`wTTf(rr*a3r<Yu@Gjl8^yyUG*E;|LKuPu);~J&
z2M*wfn$ZUj9=t&TJN1LDz?}lz1W%tnef9(i;4n7ns0Y7B0XsFYNgoC7G~gzYdiCl>
zfM?x;31=xCQS09+V5bMR0=Erdn?Qn_>E3Jtyjrzt`iK!DzBK!z_UQqxW^M-nM}gL?
z032p@eblH?ixr^L1KLU>1#So6CgBi2=_|ldm5p`O=UbVkj_rY5f!iUt2`uE>^F@PF
zvt~`!QGZ{7*&dkV>7>A&0k}y-6ov8>;P5TipMCb(H{uzlKHCSn0(XYsCdfK>?(7M`
z>(r^EBicT2<)*{-U@36B05_T4p+g6$07uC@9Z^EhgbheR?5_g1OK_vYS{~}2O942N
z!|O;TF*=Aq31goWxLtyqOh<rjc~oz31#sjI)R8=Bco;zx)IKY4O8_^Si>d|HTDNYU
z5x|iMlX0B41{EY>?Uw?#BybY|g@uK+^7Hc@0lZP8M*6&Y^FmXVH%vfR;Fbt(G9DSN
z>b7dt$`-(pl0jdzXi@Jl0VYg+Rp6EkZZe+*lUlTBkrLodn>N)^=A=uQz!J8;DsX!M
zZh`<6)=q8Sym>-^^LykNX%jZEgsr~{+#Z3OKp=oQLtDKGIinX86y%2uC}Hfc0=I|Y
zCLkz!P_`z(DT`BN2_sO#*k=W9kHJk)EM2;^C!MXh*bE~`!rJG^7JR}?salRxpj3{J
zUkyLP6j0!fFmrQ#XbRl9j(`Y{Ux7Qq%+2+oDRAdH0wO$q1?~tlH`j-zz@6&|i17IT
Y1MT~g8Gu|h>;M1&07*qoM6N<$f{u_*s{jB1

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connecting.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_connecting.png
deleted file mode 100644
index 5f1d4ca1b48496ecf1372e1a0f727058bbc24d95..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 5679
zcmV+~7SQR5P)<h;3K|Lk000e1NJLTq006cC004#v1^@s6aEfrL00001b5ch_0Itp)
z=>Px#32;bRa{vGr5&!@f5&>tQ(oz5b71T*YK~#7F?Oh3wRK*!?SZ<M34v`yF4nYtQ
z5WIlpz69?pMlDTBqtV1lOrqso#tMmvRi><pl_(OgBGDq;axJi;h|00x3M|J0$|<4?
z2qG-`z9+NJ4zGLq&AhiW^WNW8uV!9fuls-B^!)u_UE{=w6H1a$AZ!$<8MX<@e1rm|
zfB;)?5K0ONutWJ;Wl{oc!9XY}AixggYn4d}umuC5q<{cBl&@7LRZB>aJ_Vo)sPX;x
z-#0vZ^l1Lc>x|>akJm$fUPVPk9-dG$_L-NLcLdkrTD5BN`j(%yYu7HXSFhf_8Z~NE
zq(2(zffNv6C&2;0S@Xbw1MR;4`s*$S4<2lH=+L27xLU_Pzy0>x765Z2bd&DCUj@Nk
zzkdBayzqU`>8GE*71!oQjT$*u!-fsF)vQ_b`y@k_Vo;!lXdZvW0f5{3%P+s|gR2*T
z%<G$PzUjo(_s3e9`-T<$IDlT(xN+mvO`0?*#<d#Xi;=elWuiikdo_^-_OWBf8tmG&
z>$2UuclY1BcW+-@eGVT!e0Cgda^@>onFD8?b=HT?n>Sy2_St7I#rI`(>eM-qGZP44
zppgMKR^7S)@qisWb_~W<uxHPni^2ES4uGZ^?~*G!SMnAuS}bncw(V?yeF=E^BN-o9
zH4Y%uz{U!E*4C|C$CZ_pjsN0{FNOl#^{bJ#S@S4vR$I1gS=gpcn>hgbEb#1`vSx4r
z4J35HE-x=XXY=OG*8<Sv$!36V>2B(@q;JrmfdYT)T-fj_0I2f93hDYCKQ8s%ci$;&
zI9)$k#tWNM?Q_#DAdi0Tx#vzf=bUq<<mcyaOt-&mY#$0>A31WQF~EF%X=&-L0P`h&
z5gHN*1rR8#aFqa#0T~hsMeqidum@1syjEWO_wRSUV>7G3LizUCrcIl!Ai&Q%@4PoK
zr|rIVoZ*gg7TA;vZ`-zQ?1l{+Zo}so+}BB$mJqQi@S_TwFz0I4teLawrrWQd?Fnl9
zD>)$Fw{M>Ui>0t%@B{1>U{&7j(xuBk+qG*qJ=evGIR|X;&CS-WTX$DUNy$C<yKa*X
zXt)~3K+I44EvM66#@cdq-??+A19EJP6~vWkjRkDg?oORLy?Xxn=f9Mz{CLg)n^KIm
zYuDZfmg73CT6I%-bC4D&ND37GdR2!G9TfTEFeb2Ol|bi;PWC0mRMEbD`~UUm(c?La
z5mW3VBh9iN*q?v?`LLBMS3ZIjX<#Z8iVB!bv?0ra{fBemAJ0@(TShrK0S=(Q12*Nj
zwqlkPWF@d^dqJtjiWMs!p(fBPtq5j_w<=d=^3IZ!!-sPP$G${C1ga>Z@tUxC-h9zT
z7d?f|=4;su@T>#&mMvSZ`uO9IpN15mn^&TfwdmHZn*whbS~kNgO?34sZUkHBfE*fF
zT{Ue!_9Ghr@FyWQd<zSSe_|T#6TKB=4X~-+Ubbx6MDWrByiGwlBDwC}yDO|BStrHt
zI+sk;hmn`UW?X&x>8FYtQ7`F?GtMaK)2Gj4*tfjxrCrc<GY)L5%w3l+U;Zpuk1M@S
z7UC&IK(}t)+G|s(??M4?I<Y}_F0SZa5;m7bmt1nmuP7Jy(k`gF83Q&5m;cd6A3cqg
z;uo}Aww)lgdmTG=bO3$knP=KIlX@N~Ku~k_UbAM6BG^5oiq4%oPwLyZ@59i_?)K2m
z_o^8IHg@Q@fbIB;7i&6h2+2ExuM_^+cNn;LNVep&&puPDSFcvEJ9n?-l1ppD-o1N2
zjepa>VT0+7w{ht&m8@z7HrS5y-+S-97a_VE<YlmAH3keApk#&iLN)*DQhKs}{dxr{
zl_!A1UVPQSfdlW%1bb2~z=lGl)~Z#jeh<PthVRy<qS%<I{{8zaSfu&)mZYbYDL@tl
z5-W#Iv2{?vKkad>+<(Oe^KrVtrTlP@4Fd-@H;09Vg|B*%N7t=e*I_xjcI~S0SLSg_
zQaxx2P~lTlROHyG*glJ@`75rt;x6bH7TLB*r(R&d#xJ^NadGj3lu6^S%t}K-KAK=A
zA1z9ibY5%lZMkB@W=BDy<(S!8KC$A$3oraLHkXfL!3xxOGZ0|YcW~jtg>O<eZ8>2_
z7F|$K;C$M)k$Rb@0Hr1n1UQNw+tGmM{$$9IAvZzEQ)=7BYdznA4HME)U_Jf~WBDew
zgP|<CU%!5$T(Kos7S^M6Ap`>otf$rJz;7Rd-1~l*$-ZpWz+)xffQ?OI9@!3V5;2Av
zHshcN%Ai4mM8RT1tQ@FA>B$EleBfv?ZHEhO@$2Bdf9Chb(idREF1qD{1q;Y}TwyyQ
zScxf2NO);mg5^-XO`A5U#fukPtLG^e95!s&)!1Ne@oSoC1DjzB-hKDoX$%}=Gbp-K
zQ6^1gi=^;UfNpK`=g(JPef5>qBq0g=3VipC&{@p0YLKK-TENCH^ZG@L7EQumkd?(g
zHVuj!M9QZng`Wb{T$1mmnXFBs%$w@?o;`a`w5e~ZlQOVB`Q($wd7*PFej2Vu4(lOu
zY18WnXBoAY1UPwcn?%3M%Pza@o^;glo`H?Q)#WOU)%r%8L9!0)1{5?;w$-Ix2q{38
zWZt}a)^2LB+?+jh=+Nt6cal;Z3Qxd>O7--)bLUQFBqbZ#Q{i&?<(Dh`0&S{Gosd(2
zDtYY39DhuksZ!oOa^%P{saOhH0~><)rn6?vnr*8Z$1hD`rz@g7n>QGtI^??{K~u25
zx0*F#os^9pJ$eN8Wp<4E$zH91O-&*|Jr_G&D^UjJ)1yX>QV`=<4PGimivrMjD6q3?
z<Hn6v6Nk&+uCZgs4uN%NiB$tsN(yX<@tRMaI(0d~ZDnFd(^7((k&+|{1#}dkt;zfE
zzwcNI>gvSj!**!zm@#99VzDfa&)0oVYC4Bs%O1!U=jb|!&!=bj`0?Wf)bT`-@2(W!
z{_E09FIByI^>Qsw%mgdkY{rZkg<yqyCziS0Cj~YJZ~_~^yCJTd<kmra9z}U{-I62}
zu%!Ux){f1+O?}uOH3qmB*nm4Ju=zlOo1PHV>zf9E;5Lp(hdh)dp@1y~5Qs+sU&L9`
zCSY;5op#!3NrPuv0h>?5Ln~mgbQ|34|6_VOtoxi@uYlV`B`Hg!0OFG*HCd*M88(rF
z!5;5TY@c{<4Qw_9t8pAE@ta}5G&QlK_<IDsady47?nCiy<$LrffD_l$?AfywJ#%yk
zk#Cn{^Ed>XNGs!$q*4*L2SNK-2U?_e7{1r7JeEf_y6s;~tc`p|ivm>I5Y&ikuAMl~
z)`6sLG|ts2*H%g>ND0{NgQ|5}^?|P*p3rBNTUzl^`zT2$kVpZZ+%R+IOk>z%o}&Zp
z<5(#C4korY-KPv}b_y+0{W){y%;bSZriWZ`!37H55~eCr7BLDi>MKEQGHY$ss@41v
zBSwsesk41hlaqAx#A7GYo?Z`l@Hm9GdM~jo{+?m8KK$^*_$>JzVG1z#&h+Wiji9Cx
z6tR^Gs7czifXxnQeTBb@(L7s__qxPrLX1fvDcTf(2HOEO9T9X1M}<rqK79BDfZ9`h
zwfO$h1~xn6VVN*g83}QW5xI;c1fR(G=gap9QGiihxl)@>Sm@B9!`m>PyB3N*Z&5K5
z=;#Zu*(bpL4a70S>A#lnj4HQ`L&0E&lA=Wcf_d7sX^P<1CC1vOdl<yZX~!J#4cHtk
z{MPmZ+{0i9wN^KH=6m&IHuWWC*-rto9bBnRXICPE?&QIP2md4;ubFsC_zG-x3<3I=
zw8Db@?7H{|C4Q%?5M72Og_{DDdT^ySMQf!i7_{1VPyy%{HGBs)2S$$vYKh=ZZ#1~2
zi@vQ*u3r<DeyWcGFjjI_YEz7DgtU7RdXAsdWW&#q1p;gi5QZu{pw}<JVLZlI5r`V)
zoQ2}&q@=IRQ-Fu6!V=FI*AM!Q=i#(_FOBT{9&up6=0JIbF~LoXEZx9qPl7mq)~-Uj
zek4D8D8O)MRK8GMu1g3`IT1>`U+c=#%?}jV92{2cGJ+fI$qwCMX$eRV=Iz^)S|jSZ
zko+v60FT?F?FS8;bP3J{&s==*#lO>)`;qTirH->nx*-5cC$A4@7&M+agI}@s;23Nk
zoKOus3fiv(#gXHwVcQ>Hiisz*?WelxF{}j-nX*Y_50)+s?tooH1#^z|Fqtevr1u7{
z|Jsa~EXsrl6O5Lm+J49ic)1>W=%GKMGx9_^aX~JM>Deb(lI6s_V)UOpd9wB7VAqpV
zbK`~*lk<enSpC3R5$!KZ3WNdyQb2$mAaSMZ%uzsqojKaelLMrH06Re9O4pgAfB-vl
zw3jCbNC5$MfW(!qGe-ddcIId=PY#d*0_*^ZD_v)f0s`#J(O#Y$AO!^20TNfb&Kv~<
z*qNifJUKuL2(SYru5_I_3J9<>M|*j4fD{m52S{A$I&%~dU}ui@^5g(1P|IuIa0aMA
zFcaUriM>1@wzhPPF#Z@}!|QYz`}BIk0_%Hi<7Ezh*QIlYZ6ZzF=0+Q4rr4*ZzZ0~N
zj?q<9$JcB;>xY4*(5q(;niQVlYZHV?dkPVy9yN7}lNS_XR9HpGH}w;RGWsRrL^wt7
z8eO8#D&6}KbzqaOPPXOe9I#2iWy_XLEG{not%;bOJ9l=DxUS9>#x$O6ETan?LCr7;
zy2L00C!-CN>FQ)-eog|Lgv3#5&m)TK116#(W`%-#zo|-O%WT5<Vuda}8D-$}Tq9J@
z0-J<JG^rO$N=oiA5nW<)pGqA@Wn#<^Q^Zq7@;Vt^VCShlWPgtR&La!wf^!1z1<Ua-
z)6f{3n}IMT{XhYR@ny&{6Q~(`aoo6Z0}(PKCqd1b=Jblq2~bLc<BKPimX_YidtK_?
zySHMff+#0OI^{}jig?OsxeP4I7>v10tDIi3NqCB&aDdYt3_)vp5mArLZ4<_q@y*G8
z<T|JwTqKcQny`{pWeCzzYr%pAZ{aAuYfJ+hFkpb{-o3l2O6bb=@89o)95Y2c<%tvw
z-p@GaVIV-xuh_Ad07b<y1jo6lZQHifV|i|$QH#yZvlAJc+5~ExAyfoV4-X5d`QAeV
zY-civgwJChTDNXJ#|_l6yr{(HX2>z})TWSaEnBuM#2JdC0BZeF12Mwo&}XQCO}ay6
zd=v-sT!k05!1Nx%9-Es7f->SM&r;MSEC6$HFxD6zkfp1WtNA%E710qMXHYgkfXP`1
zX**C?hgwOnFAC?w>#F2rKEwDTPM<O2DOk3d_;<So3xOW_IXU|u1|7N;JN7PkJ|ItY
zMUct&V|j_6+&G6VHn&X}-}dd>PX(y24lAhno<j?4PL9VElYis^^SpOUvDn-=I@_%{
zr}A*Ny|Yr|-%2}f{5wq<I&|oDWZATpLQoKDVDtT8Q&f%}{|LxvSLogs!Hsj_6^_o<
zRmuANva&KYckW!CajzXKtR7!4C@8p@5+rS<kQ9U-*nCeortfQtvk*|eSohut2=b-7
zcJ0zt$=du)n>INoLYM-sck0yX6`1n=6rk24KWk^`ePEFQHpv2Q+P;&=^p)ty#J_N!
zXkfBU*0s%4K2Dc#_6a6M8;+ZM3EJ5^sin=-IIH`)kpVUdTfct&y-*ns$<NQ<pd&QT
zPDy5?tZQ4{`RmrLQ?QdUdcJh)*6r^&ZtiY?I%RK^>YkS$&x;hWNibNf?V>$|$r~i*
zRl>tJvo+CbamkV;#^Lqo(c?K-K>jjnpe9iw2W(CnXHb4YaKq(kEAQPBwRKc*n9Muf
z+Eqs$yocy$VSH52o;{!K-@pHFjFm!M7)fCBeV+8=8w`+Z<$Uxqp-Q^EygX|lKr2PK
z#u>*06Wu5K_3QVru~NtjL#uhTeQz-5><A;F#V`_Tp=*O5fx7a_EBRy4RjHPI94Dw&
zu3Tw+R^PsTAI3R~&l)R5pfIv4cI@3^BU#FG-yt>8x@ptvgey1Bs*E+O_D`<T$v{ok
zLqPq*tBL%I9YZKKiWdO9h2X85#_|$B;RmSTGDYc1Vo_lC6yuSf#=)_sXPm(C%@4r8
z^956-D3wKi#g4sfC~ww6i8BnE%Kfpt#7}M{lbL}gwn^unpe`yZN(yRt;@=~nu1aZH
zv8&QU!G^gHq#^Sm^2<*ss=S3?pn_C|8qLZ)zrRq6NYh&Qa+<oPTiji6Xnw_1DT-yX
zVkf+H7)*Uk!zow?9!w~zyrowPHI$Th2ayPBS{<4|4cYW@s>lV@?r%VV?Lrrrx_$s`
zkEZFXOR<whwR<v~XI)!UK5bU!&!4Y0Z{Dn}22dZPF;mBm9bea0ig<yrA_f4!wz&Y{
zodK|EcZ=}UQLy_~_z@U-vMZvk%Dj2=)b{P$wGCjzbQET%H_)b9TS*F{sd==0@2y(3
zT1YoDfJy6RLQ~gd=At&wBdBRQn*`L~VLVq0sFPDvR_x?7Qd_rf9gCIp9q_)jb=BLo
zYp39qqVOZoRng|t@QOUU$z&Fe0f$G77%_o<irS8(pppXK-$G^6=zIZaXTUe|2J*JL
zSp)pehR<XZ?benXP}-!JKn*tM5Z&Aa)NT}X&yy9~oi47qFzCM?(uy}AU(R!_fJ`s3
zxoyJu!oBSPJ;__NXi=nlrsSVW0a>w6rHM8NVbrD!8Z_v3RL~miZ``=iF()+{{__Db
z11nQ(Y6h^OTbqEI6!Vq@*xu-+AYyxsN)a^E8t$)Ozg{g}x>VaUqcSl%lgZwj8c=%t
zQ1qznND8zR5MXObqc5ORglcSk4W$sbTQQtkVzLS2%b<|77pJl)vAx{eQ9yugN2gP2
z;k1N*!0_n)QwriT)~s1mB{nzhx*40=WZz9ILx6fPyy{oQbtPXtQXub%C!X-wM5@Oq
zfC#0_8M_2ANruPr5<g?o4mdO<HGO5EbyyD$M&Na=!*OE&a_>$7k&3v}#ZxZqq#uS8
zz%!;s_yHJ0j?t5c><8_`P5nrj9R&o~c63Tw3&-?50k^HklU8)8K;KKUA8;_<;!-SG
zDNsOwodVHxO>oxDA6Knf^#@(KTRy$zxl+>y)2&?cQlo$XJ2kp#TR{@?95#&)YAeJQ
zFun;vO|SX5Z29T~1q9eW5HYa}$gp34E7yIA`SJH~Gb;h8hcM1be7=15hXNw*^M{UA
zdZ8GQVa2Ls#@#T6Afz9I1k`av@%gK)*gg|9)*V#pHQ?IyGGgo99?Rn=qrNggCSwW4
z=gW70DImc1m!4I61GsAz78Xv1{m3mWV4QB+elYrLm5OrXI|T&TzLT_ShcIK!gGJz*
zh)L3lzLbpDUA2bX1wjD;b`Vre=o8?s1^2SLP|{>B;!eVt!hS2j4*MI9==?+~644hQ
z_Gt^S!~TXNIzIt+L|=T^r!Bw^`x}nv`~=t$eeq$Rwg5ZqZ#bg!6JSU5#fN>`{|B=;
VL=C_Dk2wGU002ovPDHLkV1kGw)=~ff

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_disconnected.png b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/images/rf_disconnected.png
deleted file mode 100644
index 0e99e624009059328820b317c908d337caf55ddc..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 5321
zcmV;)6gKOLP)<h;3K|Lk000e1NJLTq006cC004#v1^@s6aEfrL00001b5ch_0Itp)
z=>Px#32;bRa{vGr5&!@f5&>tQ(oz5b6mCgGK~#7F?VSm@O;sDm&oz@NMMR-8H7LW^
z%~*!dSUw)ylFASb9z7*ZzBH*+nyD{Jq^p!iBr=r3EmQa;Au?nvN|`BXegFUcI_`1Y
zyVl<4>~qc@-u*oLInzFCul2sav(DaYz3cy`DWyWPi3R*-fqZ^zkhDiEKnn=i!htU>
zAYl8_t<op~TNv=A1q5tgx>Xt_U<(7jw19x^OSej+3Wy2fw*ck>(heRxSbX2UeWkeX
z-MhE+(W6I;96x?MKli`>`YT`fu}G03M~fCMdW3tiV#N;gv1G}T`_DMzj6M1C<@+oC
z+DHksfPih_fKYDPvZeBO-+fn;k2`kksJMOm_DbQ$AAkI@!v6jHOY%5FQQD6QHQ_E-
zuH5eMUb%ARE$5wg-lp(=?z!h~Em*MNF>OKeVYUU*Wacr41OmHk*|Pd8R;;K)kh!m4
zzrH$q-<+dT_bh+@{Ku<Qsq(|6mtMNEcJ12VgdeL`t-3iaElsA7BU}?$un!+TT<ps)
zzihmC@!~6%E?xQ$0{zoZKb4QLjc1;gC{f}-dV2bjMvWRR;C{swS1jgxo@qb=DjFED
zfB*gW!iyFyYA|>1+-9GD{(18yOO~V`J9eyK0&JS{BH6REN5AsQE9bXu+jeHtrcJYW
zZJ+XrC9wj&27CAJ-Q}iDn|96AsZ;+oXU?3KM~)mRnnc^W=2W~vZPu*W+%|36%xc%J
z-Hh|kKYycZDwm*&_zvt%n>L*{Y0{)FgqfEa@!r(sWp`ZDhALF35W+QY2-mnF-0+3a
zE1t9isFPmvb6l^7FlrL|?YG~uA9H*D>#x6taB~_$-SawqT<`PRJR>7xBKHd}xL`wE
zg}L<0z5p8_l$khjVn$|W=8X#%E^O$OtqT<@6uRV+OF|fx$c8rzF+s+NMK-ifoh!N=
z{JVtKty>pbyLRnK`}f~}ANu2uKcWwh`E}j8b^lAiufP8Kch5QJoNX}|<gzb%7Hp0S
zPoF;h>T%=7_4xSXkK4o9h2pg>d)<Z&8=lzf*RLNcT)1$&#X9=^KmYtQgny-M*uVbz
z>k#f2LilHj8+Hyiwr<^ecAq|dMqhKyHPbvltjOU$FYUN)E<1GS&_U>3wt^TAamBR5
zkqW)By7ksu6@DBFJt55C&F#>kLu%HnS?b<<?^Wo5726i8UHHAT&N}O-`|i8%nGG8@
zoDYk5ijQ!8JyU7)O6fP;a6=|~P~P3g<T#8LsOHU^tJhw8P3_vX%bOHisP&#bd(;OX
ze4zUE>!)hes1cK`Xk+|9j(6(RX)=aI8-;=K%A@PS{^XNS{)u6$dGWy9qD2cea^y&b
z-rfQh{ySvl%9U#1z=5iK`SLMCj&btExR2?IOQHN;fZLT|V>BRb%9JS`agDn)7N83h
zD4<%lY^g?#8l`^z`Dg!;8e@w9rJ6Z&rs~$Mo5F}qOpxP7dgEJfz173*fV&Rt$&)8{
zy6B>dzKsQFTpOw(Lxu#lXSTyTg0<A>(W4b6Z`9w@@wPy(UcLIdciwsDdfde4b7K$g
z8nD0k;)})&8Z=lK3(&j?96NTb!tA0Q-^#InTVV6%%?dY*s(A6@w&13(F1+x<)tEQv
z>^8Vl4)*HRt1s-(p~F<WK(m*@bg}yM(@zCZhb+LG&W9g<Sd}ha+BV=#nl#B;zI=II
zw*a0purcFS>W(|^7><#OKkYz`**n#@Z(p@$%^HW?DaAxvfR`y4QdMQkmbC>qM^SqB
z?)@f$$<9hO;3)xn{P^+Rafkk+9iTZ>$Kk7>j%-B3myFjOAAj-17uDHkpKS|pL>BHJ
zHf-3v2r?^>D!`KpHhS4wS6y}0TsuJXSj>niT(Ts?mvW9=EP(iy?6H5lfM0gmWh+v3
zd6E>c`OAI$@y7>anwCKhmVf;<Yt~elF3-i(@>VJ=fR#e(uDkA1{P(o#M_y`TMsyhB
z-;1KoN#Tv>N%)C)b7*%wx=fie>gAVTR`@}r!hdp3g9Q+yqOh33GTi(TAXIh(V&ShM
zbjjEgb`p+nKKtym_uyvlh}B;=CsuGnsd#rTo4YN5Ni_BP>#r+zLRS6Do6Gy}zyE0j
ztQAZ&+zA1D+qP|$8aHnIh1CZ0IIQ?kt5&UYw>PDBr&xe9yFGjMv^B|7uU@@nSW8+h
zk#IW>_KX=b+G4f!FIJ)Ec=Uh)0~BviWb>{Cva+%iW{fTO-lv^*+QB#9e6x3=;C2jb
z#tsY`G-xP5<+2Y;4a5o*g&-&IdQ)nCk_9;P%OP2-{^xPsyLTU-h#N~sz{WDBvk`MJ
z-%f)%cI>Er`Q?|B3?nc6VS)GFd(YPNJck9bc%mv=?+A}9C+>nET~HrA?@p^wL;WZ_
z>dqf7lvd<r0cf&hFXXVw1#Uw3FhrS9I<d!9$oucVpMmhl!&WPgn+C-O%N7g^;1VPI
z#?mSu9P@tWnP=`xDcFxb`sgEeuBUtS=%Fyo6AX_^D^Ie(m@#8)#eZYn<s0!%$J_3)
zF?vz>y6di+VD(qX;}|g}Td*zg%{SjD#Bf`_u|(wN3<!Om2CLa-l;5%SB}}Q7z?#9&
ztU}ER7YykH+oRI@6Bc09AYz3q!_D#TSR(~3gN=dsGwn=`Bf?9~o;~|SqvVNLfEIvW
zibDLoWw@c`vKjg+)$vu!tnye(2XiK|R;^lVtoGCuD^^sDCy-4nkedY<0|dnZ%WyNq
znK4Hw%M!0V&UhgI3ZTop#VXVnUwpCJx^-)A?UDDy0w*lMSd;$!`&)(^iyn4kwS8?A
zU}ToZ7!Tr#@mp@WWt0`LDRY38F()c7Ps9Qy3k)7S*fQK4>$V!-Z3G(?qc~z30$s+M
z;O2q=iTN<OQa+EizzZ+DU^$2i>oI?`0=Ffw2{*$~Ij?Vm8@g{YULEZ@d2O@+$GWX7
zU_cb;O3K`kN!_mfF#3xObn4o*>qHaWojZ3{6lal5EMV0FoTWs}i1xAsx`fLSt6v6X
z8o4zd5M2mogb=_q#RNBGX%%{TtL>8G0&IZ;2M#F6*lD4@{PN3}KvTSQG>>_`whcB5
zLU>}K_U+qGH^JSjS1-l8U)jV0d0BvyHjr-CLXEsSU*fouD8n+ZmJf_BlvC@iTD6*O
zg8R1HZp*7p@_xWA0KtBRNk1*r=*j1yM=u`DpXqhXV6$Kbh$FYj=O(zhvRO8<K%@nz
z4}+8;TBso``YE(cis5^<Iko+T=#wx|#mf3dEaHr8mpl)!1(5WWntxiT83cvt_af1}
zS$!Qh*gO$~qp%!*k*Vi?=%I%K>`rMqEr9S0W0W7Y9C;sy!(-+%<}XH{lv;dNf~1~$
z>M6EQwg6gys;)>(rR}LPR6NNEc?QS8hMz*X891Hm*GxS(_26U+mIavO2YG|EP&3Xy
z-USBakh`N`vp|NoA`oho32x?rku4Y&KuSMFMFJfYH{Ep8I483tI1V=9W<(%#_txqf
zLOl^qqsr!Q3vlHO(hO>$=29@HGb1DfY{E@R24sExUI#bRwjtevzdak^)*)C)K|Dzd
zHFQW`Wsn`2adLOGu;_{*F8dtZENs%j&A=C=dI+%l{n>P+FEnOG!2AYpwi3c%LJEzn
zEbfG>m=-EPURZtf(MSIDZ~$9Hxic;e)OBb~kQ&K})6WwQHY>~wuMiF2p=&4-lV)d^
z4Il@;YVw>pa}-69biRJ@!3Upk8szBmk^(kQ3Za}Drt}=lJ&4@kzH)Ss8UsO6#T-F8
zsF?sD8p1@pP8!&(JQrkg?V7IPP~lWaaU3Kbe9_hqKm1S?DpW`dwNoljR(=Rc1)CM(
zf=sSm)4^S`WJ$GT$r4{UJP3_|)SaS+jLxT+lw%}Z(s)bSi6R@tHEUeErZdFpr=PA?
ztXL5QE<D}F%*;&fk}k^Nz542_{UZIJjOQr<n+?NoP&#_%eLA?$Jo8NT?YG~0+VOs_
z{2On)p*R<jmk*hm1IP492FTIpNEz6y2(G0YQQ1B(!|;9PM;C=w_x(IxdF2)D%5o~F
zjvF`brfA@j^*W_svysdsh2fz?I=HDUwQ=J{_jxy<HG2N}=kx5P=|@~|ADb{?!ga}l
zIJfhp9Bft!`OsUMvWr!&Tv=_|vL&D>xu@AoMXl?En9CD0$(?h9Et&7R0&F&zNtrNQ
z^t;Yz$Q7s%gW?`92dpMsD5CQZ{Wo>$)DFo6IInZL25eT4MlogYtx=<fLiAw3kV<`X
zkzH2{HUDwhIpqafvfp<V*laxi#(0gU>lr9~DT$eq13Tq2m{eBh58fm3ax&TQ>dxmn
zuvyu6-+i|mhl+H@tW&3sf`CeLyc^K75NZgLYN0M(y!e56^X6Sizqx65Rb?U#!=WM*
z+)xKn6kL(bc?(dY4y#(UP;(xFL$;BAbIWtrf=vT)aNm@`2`WJf5)jUNHozrPm>ug6
zwNP{B7-0{Wy9MOvdbk>FR+iJTx=Rv%2GJfxQA63{w*a&2cIwng3$-1cYWgr0drD4f
zx1kK6F~Kd`-0?%r{4mgD)Ix1Hvw&S+J9WG#z-D6^@@Rrvw7Fx48&YBll44q@W61^M
z6sUH~@eJ5(*pMMZ9x}n*rArsl=C;YV6&YWIHEfS1dzW1xojTrAV6)Mf{TgC|8<`hG
zo7*DX%o)_6K?7}1%{8lB-sco_$tcHjVACj=1si69yLa#2qRnl98`%MjGQLz9;DYRA
z!06;TJP9@paOa(OzGQ;?_S<haxHh;STaodtR;}84=J<3HxMY>(S+Hp!fcqa4+@j5W
z>W|loj4zeEcJAC+Az2_geI8GPO$DKwZ@zi73GN3Tc;Hm;2J{`u_@XD)UQ<(hao4V0
z<(!5sndNyJY#NH1Z#Uj}<J%^<A9>^v93Jcq*UCm2U#jI&SQM7>G#j3-eAxI@>7)d$
z3GSz#embyZTaodlzB#3!!*=!Zqc6aw1E{M^(Qp&oFTM0q;NV`fW{pwCml-K2-tT3Y
zBkS%Pu-Pao;bZpkBNN;sM~(~(+|Y3`%J?>E(j<%NRwBXh`g31_O=mE7Nt-rpX6oRk
zHuu=EV{y2@w`I$gDFiHOZxosJjR~?~316|`tHy+#!)#M6TC|v>gPVF7SkT~GvKK8{
zq)L@4rG=V#I+@ZiY&SnW`Vwq9i1`7T{89%uWx4#Q%{_nqe4~snGb=L*t)F0yY>RKf
zW+R!=73qu@=-{R{_q1u#aJWA<D>A+vJ9eBBZ@M{H%hl|-x^hk!k2$!RU|t6|wYg`{
zp6z+Et;qOhWMsVWRAw$G{FA6Md=EAahef}o>(;HiTn9I`xuHsh!@appnKH#F<BO=r
z@lIyuf~8!`k83ODw9z2fa7OLgwO8ukrZ)G21q(b!wiOxQUcGvaaXK@X(>`*tyug4>
zqamWLEOL0S*1=6}?ytW3$}@1k{r1~h8DF*)5(=Xdk(tX$5S=b7P+-$|h-@ogy?XU^
zI=H=}&25tLWgGkV?>{1FP}9$W1DlQBzI}T|=m2ie!R>Z!?hzwKXk~oawt)i&KIe2#
z=#}yU2{xSr<<@hd;QE6OZY*9^Sm%es-L*aU+;iHA7q)58pg}`X>%jUqunnivH*MNf
zwNj-@+jMZdO`H3PC!R1ujS$^OgA6s>9%!&>fc5LwS3?5(ojSPPqRl;c@L(g<(61g8
zbf^XFzyGQc)>#XQ?04zlPPI1oJ@?#Wgc_G90|n~;Uw#F?#}0$AYSpTXal`nt4sNUi
zR9G^FuOx4y;weTpv`|yuaQN`ycc50{&%bRThKPUx>Gv+fP~WdQxRa^PjR_Uiw{Kq~
z)QB&?RiHlkM=fASfK51-E?rt5;huYSa3@2X+lq`YWtPW`8PiLkJ{fA-L%@y#n?_l<
zaA5-qn(N?BPfu4^b%Mj4-zejI?X}lxdupbe8$W)0cbr{(n2Qa>D7hGguw-RrH8G{>
zYuvc8<J#Pm@kLmv7HXz4L3~JtK%MuGTENZ&Y(n$dXP-4k)ZbxU&)vLvb4B@GCpMPT
zu3bAV)XdC<NWP8&b>2|ZHUhQ=Y#M0RtXZuQuYFVpH`Z7x_O$VAR%CoxkLlB=w`aX%
z*V{l0WC0Sau({flrmsVX4hpN}V`7^!zD=7p)%Mi<=fGl!Rsysh=&*eRYztu1Sd%AD
z?qo{S*R^X`+uGce@r9;`7Ha03=VejYY4T`>TfnvmHeuoo8%HB_mnC+zxhdmYuU<VZ
z)Fn!k*v}hTf!Pdmq>Th@8(`CLnVFe4n9}rF(dMR%FIMzuq2_oxhaMvxCeN(_E@0aP
zn_zKL#FVD5U%!4hH1`eiysB2MT3V<%1Io!FlpsEe!3JWq7>q{PIE}5lB;jWR1`Ifb
z?5$h38fAPLv%=|pfjagdwSXNX*o2OOM<%!t@P7hs#DA+QRjO!vYDO6{AWNW*9ctQ6
zz>WiK8jzu)Cb%Da>@kJ7Z-qq-TBsQpzIN@}ngVrvPz%^`LLCP1$tR!uw+U{pe%Bqt
zl{{SZ5H3?5<AYmzY=_|Hax5LVy3e@wlFQTt=J;Taw4Z?O5ZE*-7trbe&h0a<mgmCa
zNT<m2_yHHN9R!;|-hKDo&*uhkZtqdwgi;U!a{M4i+fcxE7;GAtA~m^z9Qhs<sVLqP
z?GSnG4CDfK0>Gy75@p3AL5_S*4MEDS3B=AooSPj5>;!;KLlf?vJ$sIg1e(vO`bvS!
z+?*lrIS0CcoglCYDb-CW-5Z9RI^C2s7J!`tI4@hK@dMcsX92*SzgxF%6L##_QE}$X
znQbwiy+3hhlaj+05U|6RNZ=z@oEN|fo5F~zK9s=INYN1%5U?YRAy55dfqedHinK&5
zkYfP>JI5CC%tsawuzloAX-bX-1neAJ$TJ^VK*08qGo>jx77(y=Y$4BlWB~!&N6wU{
b<XGT;)oaV+3*z)L00000NkvXXu0mjf@PT8C

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
deleted file mode 100644
index c792c916..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/MainWindow.h
+++ /dev/null
@@ -1,433 +0,0 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero
-//
-//    This file is part of D-FaLL-System.
-//    
-//    D-FaLL-System is free software: you can redistribute it and/or modify
-//    it under the terms of the GNU General Public License as published by
-//    the Free Software Foundation, either version 3 of the License, or
-//    (at your option) any later version.
-//    
-//    D-FaLL-System is distributed in the hope that it will be useful,
-//    but WITHOUT ANY WARRANTY; without even the implied warranty of
-//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-//    GNU General Public License for more details.
-//    
-//    You should have received a copy of the GNU General Public License
-//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
-//    
-//
-//    ----------------------------------------------------------------------------------
-//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
-//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
-//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
-//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
-//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
-//
-//
-//    DESCRIPTION:
-//    Main window of the Student's GUI
-//
-//    ----------------------------------------------------------------------------------
-
-
-#ifndef MAINWINDOW_H
-#define MAINWINDOW_H
-
-#include <QMainWindow>
-#include <QShortcut>
-
-#include <std_msgs/Int32.h>
-#include <std_msgs/Float32.h>
-
-#include "rosNodeThread_for_studentGUI.h"
-
-#include "dfall_pkg/CrazyflieContext.h"
-#include "dfall_pkg/CrazyflieData.h"
-#include "dfall_pkg/Setpoint.h"
-#include "dfall_pkg/SetpointV2.h"
-#include "dfall_pkg/ViconSubscribeObjectName.h"
-
-
-// Types of controllers being used:
-#define SAFE_CONTROLLER    1
-#define DEMO_CONTROLLER    2
-#define STUDENT_CONTROLLER 3
-#define MPC_CONTROLLER     4
-#define REMOTE_CONTROLLER  5
-#define TUNING_CONTROLLER  6
-#define PICKER_CONTROLLER  7
-
-
-// Commands for CrazyRadio
-#define CMD_RECONNECT  0
-#define CMD_DISCONNECT 1
-
-// CrazyRadio states:
-#define CONNECTED        0
-#define CONNECTING       1
-#define DISCONNECTED     2
-
-// The constants that "command" changes in the
-// operation state of this agent. These "commands"
-// 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
-#define CMD_USE_STUDENT_CONTROLLER   3
-#define CMD_USE_MPC_CONTROLLER       4
-#define CMD_USE_REMOTE_CONTROLLER    5
-#define CMD_USE_TUNING_CONTROLLER    6
-#define CMD_USE_PICKER_CONTROLLER    7
-
-#define CMD_CRAZYFLY_TAKE_OFF        11
-#define CMD_CRAZYFLY_LAND            12
-#define CMD_CRAZYFLY_MOTORS_OFF      13
-
-// Flying States
-#define STATE_MOTORS_OFF 1
-#define STATE_TAKE_OFF   2
-#define STATE_FLYING     3
-#define STATE_LAND       4
-
-// Battery states
-#define BATTERY_STATE_NORMAL 0
-#define BATTERY_STATE_LOW    1
-
-// Battery label image index
-#define BATTERY_LABEL_IMAGE_INDEX_EMPTY     0
-#define BATTERY_LABEL_IMAGE_INDEX_20        1
-#define BATTERY_LABEL_IMAGE_INDEX_40        2
-#define BATTERY_LABEL_IMAGE_INDEX_60        3
-#define BATTERY_LABEL_IMAGE_INDEX_80        4
-#define BATTERY_LABEL_IMAGE_INDEX_FULL      5
-#define BATTERY_LABEL_IMAGE_INDEX_UNKNOWN   6
-
-// For which controller parameters to load
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT           1
-#define LOAD_YAML_DEMO_CONTROLLER_AGENT           2
-#define LOAD_YAML_STUDENT_CONTROLLER_AGENT        3
-#define LOAD_YAML_MPC_CONTROLLER_AGENT            4
-#define LOAD_YAML_REMOTE_CONTROLLER_AGENT         5
-#define LOAD_YAML_TUNING_CONTROLLER_AGENT         6
-#define LOAD_YAML_PICKER_CONTROLLER_AGENT         7
-
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR     11
-#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR     12
-#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR  13
-#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR      14
-#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR   15
-#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR   16
-#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR   17
-
-
-// FOR WHICH BUTTON WAS PRESSED IN THE PICKER CONTOLLER
-#define PICKER_BUTTON_GOTOSTART     1
-#define PICKER_BUTTON_ATTACH        2
-#define PICKER_BUTTON_PICKUP        3
-#define PICKER_BUTTON_GOTOEND       4
-#define PICKER_BUTTON_PUTDOWN       5
-#define PICKER_BUTTON_SQUAT         6
-#define PICKER_BUTTON_JUMP          7
-
-#define PICKER_BUTTON_1             11
-#define PICKER_BUTTON_2             12
-#define PICKER_BUTTON_3             13
-#define PICKER_BUTTON_4             14
-
-
-// Universal constants
-#define PI 3.141592653589
-
-#define RAD2DEG 180.0/PI
-#define DEG2RAD PI/180.0
-
-namespace Ui {
-class MainWindow;
-}
-
-class MainWindow : public QMainWindow
-{
-    Q_OBJECT
-
-public:
-    explicit MainWindow(int argc, char **argv, QWidget *parent = 0);
-    ~MainWindow();
-
-private slots:
-    void updateNewViconData(const ptrToMessage& p_msg);
-
-    // # RF Crazyradio Connect Disconnect
-    void on_RF_Connect_button_clicked();
-    void on_RF_disconnect_button_clicked();
-
-    // # Take off, lanf, motors off
-    void on_take_off_button_clicked();
-    void on_land_button_clicked();
-    void on_motors_OFF_button_clicked();
-
-    // # Setpoint
-    void on_set_setpoint_button_safe_clicked();
-    void on_set_setpoint_button_demo_clicked();
-    void on_set_setpoint_button_student_clicked();
-    void on_set_setpoint_button_mpc_clicked();
-
-    // # Load Yaml when acting as the GUI for an Agent
-    void on_load_safe_yaml_button_clicked();
-    void on_load_demo_yaml_button_clicked();
-    void on_load_student_yaml_button_clicked();
-    void on_load_mpc_yaml_button_clicked();
-    void on_load_remote_yaml_button_clicked();
-    void on_load_tuning_yaml_button_clicked();
-    void on_load_picker_yaml_button_clicked();
-
-    // # Enable controllers
-    void on_enable_safe_controller_clicked();
-    void on_enable_demo_controller_clicked();
-    void on_enable_student_controller_clicked();
-    void on_enable_mpc_controller_clicked();
-    void on_enable_remote_controller_clicked();
-    void on_enable_tuning_controller_clicked();
-    void on_enable_picker_controller_clicked();
-
-    
-
-    void on_demoButton_1_clicked();
-    void on_demoButton_2_clicked();
-    void on_demoButton_3_clicked();
-
-    void on_studentButton_1_clicked();
-    void on_studentButton_2_clicked();
-    void on_studentButton_3_clicked();
-
-    // Buttons within the REMOTE controller tab
-    void on_remote_subscribe_button_clicked();
-    void on_remote_unsubscribe_button_clicked();
-    void on_remote_activate_button_clicked();
-    void on_remote_deactivate_button_clicked();
-
-    // Buttons within the TUNING controller tab
-    void on_tuning_test_horizontal_button_clicked();
-    void on_tuning_test_vertical_button_clicked();
-    void on_tuning_test_heading_button_clicked();
-    void on_tuning_test_all_button_clicked();
-    void on_tuning_test_circle_button_clicked();
-    void on_tuning_slider_horizontal_valueChanged(int value);
-    void on_tuning_slider_vertical_valueChanged(int value);
-    void on_tuning_slider_heading_valueChanged(int value);
-
-    // Interations with the PICKER controller tab
-    // > For the buttons
-    void on_picker_gotostart_button_clicked();
-    void on_picker_attach_button_clicked();
-    void on_picker_pickup_button_clicked();
-    void on_picker_gotoend_button_clicked();
-    void on_picker_putdown_button_clicked();
-    void on_picker_squat_button_clicked();
-    void on_picker_jump_button_clicked();
-    void on_picker_1_button_clicked();
-    void on_picker_2_button_clicked();
-    void on_picker_3_button_clicked();
-    void on_picker_4_button_clicked();
-    // > For the sliders
-    void on_picker_x_slider_valueChanged(int value);
-    void on_picker_y_slider_valueChanged(int value);
-    void on_picker_z_slider_valueChanged(int value);
-    void on_picker_mass_slider_valueChanged(int value);
-    // > For the dial
-    void on_picker_yaw_dial_valueChanged(int value);
-
-
-
-
-
-private:
-    Ui::MainWindow *ui;
-
-    QShortcut* m_close_GUI_shortcut;
-
-    rosNodeThread* m_rosNodeThread;
-    int m_radio_status;
-    float m_battery_voltage;
-    int m_battery_level;
-
-    std::string m_ros_namespace;
-
-    ros::Timer m_timer_yaml_file_for_safe_controller;
-    ros::Timer m_timer_yaml_file_for_demo_controller;
-    ros::Timer m_timer_yaml_file_for_student_controller;
-    ros::Timer m_timer_yaml_file_for_mpc_controller;
-    ros::Timer m_timer_yaml_file_for_remote_controller;
-    ros::Timer m_timer_yaml_file_for_tuning_controller;
-    ros::Timer m_timer_yaml_file_for_picker_controller;
-
-
-    int m_student_id;
-    CrazyflieContext m_context;
-
-    Setpoint m_safe_setpoint;
-    Setpoint m_demo_setpoint;
-    Setpoint m_student_setpoint;
-    Setpoint m_mpc_setpoint;
-    Setpoint m_picker_setpoint;
-
-    int m_flying_state;
-    QMutex m_flying_state_mutex;
-    QMutex voltage_field_mutex;
-    QMutex battery_status_label_mutex;
-    QMutex rf_status_label_mutex;
-    int m_battery_state;
-    // BATTERY EMPTY VOLTAGES (THESE SHOULD BE READ IN AS PARAMTERS)
-    //const std::vector<float> m_cutoff_voltages {3.1966,        3.2711,        3.3061,        3.3229,        3.3423,        3.3592,        3.3694,        3.385,        3.4006,        3.4044,        3.4228,        3.4228,        3.4301,        3.4445,        3.4531,        3.4677,        3.4705,        3.4712,        3.4756,        3.483,        3.4944,        3.5008,        3.5008,        3.5084,        3.511,        3.5122,        3.5243,        3.5329,        3.5412,        3.5529,        3.5609,        3.5625,        3.5638,        3.5848,        3.6016,        3.6089,        3.6223,        3.628,        3.6299,        3.6436,        3.6649,        3.6878,        3.6983,        3.7171,        3.7231,        3.7464,        3.7664,        3.7938,        3.8008,        3.816,        3.8313,        3.8482,        3.866,        3.8857,        3.8984,        3.9159,        3.9302,        3.9691,        3.997,        4.14    };
-    const float battery_voltage_empty_while_flying      =  2.80;   // in Volts
-    const float battery_voltage_empty_while_motors_off  =  3.30;  // in Volts
-    // BATTERY FULL VOLTAGES
-    const float battery_voltage_full_while_flying      =  3.70;   // in Volts
-    const float battery_voltage_full_while_motors_off  =  4.20;   // in Volts
-
-    int m_battery_label_image_current_index;
-
-    ros::Publisher crazyRadioCommandPublisher;
-    ros::Subscriber crazyRadioStatusSubscriber;
-    ros::Publisher FlyingAgentClientCommandPublisher;
-    ros::Subscriber CFBatterySubscriber;
-    ros::Subscriber flyingStateSubscriber;
-    ros::Subscriber batteryStateSubscriber;
-
-    ros::Publisher controllerSetpointPublisher;
-    ros::Subscriber safeSetpointSubscriber;
-
-    // SUBSCRIBERS AND PUBLISHERS:
-    // > For the Demo Controller SETPOINTS
-    ros::Publisher  demoSetpointPublisher;
-    ros::Subscriber demoSetpointSubscriber;
-    // > For the Student Controller SETPOINTS
-    ros::Publisher  studentSetpointPublisher;
-    ros::Subscriber studentSetpointSubscriber;
-    // > For the MPC Controller SETPOINTS
-    ros::Publisher  mpcSetpointPublisher;
-    ros::Subscriber mpcSetpointSubscriber;
-
-    // > For the Remote Controller subscribe action
-    ros::Publisher remoteSubscribePublisher;
-    // > For the Remote Controller activate action
-    ros::Publisher remoteActivatePublisher;
-    // > For the Remote Controller data
-    ros::Subscriber remoteDataSubscriber;
-    // > For the Remote Control setpoint
-    ros::Subscriber remoteControlSetpointSubscriber;
-
-    // > For the TUNING CONTROLLER "test" button publisher
-    ros::Publisher tuningActivateTestPublisher;
-    // > For the TUNING CONTOLLER "gain" sliders
-    ros::Publisher tuningHorizontalGainPublisher;
-    ros::Publisher tuningVerticalGainPublisher;
-    ros::Publisher tuningHeadingGainPublisher;
-
-
-
-	// > For the PICKER CONTROLLER
-	ros::Publisher  pickerButtonPressedPublisher;
-	ros::Publisher  pickerZSetpointPublisher;
-	ros::Publisher  pickerYawSetpointPublisher;
-	ros::Publisher  pickerMassPublisher;
-	ros::Publisher  pickerXAdjustmentPublisher;
-	ros::Publisher  pickerYAdjustmentPublisher;
-	ros::Publisher  pickerSetpointPublisher;
-	ros::Subscriber pickerSetpointSubscriber;
-    ros::Subscriber pickerSetpointToGUISubscriber;
-
-    ros::Publisher  pickerButtonPressedWithSetpointPublisher;
-
-    bool shouldSendWithSetpoint_for_pickerButtons = true;
-
-
-
-
-    ros::Publisher demoCustomButtonPublisher;
-    ros::Publisher studentCustomButtonPublisher;
-
-    ros::Subscriber DBChangedSubscriber;
-
-
-
-    // > 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
-    ros::Publisher requestLoadControllerYamlPublisher;
-
-    // Subscriber for locking the load the controller YAML
-    // parameters when the Coordintor GUI requests a load
-    ros::Subscriber requestLoadControllerYaml_from_my_GUI_Subscriber;
-
-
-    ros::Subscriber controllerUsedSubscriber;
-
-    ros::ServiceClient centralManager;
-
-    // callbacks
-    void crazyRadioStatusCallback(const std_msgs::Int32& msg);
-    void CFBatteryCallback(const std_msgs::Float32& msg);
-    void flyingStateChangedCallback(const std_msgs::Int32& msg);
-
-    void safeSetpointCallback(const Setpoint& newSetpoint);
-    void demoSetpointCallback(const Setpoint& newSetpoint);
-    void studentSetpointCallback(const Setpoint& newSetpoint);
-    void mpcSetpointCallback(const Setpoint& newSetpoint);
-    void pickerSetpointCallback(const Setpoint& newSetpoint);
-
-
-    void remoteDataCallback(const CrazyflieData& objectData);
-    void remoteControlSetpointCallback(const CrazyflieData& setpointData);
-
-
-    // > For actually sending the button message
-    void send_picker_button_clicked_message(int button_index);
-    void send_picker_button_clicked_message_with_setpoint(const SetpointV2& setpointV2_to_send);
-    
-
-    void DBChangedCallback(const std_msgs::Int32& msg);
-
-    // # Load Yaml when acting as the GUI for an Agent
-    void safeYamlFileTimerCallback(const ros::TimerEvent&);
-    void demoYamlFileTimerCallback(const ros::TimerEvent&);
-    void studentYamlFileTimerCallback(const ros::TimerEvent&);
-    void mpcYamlFileTimerCallback(const ros::TimerEvent&);
-    void remoteYamlFileTimerCallback(const ros::TimerEvent&);
-    void tuningYamlFileTimerCallback(const ros::TimerEvent&);
-    void pickerYamlFileTimerCallback(const ros::TimerEvent&);
-    
-
-
-    void requestLoadControllerYaml_from_my_GUI_Callback(const std_msgs::Int32& msg);
-    void controllerUsedChangedCallback(const std_msgs::Int32& msg);
-    void batteryStateChangedCallback(const std_msgs::Int32& msg);
-
-    float fromVoltageToPercent(float voltage);
-    void updateBatteryVoltage(float battery_voltage);
-    void setCrazyRadioStatus(int radio_status);
-    void loadCrazyflieContext();
-    void coordinatesToLocal(CrazyflieData& cf);
-
-    void initialize_demo_setpoint();
-    void initialize_student_setpoint();
-    void initialize_mpc_setpoint();
-    void initialize_picker_setpoint();
-
-
-    void disableGUI();
-    void enableGUI();
-    void highlightSafeControllerTab();
-    void highlightDemoControllerTab();
-    void highlightStudentControllerTab();
-    void highlightMpcControllerTab();
-    void highlightRemoteControllerTab();
-    void highlightTuningControllerTab();
-    void highlightPickerControllerTab();
-
-    bool setpointInsideBox(Setpoint setpoint, CrazyflieContext context);
-    Setpoint correctSetpointBox(Setpoint setpoint, CrazyflieContext context);
-
-};
-
-#endif // MAINWINDOW_H
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
deleted file mode 100644
index 823094a0..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/include/rosNodeThread_for_studentGUI.h
+++ /dev/null
@@ -1,93 +0,0 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Angel Romero
-//
-//    This file is part of D-FaLL-System.
-//    
-//    D-FaLL-System is free software: you can redistribute it and/or modify
-//    it under the terms of the GNU General Public License as published by
-//    the Free Software Foundation, either version 3 of the License, or
-//    (at your option) any later version.
-//    
-//    D-FaLL-System is distributed in the hope that it will be useful,
-//    but WITHOUT ANY WARRANTY; without even the implied warranty of
-//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-//    GNU General Public License for more details.
-//    
-//    You should have received a copy of the GNU General Public License
-//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
-//    
-//
-//    ----------------------------------------------------------------------------------
-//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
-//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
-//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
-//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
-//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
-//
-//
-//    DESCRIPTION:
-//    Takes care of creating a ros node thread.
-//
-//    ----------------------------------------------------------------------------------
-
-
-#ifndef ___ROSNODETHREAD_FOR_STUDENTGUI_H___
-#define ___ROSNODETHREAD_FOR_STUDENTGUI_H___
-
-#include <QtCore>
-#include <QThread>
-#include <QStringList>
-#include <stdlib.h>
-#include <QMutex>
-#include <iostream>
-#include "assert.h"
-
-#include <ros/ros.h>
-#include <ros/network.h>
-#include "dfall_pkg/UnlabeledMarker.h"
-#include "dfall_pkg/CrazyflieData.h"
-#include "dfall_pkg/ViconData.h"
-
-using namespace dfall_pkg;
-
-typedef ViconData::ConstPtr ptrToMessage;
-
-Q_DECLARE_METATYPE(ptrToMessage)
-
-
-class rosNodeThread : public QObject {
-	Q_OBJECT
-public:
-    explicit rosNodeThread(int argc, char **pArgv, const char * node_name, QObject *parent = 0);
-    virtual ~rosNodeThread();
-
-    bool init();
-
-    // void messageCallback(const ViconData& data);
-    void messageCallback(const ptrToMessage& p_msg);
-
-    ros::ServiceClient m_read_db_client;
-    ros::ServiceClient m_update_db_client;
-    ros::ServiceClient m_command_db_client;
-
-
-signals:
-
-    void newViconData(const ptrToMessage& p_msg);
-
-public slots:
-    void run();
-
-private:
-    int m_Init_argc;
-    char** m_pInit_argv;
-    const char * m_node_name;
-
-    QThread * m_pThread;
-
-    ViconData m_vicon_data;
-
-    ros::Subscriber m_vicon_subscriber;
-    // ros::Publisher  sim_velocity;
-};
-#endif
-
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
deleted file mode 100644
index 3d74934f..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.cpp
+++ /dev/null
@@ -1,2181 +0,0 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero
-//
-//    This file is part of D-FaLL-System.
-//    
-//    D-FaLL-System is free software: you can redistribute it and/or modify
-//    it under the terms of the GNU General Public License as published by
-//    the Free Software Foundation, either version 3 of the License, or
-//    (at your option) any later version.
-//    
-//    D-FaLL-System is distributed in the hope that it will be useful,
-//    but WITHOUT ANY WARRANTY; without even the implied warranty of
-//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-//    GNU General Public License for more details.
-//    
-//    You should have received a copy of the GNU General Public License
-//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
-//    
-//
-//    ----------------------------------------------------------------------------------
-//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
-//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
-//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
-//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
-//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
-//
-//
-//    DESCRIPTION:
-//    Main window of the Student's GUI
-//
-//    ----------------------------------------------------------------------------------
-
-
-#include "MainWindow.h"
-#include "ui_MainWindow.h"
-#include <string>
-
-#include <ros/ros.h>
-#include <ros/network.h>
-#include <ros/package.h>
-
-#include "dfall_pkg/CMQuery.h"
-
-#include "dfall_pkg/ViconData.h"
-
-#include "dfall_pkg/CustomButton.h"
-
-MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
-    QMainWindow(parent),
-    ui(new Ui::MainWindow),
-    m_battery_level(0)
-{
-
-    ui->setupUi(this);
-
-    m_rosNodeThread = new rosNodeThread(argc, argv, "student_GUI");
-    m_rosNodeThread->init();
-
-    setCrazyRadioStatus(DISCONNECTED);
-
-    m_ros_namespace = ros::this_node::getNamespace();
-    ROS_INFO("[Student GUI] node namespace: %s", m_ros_namespace.c_str());
-
-    qRegisterMetaType<ptrToMessage>("ptrToMessage");
-    QObject::connect(m_rosNodeThread, SIGNAL(newViconData(const ptrToMessage&)), this, SLOT(updateNewViconData(const ptrToMessage&)));
-
-    ros::NodeHandle nodeHandle(m_ros_namespace);
-
-
-    // SUBSCRIBERS AND PUBLISHERS:
-    // > For the Demo Controller SETPOINTS and CUSTOM COMMANDS
-    demoSetpointPublisher     = nodeHandle.advertise<Setpoint>("DemoControllerService/Setpoint", 1);
-    demoSetpointSubscriber    = nodeHandle.subscribe("DemoControllerService/Setpoint", 1, &MainWindow::demoSetpointCallback, this);
-    demoCustomButtonPublisher = nodeHandle.advertise<CustomButton>("DemoControllerService/GUIButton", 1);
-    // > For the Student Controller SETPOINTS and CUSTOM COMMANDS
-    studentSetpointPublisher     = nodeHandle.advertise<Setpoint>("StudentControllerService/Setpoint", 1);
-    studentSetpointSubscriber    = nodeHandle.subscribe("StudentControllerService/Setpoint", 1, &MainWindow::studentSetpointCallback, this);
-    studentCustomButtonPublisher = nodeHandle.advertise<CustomButton>("StudentControllerService/GUIButton", 1);
-    // > For the MPC Controller SETPOINTS
-    mpcSetpointPublisher  = nodeHandle.advertise<Setpoint>("MpcControllerService/Setpoint", 1);
-    mpcSetpointSubscriber = nodeHandle.subscribe("MpcControllerService/Setpoint", 1, &MainWindow::mpcSetpointCallback, this);
-
-
-    // > For the Remote Controller subscribe action
-    remoteSubscribePublisher = nodeHandle.advertise<ViconSubscribeObjectName>("RemoteControllerService/ViconSubscribeObjectName", 1);
-    // > For the Remote Controller activate action
-    remoteActivatePublisher = nodeHandle.advertise<std_msgs::Int32>("RemoteControllerService/Activate", 1);
-    // > For the Remote Controller data
-    remoteDataSubscriber = nodeHandle.subscribe("RemoteControllerService/RemoteData", 1, &MainWindow::remoteDataCallback, this);;
-    // > For the Remote Controller data
-    remoteControlSetpointSubscriber = nodeHandle.subscribe("RemoteControllerService/RemoteControlSetpoint", 1, &MainWindow::remoteControlSetpointCallback, this);;
-
-
-    // > For the TUNING CONTROLLER "test" button publisher
-    tuningActivateTestPublisher = nodeHandle.advertise<std_msgs::Int32>("TuningControllerService/ActivateTest", 1);
-    // > For the TUNING CONTOLLER "gain" sliders
-    tuningHorizontalGainPublisher = nodeHandle.advertise<std_msgs::Int32>("TuningControllerService/HorizontalGain", 1);
-    tuningVerticalGainPublisher = nodeHandle.advertise<std_msgs::Int32>("TuningControllerService/VerticalGain", 1);
-    tuningHeadingGainPublisher = nodeHandle.advertise<std_msgs::Int32>("TuningControllerService/HeadingGain", 1);
-
-
-    // > For the PICKER CONTROLLER
-    pickerButtonPressedPublisher  =  nodeHandle.advertise<std_msgs::Int32>("PickerControllerService/ButtonPressed", 1);
-    pickerZSetpointPublisher      =  nodeHandle.advertise<std_msgs::Float32>("PickerControllerService/ZSetpoint", 1);
-    pickerYawSetpointPublisher    =  nodeHandle.advertise<std_msgs::Float32>("PickerControllerService/YawSetpoint", 1);
-    pickerMassPublisher           =  nodeHandle.advertise<std_msgs::Float32>("PickerControllerService/Mass", 1);
-    pickerXAdjustmentPublisher    =  nodeHandle.advertise<std_msgs::Float32>("PickerControllerService/XAdjustment", 1);
-    pickerYAdjustmentPublisher    =  nodeHandle.advertise<std_msgs::Float32>("PickerControllerService/YAdjustment", 1);
-    pickerSetpointPublisher       =  nodeHandle.advertise<Setpoint>("PickerControllerService/Setpoint", 1);
-    pickerSetpointSubscriber      =  nodeHandle.subscribe("PickerControllerService/Setpoint", 1, &MainWindow::pickerSetpointCallback, this);
-    pickerSetpointToGUISubscriber =  nodeHandle.subscribe("PickerControllerService/SetpointToGUI", 1, &MainWindow::pickerSetpointCallback, this);
-
-    pickerButtonPressedWithSetpointPublisher =  nodeHandle.advertise<SetpointV2>("PickerControllerService/ButtonPressedWithSetpoint", 1);
-
-    // SET ALL SLIDERS AND DIALS TO DEFAULT VALUES
-    ui->picker_z_slider->setValue( 40 );
-    ui->picker_mass_slider->setValue( 29 );
-    ui->picker_yaw_dial->setValue( 0 );
-    ui->picker_x_slider->setValue( 0 );
-    ui->picker_y_slider->setValue( 0 );
-
-    // SET ALL THE FIELDS TO DEFAULT VALUES
-    // > For goto start
-    ui->picker_gotostart_x->setText("-0.30");
-    ui->picker_gotostart_y->setText("+0.00");
-    ui->picker_gotostart_z->setText("+0.50");
-    // > For attach
-    ui->picker_attach_z->setText("+0.38");
-    // > For pickup
-    ui->picker_pickup_z->setText("+0.60");
-    // > For goto end
-    ui->picker_gotoend_x->setText("+0.30");
-    ui->picker_gotoend_y->setText("+0.00");
-    // > For putdown
-    ui->picker_putdown_z->setText("+0.39");
-    // > For squat
-    ui->picker_squat_z->setText("+0.35");
-    // > For jump
-    ui->picker_jump_z->setText("+0.50");
-    // > For the check boxes
-    ui->picker_gotostart_checkBox->setChecked(1);
-    ui->picker_attach_checkBox->setChecked(1);
-    ui->picker_pickup_checkBox->setChecked(1);
-    ui->picker_gotoend_checkBox->setChecked(1);
-    ui->picker_putdown_checkBox->setChecked(1);
-    ui->picker_squat_checkBox->setChecked(0);
-    ui->picker_jump_checkBox->setChecked(0);
-
-
-
-
-    // subscribers
-    crazyRadioStatusSubscriber = nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &MainWindow::crazyRadioStatusCallback, this);
-
-    CFBatterySubscriber = nodeHandle.subscribe("CrazyRadio/CFBattery", 1, &MainWindow::CFBatteryCallback, this);
-
-    flyingStateSubscriber = nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &MainWindow::flyingStateChangedCallback, this);
-
-    batteryStateSubscriber = nodeHandle.subscribe("FlyingAgentClient/batteryState", 1, &MainWindow::batteryStateChangedCallback, this);
-
-    controllerUsedSubscriber = nodeHandle.subscribe("FlyingAgentClient/controllerUsed", 1, &MainWindow::controllerUsedChangedCallback, this);
-
-
-    safeSetpointSubscriber = nodeHandle.subscribe("SafeControllerService/Setpoint", 1, &MainWindow::safeSetpointCallback, this);
-    DBChangedSubscriber = nodeHandle.subscribe("/my_GUI/DBChanged", 1, &MainWindow::DBChangedCallback, this);
-
-    ros::NodeHandle my_nodeHandle("~");
-    controllerSetpointPublisher = my_nodeHandle.advertise<Setpoint>("ControllerSetpoint", 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_FlyingAgentClient.advertise<std_msgs::Int32>("requestLoadControllerYaml", 1);
-
-
-    // Subscriber for locking the load the controller YAML
-    // parameters when the Coordintor GUI requests a load
-    requestLoadControllerYaml_from_my_GUI_Subscriber = nodeHandle.subscribe("/my_GUI/requestLoadControllerYaml", 1, &MainWindow::requestLoadControllerYaml_from_my_GUI_Callback, this);
-
-    // First get student ID
-    if(!nh_FlyingAgentClient.getParam("agentID", m_student_id))
-    {
-		ROS_ERROR("Failed to get agentID");
-	}
-
-    // Then, Central manager
-    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
-    ros::NodeHandle dfall_root_nodeHandle("/dfall");
-    centralManager = dfall_root_nodeHandle.serviceClient<CMQuery>("CentralManagerService/Query", false);
-    loadCrazyflieContext();
-
-
-
-
-    // Load default setpoint from the "SafeController" namespace of the "ParameterService"
-    std::vector<float> default_setpoint(4);
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service("ParameterService");
-    ros::NodeHandle nodeHandle_for_safeController(nodeHandle_to_own_agent_parameter_service, "SafeController");
-
-    if(!nodeHandle_for_safeController.getParam("defaultSetpoint", default_setpoint))
-    {
-        ROS_ERROR_STREAM("The StudentGUI could not find parameter 'defaultSetpoint', as called from main(...)");
-    }
-
-    // Copy the default setpoint into respective text fields of the GUI
-    ui->current_setpoint_x_safe->setText(QString::number(default_setpoint[0]));
-    ui->current_setpoint_y_safe->setText(QString::number(default_setpoint[1]));
-    ui->current_setpoint_z_safe->setText(QString::number(default_setpoint[2]));
-    ui->current_setpoint_yaw_safe->setText(QString::number(default_setpoint[3]));
-
-
-    disableGUI();
-    highlightSafeControllerTab();
-
-    // INITIALISE THE BATTERY STATE AS NORMAL
-    m_battery_state = BATTERY_STATE_NORMAL;
-
-    // SET THE BATTERY VOLTAGE FIELD TO BE BLANK
-    QString qstr = "-.-- V";
-    ui->voltage_field->setText(qstr);
-    // SET THE IMAGE FOR THE BATTERY STATUS LABEL
-    QPixmap battery_unknown_pixmap(":/images/battery_unknown.png");
-    ui->battery_status_label->setPixmap(battery_unknown_pixmap);
-    ui->battery_status_label->setScaledContents(true);
-    m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
-
-    // SET THE IMAGE FOR THE CRAZY RADIO STATUS LABEL
-    QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
-    ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
-    ui->rf_status_label->setScaledContents(true);
-
-    // SET THE IMAGE FOR THE FLYING STATE LABEL
-    QPixmap flying_state_off_pixmap(":/images/flying_state_off.png");
-    ui->flying_state_label->setPixmap(flying_state_off_pixmap);
-    ui->flying_state_label->setScaledContents(true);
-
-
-
-    //QPixmap battery_80_pixmap(":/images/battery_80.png");
-	//m_battery_80_pixmap = battery_80_pixmap.scaled(50,70,Qt::IgnoreAspectRatio);
-	// The syntax for "scaled" is (int width, int height, ...)
-
-
-    ui->error_label->setStyleSheet("QLabel { color : red; }");
-    ui->error_label->clear();
-
-    // Add keyboard shortcuts
-    // > for "all motors off", press the space bar
-    ui->motors_OFF_button->setShortcut(tr("Space"));
-    // > for "kill GUI node", press "CTRL+C" while the GUI window is the focus
-    m_close_GUI_shortcut = new QShortcut(QKeySequence(tr("CTRL+C")), this, SLOT(close()));
-
-
-    initialize_demo_setpoint();
-    initialize_student_setpoint();
-    initialize_mpc_setpoint();
-    initialize_picker_setpoint();
-}
-
-
-MainWindow::~MainWindow()
-{
-    delete ui;
-}
-
-void MainWindow::disableGUI()
-{
-    ui->motors_OFF_button->setEnabled(false);
-    ui->take_off_button->setEnabled(false);
-    ui->land_button->setEnabled(false);
-}
-
-void MainWindow::enableGUI()
-{
-    ui->motors_OFF_button->setEnabled(true);
-    if(m_battery_state == BATTERY_STATE_NORMAL)
-    {
-        ui->take_off_button->setEnabled(true);
-        ui->land_button->setEnabled(true);
-    }
-}
-
-void MainWindow::highlightSafeControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightPickerControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightDemoControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightStudentControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightMpcControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightRemoteControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::green);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::black);
-}
-void MainWindow::highlightTuningControllerTab()
-{
-    ui->tabWidget->tabBar()->setTabTextColor(0, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(1, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(2, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(3, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(4, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(5, Qt::black);
-    ui->tabWidget->tabBar()->setTabTextColor(6, Qt::green);
-}
-
-
-void MainWindow::DBChangedCallback(const std_msgs::Int32& msg)
-{
-    loadCrazyflieContext();
-    ROS_INFO("context reloaded in student_GUI");
-}
-
-void MainWindow::controllerUsedChangedCallback(const std_msgs::Int32& msg)
-{
-    switch(msg.data)
-    {
-        case SAFE_CONTROLLER:
-            highlightSafeControllerTab();
-            break;
-        case DEMO_CONTROLLER:
-            highlightDemoControllerTab();
-            break;
-        case STUDENT_CONTROLLER:
-            highlightStudentControllerTab();
-            break;
-        case MPC_CONTROLLER:
-            highlightMpcControllerTab();
-            break;
-        case REMOTE_CONTROLLER:
-            highlightRemoteControllerTab();
-            break;
-        case TUNING_CONTROLLER:
-            highlightTuningControllerTab();
-            break;
-        case PICKER_CONTROLLER:
-            highlightPickerControllerTab();
-            break;
-        default:
-            break;
-    }
-}
-
-void MainWindow::safeSetpointCallback(const Setpoint& newSetpoint)
-{
-    m_safe_setpoint = newSetpoint;
-    // here we get the new setpoint, need to update it in GUI
-    ui->current_setpoint_x_safe->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y_safe->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z_safe->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw_safe->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
-}
-
-void MainWindow::demoSetpointCallback(const Setpoint& newSetpoint)
-{
-    m_demo_setpoint = newSetpoint;
-    // here we get the new setpoint, need to update it in GUI
-    ui->current_setpoint_x_demo->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y_demo->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z_demo->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw_demo->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
-}
-
-void MainWindow::studentSetpointCallback(const Setpoint& newSetpoint)
-{
-    m_student_setpoint = newSetpoint;
-    // here we get the new setpoint, need to update it in GUI
-    ui->current_setpoint_x_student->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y_student->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z_student->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw_student->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
-}
-
-void MainWindow::mpcSetpointCallback(const Setpoint& newSetpoint)
-{
-    m_mpc_setpoint = newSetpoint;
-    // here we get the new setpoint, need to update it in GUI
-    ui->current_setpoint_x_mpc->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y_mpc->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z_mpc->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw_mpc->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
-}
-
-void MainWindow::pickerSetpointCallback(const Setpoint& newSetpoint)
-{
-    m_picker_setpoint = newSetpoint;
-    // here we get the new setpoint, need to update it in GUI
-    ui->picker_z_slider->setValue( int(newSetpoint.z*100.0) );
-    ui->picker_yaw_dial->setValue( int(newSetpoint.yaw * RAD2DEG) );
-    
-}
-
-void MainWindow::flyingStateChangedCallback(const std_msgs::Int32& msg)
-{
-	// PUT THE CURRENT STATE INTO THE CLASS VARIABLE
-	m_flying_state_mutex.lock();
-	m_flying_state = msg.data;
-	m_flying_state_mutex.unlock();
-
-	// UPDATE THE LABEL TO DISPLAY THE FLYING STATE
-    //QString qstr = "Flying State: ";
-    switch(msg.data)
-    {
-        case STATE_MOTORS_OFF:
-        {
-            //qstr.append("Motors OFF");
-            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
-            ui->flying_state_label->clear();
-            QPixmap flying_state_off_pixmap(":/images/flying_state_off.png");
-            ui->flying_state_label->setPixmap(flying_state_off_pixmap);
-            ui->flying_state_label->setScaledContents(true);
-            ui->flying_state_label->update();
-            break;
-        }
-
-        case STATE_TAKE_OFF:
-        {
-            //qstr.append("Take OFF");
-            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
-            ui->flying_state_label->clear();
-            QPixmap flying_state_enabling_pixmap(":/images/flying_state_enabling.png");
-            ui->flying_state_label->setPixmap(flying_state_enabling_pixmap);
-            ui->flying_state_label->setScaledContents(true);
-            ui->flying_state_label->update();
-            break;
-        }
-
-        case STATE_FLYING:
-        {
-            //qstr.append("Flying");
-            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
-            ui->flying_state_label->clear();
-            QPixmap flying_state_flying_pixmap(":/images/flying_state_flying.png");
-            ui->flying_state_label->setPixmap(flying_state_flying_pixmap);
-            ui->flying_state_label->setScaledContents(true);
-            ui->flying_state_label->update();
-            break;
-        }
-
-        case STATE_LAND:
-        {
-            //qstr.append("Land");
-            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
-            ui->flying_state_label->clear();
-            QPixmap flying_state_disabling_pixmap(":/images/flying_state_disabling.png");
-            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
-            ui->flying_state_label->setScaledContents(true);
-            ui->flying_state_label->update();
-            break;
-        }
-
-        default:
-        {
-            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
-            ui->flying_state_label->clear();
-            QPixmap flying_state_unknown_pixmap(":/images/flying_state_unknown.png");
-            ui->flying_state_label->setPixmap(flying_state_unknown_pixmap);
-            ui->flying_state_label->setScaledContents(true);
-            ui->flying_state_label->update();
-            break;
-        }
-    }
-    //ui->flying_state_label->setText(qstr);
-}
-
-void MainWindow::batteryStateChangedCallback(const std_msgs::Int32& msg)
-{
-    // switch case with unabling buttons motors off, take off, etc... when battery is low
-    QString qstr = "";
-    switch(msg.data)
-    {
-        case BATTERY_STATE_LOW:
-        {
-            // DISABLE THE TAKE OFF AND LAND BUTTONS
-            ui->take_off_button->setEnabled(false);
-            ui->land_button->setEnabled(false);
-            // ui->groupBox_4->setEnabled(false);
-
-			// SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
-            m_battery_state = BATTERY_STATE_LOW;
-            break;
-        }
-
-        case BATTERY_STATE_NORMAL:
-        {
-            // ui->groupBox_4->setEnabled(true);
-            ui->take_off_button->setEnabled(true);
-            ui->land_button->setEnabled(true);
-
-            // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
-            m_battery_state = BATTERY_STATE_NORMAL;
-            break;
-        }
-
-        default:
-            break;
-    }
-}
-
-
-void MainWindow::setCrazyRadioStatus(int radio_status)
-{
-    // add more things whenever the status is changed
-    switch(radio_status)
-    {
-        case CONNECTED:
-        {
-            // SET THE APPROPRIATE IMAGE FOR THE RADIOSTATUS LABEL
-            rf_status_label_mutex.lock();
-            //ui->rf_status_label->clear();
-            QPixmap rf_connected_pixmap(":/images/rf_connected.png");
-            ui->rf_status_label->setPixmap(rf_connected_pixmap);
-            ui->rf_status_label->setScaledContents(true);
-            //ui->rf_status_label->update();
-            rf_status_label_mutex.unlock();
-            // ENABLE THE REMAINDER OF THE GUI
-            enableGUI();
-            break;
-        }
-
-        case CONNECTING:
-        {
-            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
-            rf_status_label_mutex.lock();
-            //ui->rf_status_label->clear();
-            QPixmap rf_connecting_pixmap(":/images/rf_connecting.png");
-            ui->rf_status_label->setPixmap(rf_connecting_pixmap);
-            ui->rf_status_label->setScaledContents(true);
-            //ui->rf_status_label->update();
-            rf_status_label_mutex.unlock();
-            break;
-        }
-
-        case DISCONNECTED:
-        {
-            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
-            rf_status_label_mutex.lock();
-            //ui->rf_status_label->clear();
-            QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
-            ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
-            ui->rf_status_label->setScaledContents(true);
-            //ui->rf_status_label->update();
-            rf_status_label_mutex.unlock();
-            // SET THE BATTERY VOLTAGE FIELD TO BE BLANK
-            QString qstr = "-.-- V";
-            voltage_field_mutex.lock();
-            ui->voltage_field->setText(qstr);
-            voltage_field_mutex.unlock();
-            // SET THE APPROPRIATE IMAGE FOR THE BATTERY STATUS LABEL
-            battery_status_label_mutex.lock();
-            if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_UNKNOWN)
-			{
-				ui->battery_status_label->clear();
-	            QPixmap battery_unknown_pixmap(":/images/battery_unknown.png");
-	            ui->battery_status_label->setPixmap(battery_unknown_pixmap);
-	            ui->battery_status_label->setScaledContents(true);
-	            m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
-	            ui->battery_status_label->update();
-	        }
-            battery_status_label_mutex.unlock();
-            // DISABLE THE REMAINDER OF THE GUI
-            disableGUI();
-            break;
-        }
-
-        default:
-        {
-    		ROS_ERROR_STREAM("unexpected radio status: " << m_radio_status);
-            break;
-        }
-    }
-    this->m_radio_status = radio_status;
-}
-
-
-
-
-float MainWindow::fromVoltageToPercent(float voltage)
-{
-	// INITIALISE THE LOCAL VARIABLE FOR THE VOLTAGE WHEN FULL/EMPTY
-	float voltage_when_full;
-	float voltage_when_empty;
-
-	// COMPUTE THE PERCENTAGE DIFFERENTLY DEPENDING ON
-	// THE CURRENT FLYING STATE
-	m_flying_state_mutex.lock();
-	if (m_flying_state == STATE_MOTORS_OFF)
-	{
-		voltage_when_empty = battery_voltage_empty_while_motors_off;
-		voltage_when_full  = battery_voltage_full_while_motors_off;
-	}
-	else
-	{
-		voltage_when_empty = battery_voltage_empty_while_flying;
-		voltage_when_full  = battery_voltage_full_while_flying;
-	}
-	m_flying_state_mutex.unlock();
-	//voltage_when_empty = battery_voltage_empty_while_motors_off;
-	//voltage_when_full  = battery_voltage_full_while_motors_off;
-
-	// COMPUTE THE PERCENTAGE
-	float percentage = 100.0f * (voltage-voltage_when_empty)/(voltage_when_full-voltage_when_empty);
-
-
-	// CLIP THE PERCENTAGE TO BE BETWEEN [0,100]
-    // > This should not happen to often
-    if(percentage > 100.0f)
-    {
-        percentage = 100.0f;
-    }
-    if(percentage < 0.0f)
-    {
-        percentage = 0.0f;
-    }
-
-    return percentage;
-}
-
-void MainWindow::updateBatteryVoltage(float battery_voltage)
-{
-	// PUT THE VOLTAGE INTO THE CLASS VARIABLES
-    m_battery_voltage = battery_voltage;
-
-    // UPDATE THE BATTERY VOLTAGE FIELD
-    voltage_field_mutex.lock();
-    QString qstr = "";
-    qstr.append(QString::number(battery_voltage, 'f', 2));
-    qstr.append(" V");
-    ui->voltage_field->setText(qstr);
-    voltage_field_mutex.unlock();
-
-	// COMPUTE THE BATTERY VOLTAGE AS A PERCENTAGE
-	float battery_voltage_percentage = fromVoltageToPercent(battery_voltage);
-
-	//ROS_INFO_STREAM("Battery percentage = " << battery_voltage_percentage );
-
-	// UPDATE THE IMAGE DISPLAYED IN THE BATTERY VOLTAGE LABEL IMAGE
-	battery_status_label_mutex.lock();
-	switch(m_battery_state)
-	{
-		// WHEN THE BATTERY IS IN A LOW STATE
-		case BATTERY_STATE_LOW:
-        {
-			// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-			if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_EMPTY)
-			{
-				ui->battery_status_label->clear();
-				QPixmap battery_empty_pixmap(":/images/battery_empty.png");
-				ui->battery_status_label->setPixmap(battery_empty_pixmap);
-				ui->battery_status_label->setScaledContents(true);
-				m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
-				ui->battery_status_label->update();
-			}
-			break;
-        }
-
-		// WHEN THE BATTERY IS IN A NORMAL STATE
-		case BATTERY_STATE_NORMAL:
-        {
-
-			if (
-				((m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_EMPTY) && (battery_voltage_percentage <= 0.0f))
-				||
-				((m_battery_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_EMPTY) && (battery_voltage_percentage <= 2.0f))
-			)
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_EMPTY)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_empty_pixmap(":/images/battery_empty.png");
-					ui->battery_status_label->setPixmap(battery_empty_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
-					ui->battery_status_label->update();
-				}
-			}
-			else if (
-				((m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_20) && (battery_voltage_percentage <= 20.0f))
-				||
-				((m_battery_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_20) && (battery_voltage_percentage <= 22.0f))
-			)
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_20)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_20_pixmap(":/images/battery_20.png");
-					ui->battery_status_label->setPixmap(battery_20_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_20;
-					ui->battery_status_label->update();
-				}
-			}
-			else if (
-				((m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_40) && (battery_voltage_percentage <= 40.0f))
-				||
-				((m_battery_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_40) && (battery_voltage_percentage <= 42.0f))
-			)
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_40)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_40_pixmap(":/images/battery_40.png");
-					ui->battery_status_label->setPixmap(battery_40_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_40;
-					ui->battery_status_label->update();
-				}
-			}
-			else if (
-				((m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_60) && (battery_voltage_percentage <= 60.0f))
-				||
-				((m_battery_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_60) && (battery_voltage_percentage <= 62.0f))
-			)
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_60)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_60_pixmap(":/images/battery_60.png");
-					ui->battery_status_label->setPixmap(battery_60_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_60;
-					ui->battery_status_label->update();
-				}
-			}
-			else if (
-				((m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_80) && (battery_voltage_percentage <= 80.0f))
-				||
-				((m_battery_label_image_current_index == BATTERY_LABEL_IMAGE_INDEX_80) && (battery_voltage_percentage <= 82.0f))
-			)
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_80)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_80_pixmap(":/images/battery_80.png");
-					ui->battery_status_label->setPixmap(battery_80_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_80;
-					ui->battery_status_label->update();
-				}
-			}
-			else
-			{
-				if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_FULL)
-				{
-					// SET THE IMAGE FOR THE BATTERY STATUS LABEL
-					ui->battery_status_label->clear();
-					QPixmap battery_full_pixmap(":/images/battery_full.png");
-					ui->battery_status_label->setPixmap(battery_full_pixmap);
-					ui->battery_status_label->setScaledContents(true);
-					m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_FULL;
-					ui->battery_status_label->update();
-				}
-			}
-			break;
-        }
-
-		default:
-        {
-        	if (m_battery_label_image_current_index != BATTERY_LABEL_IMAGE_INDEX_UNKNOWN)
-			{
-	            // SET THE IMAGE FOR THE BATTERY STATUS LABEL
-	            ui->battery_status_label->clear();
-	            QPixmap battery_unknown_pixmap(":/images/battery_unknown.png");
-	            ui->battery_status_label->setPixmap(battery_unknown_pixmap);
-	            ui->battery_status_label->setScaledContents(true);
-	            m_battery_label_image_current_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
-				ui->battery_status_label->update();
-	        }
-			break;
-        }
-	}
-	battery_status_label_mutex.unlock();
-}
-
-void MainWindow::CFBatteryCallback(const std_msgs::Float32& msg)
-{
-    updateBatteryVoltage(msg.data);
-}
-
-void MainWindow::crazyRadioStatusCallback(const std_msgs::Int32& msg)
-{
-    ROS_INFO("[Student GUI] Callback CrazyRadioStatus called");
-    this->setCrazyRadioStatus(msg.data);
-}
-
-void MainWindow::loadCrazyflieContext()
-{
-	CMQuery contextCall;
-	contextCall.request.studentID = m_student_id;
-	ROS_INFO_STREAM("StudentID:" << m_student_id);
-
-	centralManager.waitForExistence(ros::Duration(-1));
-
-	if(centralManager.call(contextCall))
-    {
-		m_context = contextCall.response.crazyflieContext;
-		ROS_INFO_STREAM("CrazyflieContext:\n" << m_context);
-        // we now have the m_context variable with the current context. Put CF Name in label
-
-        QString qstr = "StudentID ";
-        qstr.append(QString::number(m_student_id));
-        qstr.append(" connected to CF ");
-        qstr.append(QString::fromStdString(m_context.crazyflieName));
-        ui->groupBox->setTitle(qstr);
-	}
-    else
-    {
-		ROS_ERROR("Failed to load context");
-	}
-
-	ros::NodeHandle nh("CrazyRadio");
-	nh.setParam("crazyFlieAddress", m_context.crazyflieAddress);
-}
-
-void MainWindow::coordinatesToLocal(CrazyflieData& cf)
-{
-	AreaBounds area = m_context.localArea;
-	float originX = (area.xmin + area.xmax) / 2.0;
-	float originY = (area.ymin + area.ymax) / 2.0;
-    // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
-    float originZ = 0.0;
-	// float originZ = (area.zmin + area.zmax) / 2.0;
-
-	cf.x -= originX;
-	cf.y -= originY;
-	cf.z -= originZ;
-}
-
-
-void MainWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to newViconData, from node
-{
-    for(std::vector<CrazyflieData>::const_iterator it = p_msg->crazyflies.begin(); it != p_msg->crazyflies.end(); ++it)
-    {
-		CrazyflieData global = *it;
-        if(global.crazyflieName == m_context.crazyflieName)
-        {
-            CrazyflieData local = global;
-            coordinatesToLocal(local);
-
-            // now we have the local coordinates, put them in the labels
-            ui->current_x_safe->setText(QString::number(local.x, 'f', 3));
-            ui->current_y_safe->setText(QString::number(local.y, 'f', 3));
-            ui->current_z_safe->setText(QString::number(local.z, 'f', 3));
-            ui->current_yaw_safe->setText(QString::number(local.yaw * RAD2DEG, 'f', 1));
-            ui->current_pitch_safe->setText(QString::number(local.pitch * RAD2DEG, 'f', 1));
-            ui->current_roll_safe->setText(QString::number(local.roll * RAD2DEG, 'f', 1));
-
-            ui->current_x_demo->setText(QString::number(local.x, 'f', 3));
-            ui->current_y_demo->setText(QString::number(local.y, 'f', 3));
-            ui->current_z_demo->setText(QString::number(local.z, 'f', 3));
-            ui->current_yaw_demo->setText(QString::number(local.yaw * RAD2DEG, 'f', 1));
-            ui->current_pitch_demo->setText(QString::number(local.pitch * RAD2DEG, 'f', 1));
-            ui->current_roll_demo->setText(QString::number(local.roll * RAD2DEG, 'f', 1));
-
-            ui->current_x_student->setText(QString::number(local.x, 'f', 3));
-            ui->current_y_student->setText(QString::number(local.y, 'f', 3));
-            ui->current_z_student->setText(QString::number(local.z, 'f', 3));
-            ui->current_yaw_student->setText(QString::number(local.yaw * RAD2DEG, 'f', 1));
-            ui->current_pitch_student->setText(QString::number(local.pitch * RAD2DEG, 'f', 1));
-            ui->current_roll_student->setText(QString::number(local.roll * RAD2DEG, 'f', 1));
-
-            // also update diff
-            ui->diff_x_safe->setText(QString::number(m_safe_setpoint.x - local.x, 'f', 3));
-            ui->diff_y_safe->setText(QString::number(m_safe_setpoint.y - local.y, 'f', 3));
-            ui->diff_z_safe->setText(QString::number(m_safe_setpoint.z - local.z, 'f', 3));
-            ui->diff_yaw_safe->setText(QString::number((m_safe_setpoint.yaw - local.yaw) * RAD2DEG, 'f', 1));
-
-            ui->diff_x_demo->setText(QString::number(m_demo_setpoint.x - local.x, 'f', 3));
-            ui->diff_y_demo->setText(QString::number(m_demo_setpoint.y - local.y, 'f', 3));
-            ui->diff_z_demo->setText(QString::number(m_demo_setpoint.z - local.z, 'f', 3));
-            ui->diff_yaw_demo->setText(QString::number((m_demo_setpoint.yaw - local.yaw) * RAD2DEG, 'f', 1));
-
-            ui->diff_x_student->setText(QString::number(m_student_setpoint.x - local.x, 'f', 3));
-            ui->diff_y_student->setText(QString::number(m_student_setpoint.y - local.y, 'f', 3));
-            ui->diff_z_student->setText(QString::number(m_student_setpoint.z - local.z, 'f', 3));
-            ui->diff_yaw_student->setText(QString::number((m_student_setpoint.yaw - local.yaw) * RAD2DEG, 'f', 1));
-        }
-    }
-}
-
-
-
-//    ----------------------------------------------------------------------------------
-// # RF Crazyradio Connect Disconnect
-void MainWindow::on_RF_Connect_button_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_RECONNECT;
-    this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("command reconnect published");
-}
-
-void MainWindow::on_RF_disconnect_button_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_DISCONNECT;
-    this->crazyRadioCommandPublisher.publish(msg);
-    ROS_INFO("command disconnect published");
-}
-
-
-
-//    ----------------------------------------------------------------------------------
-// # Take off, lanf, motors off
-void MainWindow::on_take_off_button_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_CRAZYFLY_TAKE_OFF;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_land_button_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_CRAZYFLY_LAND;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_motors_OFF_button_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-
-
-//    ----------------------------------------------------------------------------------
-// # Setpoint
-void MainWindow::on_set_setpoint_button_safe_clicked()
-{
-    Setpoint msg_setpoint;
-
-    // initialize setpoint to previous one
-
-    msg_setpoint.x = (ui->current_setpoint_x_safe->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y_safe->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z_safe->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw_safe->text()).toFloat();
-
-    if(!ui->new_setpoint_x_safe->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x_safe->text()).toFloat();
-
-    if(!ui->new_setpoint_y_safe->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y_safe->text()).toFloat();
-
-    if(!ui->new_setpoint_z_safe->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z_safe->text()).toFloat();
-
-    if(!ui->new_setpoint_yaw_safe->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw_safe->text()).toFloat() * DEG2RAD;
-
-
-    if(!setpointInsideBox(msg_setpoint, m_context))
-    {
-        ROS_INFO("Corrected setpoint, was out of bounds");
-
-        // correct the setpoint given the box size
-        msg_setpoint = correctSetpointBox(msg_setpoint, m_context);
-        ui->error_label->setText("Setpoint is outside safety box");
-    }
-    else
-    {
-        ui->error_label->clear();
-    }
-
-    this->controllerSetpointPublisher.publish(msg_setpoint);
-
-    ROS_INFO_STREAM("Setpoint change clicked with:" << msg_setpoint.x << ", "<< msg_setpoint.y << ", "<< msg_setpoint.z << ", "<< msg_setpoint.yaw);
-}
-
-void MainWindow::initialize_demo_setpoint()
-{
-    Setpoint msg_setpoint;
-    msg_setpoint.x = 0;
-    msg_setpoint.y = 0;
-    msg_setpoint.z = 0.4;
-    msg_setpoint.yaw = 0;
-
-    this->demoSetpointPublisher.publish(msg_setpoint);
-}
-
-void MainWindow::initialize_student_setpoint()
-{
-    Setpoint msg_setpoint;
-    msg_setpoint.x = 0;
-    msg_setpoint.y = 0;
-    msg_setpoint.z = 0.4;
-    msg_setpoint.yaw = 0;
-
-    this->studentSetpointPublisher.publish(msg_setpoint);
-}
-
-void MainWindow::initialize_mpc_setpoint()
-{
-    Setpoint msg_setpoint;
-    msg_setpoint.x = 0;
-    msg_setpoint.y = 0;
-    msg_setpoint.z = 0.4;
-    msg_setpoint.yaw = 0;
-
-    this->mpcSetpointPublisher.publish(msg_setpoint);
-}
-
-void MainWindow::initialize_picker_setpoint()
-{
-    Setpoint msg_setpoint;
-    msg_setpoint.x = 0;
-    msg_setpoint.y = 0;
-    msg_setpoint.z = 0.4;
-    msg_setpoint.yaw = 0;
-
-    this->pickerSetpointPublisher.publish(msg_setpoint);
-}
-
-void MainWindow::on_set_setpoint_button_demo_clicked()
-{
-    Setpoint msg_setpoint;
-
-    msg_setpoint.x = (ui->current_setpoint_x_demo->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y_demo->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z_demo->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw_demo->text()).toFloat();
-
-    if(!ui->new_setpoint_x_demo->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x_demo->text()).toFloat();
-    if(!ui->new_setpoint_y_demo->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y_demo->text()).toFloat();
-    if(!ui->new_setpoint_z_demo->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z_demo->text()).toFloat();
-    if(!ui->new_setpoint_yaw_demo->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw_demo->text()).toFloat() * DEG2RAD;
-
-    this->demoSetpointPublisher.publish(msg_setpoint);
-
-    ROS_INFO_STREAM("Setpoint change clicked with:" << msg_setpoint.x << ", "<< msg_setpoint.y << ", "<< msg_setpoint.z << ", "<< msg_setpoint.yaw);
-}
-
-void MainWindow::on_set_setpoint_button_student_clicked()
-{
-    Setpoint msg_setpoint;
-
-    msg_setpoint.x = (ui->current_setpoint_x_student->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y_student->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z_student->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw_student->text()).toFloat();
-
-    if(!ui->new_setpoint_x_student->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x_student->text()).toFloat();
-    if(!ui->new_setpoint_y_student->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y_student->text()).toFloat();
-    if(!ui->new_setpoint_z_student->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z_student->text()).toFloat();
-    if(!ui->new_setpoint_yaw_student->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw_student->text()).toFloat() * DEG2RAD;
-
-    this->studentSetpointPublisher.publish(msg_setpoint);
-
-    ROS_INFO_STREAM("Setpoint change clicked with:" << msg_setpoint.x << ", "<< msg_setpoint.y << ", "<< msg_setpoint.z << ", "<< msg_setpoint.yaw);
-}
-
-void MainWindow::on_set_setpoint_button_mpc_clicked()
-{
-    Setpoint msg_setpoint;
-
-    msg_setpoint.x = (ui->current_setpoint_x_mpc->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y_mpc->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z_mpc->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw_mpc->text()).toFloat();
-
-    if(!ui->new_setpoint_x_mpc->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x_mpc->text()).toFloat();
-    if(!ui->new_setpoint_y_mpc->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y_mpc->text()).toFloat();
-    if(!ui->new_setpoint_z_mpc->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z_mpc->text()).toFloat();
-    if(!ui->new_setpoint_yaw_mpc->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw_mpc->text()).toFloat() * DEG2RAD;
-
-    this->mpcSetpointPublisher.publish(msg_setpoint);
-
-    ROS_INFO_STREAM("Setpoint change clicked with:" << msg_setpoint.x << ", "<< msg_setpoint.y << ", "<< msg_setpoint.z << ", "<< msg_setpoint.yaw);
-}
-
-
-//    ----------------------------------------------------------------------------------
-// # Load Yaml when acting as the GUI for an Agent
-void MainWindow::on_load_safe_yaml_button_clicked()
-{
-    // Set the "load safe yaml" button to be disabled
-    ui->load_safe_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the safe controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_SAFE_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("Request load of safe controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::safeYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::safeYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load safe yaml" button again
-    ui->load_safe_yaml_button->setEnabled(true);
-}
-
-
-
-void MainWindow::on_load_demo_yaml_button_clicked()
-{
-    // Set the "load demo yaml" button to be disabled
-    ui->load_demo_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the demo controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_DEMO_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("Request load of demo controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_demo_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::demoYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::demoYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load demo yaml" button again
-    ui->load_demo_yaml_button->setEnabled(true);
-}
-
-
-
-void MainWindow::on_load_student_yaml_button_clicked()
-{
-    // Set the "load student yaml" button to be disabled
-    ui->load_student_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the student controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_STUDENT_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("Request load of student controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_student_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::studentYamlFileTimerCallback, this, true);    
-}
-
-void MainWindow::studentYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load student yaml" button again
-    ui->load_student_yaml_button->setEnabled(true);
-}
-
-
-
-void MainWindow::on_load_mpc_yaml_button_clicked()
-{
-    // Set the "load mpc yaml" button to be disabled
-    ui->load_mpc_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the mpc controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_MPC_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("Request load of mpc controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_mpc_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::mpcYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::mpcYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load mpc yaml" button again
-    ui->load_mpc_yaml_button->setEnabled(true);
-}
-
-
-
-
-void MainWindow::on_load_remote_yaml_button_clicked()
-{
-    // Set the "load remote yaml" button to be disabled
-    ui->load_remote_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the remote controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_REMOTE_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("[STUDENT GUI] Request load of remote controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_remote_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::remoteYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::remoteYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load remote yaml" button again
-    ui->load_remote_yaml_button->setEnabled(true);
-}
-
-
-
-void MainWindow::on_load_tuning_yaml_button_clicked()
-{
-    // Set the "load tuning yaml" button to be disabled
-    ui->load_tuning_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the tuning controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_TUNING_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("[STUDENT GUI] Request load of tuning controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_tuning_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::tuningYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::tuningYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load tuning yaml" button again
-    ui->load_tuning_yaml_button->setEnabled(true);
-}
-
-
-
-void MainWindow::on_load_picker_yaml_button_clicked()
-{
-    // Set the "load picker yaml" button to be disabled
-    ui->load_picker_yaml_button->setEnabled(false);
-
-    // Send a message requesting the parameters from the YAML
-    // file to be reloaded for the picker controller
-    std_msgs::Int32 msg;
-    msg.data = LOAD_YAML_PICKER_CONTROLLER_AGENT;
-    this->requestLoadControllerYamlPublisher.publish(msg);
-    ROS_INFO("[STUDENT GUI] Request load of picker controller YAML published");
-
-    // Start a timer which will enable the button in its callback
-    // > This is required because the agent node waits some time between
-    //   re-loading the values from the YAML file and then assigning then
-    //   to the local variable of the agent.
-    // > Thus we use this timer to prevent the user from clicking the
-    //   button in the GUI repeatedly.
-    ros::NodeHandle nodeHandle("~");
-    m_timer_yaml_file_for_picker_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::pickerYamlFileTimerCallback, this, true);
-}
-
-void MainWindow::pickerYamlFileTimerCallback(const ros::TimerEvent&)
-{
-    // Enble the "load picker yaml" button again
-    ui->load_picker_yaml_button->setEnabled(true);
-}
-
-
-void MainWindow::requestLoadControllerYaml_from_my_GUI_Callback(const std_msgs::Int32& msg)
-{
-    // Extract from the "msg" for which controller the YAML
-    // parameters should be loaded
-    int controller_to_load_yaml = msg.data;
-
-    // Create the "nodeHandle" needed in the switch cases below
-    ros::NodeHandle nodeHandle("~");
-
-    // Switch between loading for the different controllers
-    switch(controller_to_load_yaml)
-    {
-        case LOAD_YAML_SAFE_CONTROLLER_AGENT:
-        case LOAD_YAML_SAFE_CONTROLLER_COORDINATOR:
-            // Set the "load safe yaml" button to be disabled
-            ui->load_safe_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_safe_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::safeYamlFileTimerCallback, this, true);
-
-            break;
-
-        case LOAD_YAML_DEMO_CONTROLLER_AGENT:
-        case LOAD_YAML_DEMO_CONTROLLER_COORDINATOR:
-            // Set the "load demo yaml" button to be disabled
-            ui->load_demo_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_demo_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::demoYamlFileTimerCallback, this, true);    
-
-            break;
-
-        case LOAD_YAML_STUDENT_CONTROLLER_AGENT:
-        case LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR:
-            // Set the "load student yaml" button to be disabled
-            ui->load_student_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_student_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::studentYamlFileTimerCallback, this, true);    
-
-            break;
-
-        case LOAD_YAML_MPC_CONTROLLER_AGENT:
-        case LOAD_YAML_MPC_CONTROLLER_COORDINATOR:
-            // Set the "load mpc yaml" button to be disabled
-            ui->load_mpc_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_mpc_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::mpcYamlFileTimerCallback, this, true);    
-
-            break;
-
-        case LOAD_YAML_REMOTE_CONTROLLER_AGENT:
-        case LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR:
-            // Set the "load remote yaml" button to be disabled
-            ui->load_remote_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_remote_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::remoteYamlFileTimerCallback, this, true);    
-
-            break;
-
-        case LOAD_YAML_TUNING_CONTROLLER_AGENT:
-        case LOAD_YAML_TUNING_CONTROLLER_COORDINATOR:
-            // Set the "load tuning yaml" button to be disabled
-            ui->load_tuning_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_tuning_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::tuningYamlFileTimerCallback, this, true);    
-
-            break;
-
-        case LOAD_YAML_PICKER_CONTROLLER_AGENT:
-        case LOAD_YAML_PICKER_CONTROLLER_COORDINATOR:
-            // Set the "load picker yaml" button to be disabled
-            ui->load_picker_yaml_button->setEnabled(false);
-
-            // Start a timer which will enable the button in its callback
-            // > This is required because the agent node waits some time between
-            //   re-loading the values from the YAML file and then assigning then
-            //   to the local variable of the agent.
-            // > Thus we use this timer to prevent the user from clicking the
-            //   button in the GUI repeatedly.
-            m_timer_yaml_file_for_picker_controller = nodeHandle.createTimer(ros::Duration(1.5), &MainWindow::pickerYamlFileTimerCallback, this, true);    
-
-            break;
-
-        default:
-            ROS_INFO("Unknown 'all controllers to load yaml' command, thus nothing will be disabled");
-            break;
-    }
-}
-
-
-
-
-
-// # Enable controllers
-void MainWindow::on_enable_safe_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_SAFE_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_demo_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_DEMO_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_student_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_STUDENT_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_mpc_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_MPC_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_remote_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_REMOTE_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_tuning_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_TUNING_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-void MainWindow::on_enable_picker_controller_clicked()
-{
-    std_msgs::Int32 msg;
-    msg.data = CMD_USE_PICKER_CONTROLLER;
-    this->FlyingAgentClientCommandPublisher.publish(msg);
-}
-
-
-
-// # Custom command buttons - FOR DEMO CONTROLLER
-void MainWindow::on_demoButton_1_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 1;
-    msg_custom_button.command_code = 0;
-    this->demoCustomButtonPublisher.publish(msg_custom_button);
-
-    ROS_INFO("Demo button 1 pressed in GUI");
-}
-
-void MainWindow::on_demoButton_2_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 2;
-    msg_custom_button.command_code = 0;
-    this->demoCustomButtonPublisher.publish(msg_custom_button);
-    ROS_INFO("Demo button 2 pressed in GUI");
-}
-
-void MainWindow::on_demoButton_3_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 3;
-    msg_custom_button.command_code = (ui->demoField_3->text()).toFloat();
-    this->demoCustomButtonPublisher.publish(msg_custom_button);
-    ROS_INFO("Demo button 3 pressed in GUI");
-}
-
-
-
-
-
-// # Custom command buttons - FOR STUDENT CONTROLLER
-void MainWindow::on_studentButton_1_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 1;
-    msg_custom_button.command_code = 0;
-    this->studentCustomButtonPublisher.publish(msg_custom_button);
-
-    ROS_INFO("Student button 1 pressed in GUI");
-}
-
-void MainWindow::on_studentButton_2_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 2;
-    msg_custom_button.command_code = 0;
-    this->studentCustomButtonPublisher.publish(msg_custom_button);
-    ROS_INFO("Student button 2 pressed in GUI");
-}
-
-void MainWindow::on_studentButton_3_clicked()
-{
-    CustomButton msg_custom_button;
-    msg_custom_button.button_index = 3;
-    msg_custom_button.command_code = (ui->studentField_3->text()).toFloat();
-    this->studentCustomButtonPublisher.publish(msg_custom_button);
-    ROS_INFO("Student button 3 pressed in GUI");
-}
-
-
-
-Setpoint MainWindow::correctSetpointBox(Setpoint setpoint, CrazyflieContext context)
-{
-    Setpoint corrected_setpoint;
-    corrected_setpoint =  setpoint;
-
-    float x_size = context.localArea.xmax - context.localArea.xmin;
-    float y_size = context.localArea.ymax - context.localArea.ymin;
-    float z_size = context.localArea.zmax - context.localArea.zmin;
-
-    if(setpoint.x > x_size/2)
-        corrected_setpoint.x = x_size/2;
-    if(setpoint.y > y_size/2)
-        corrected_setpoint.y = y_size/2;
-    if(setpoint.z > z_size)
-        corrected_setpoint.z = z_size;
-
-    if(setpoint.x < -x_size/2)
-        corrected_setpoint.x = -x_size/2;
-    if(setpoint.y < -y_size/2)
-        corrected_setpoint.y = -y_size/2;
-    if(setpoint.z < 0)
-        corrected_setpoint.z = 0;
-
-    return corrected_setpoint;
-}
-
-bool MainWindow::setpointInsideBox(Setpoint setpoint, CrazyflieContext context)
-{
-
-    float x_size = context.localArea.xmax - context.localArea.xmin;
-    float y_size = context.localArea.ymax - context.localArea.ymin;
-    float z_size = context.localArea.zmax - context.localArea.zmin;
-    //position check
-	if((setpoint.x < -x_size/2) or (setpoint.x > x_size/2)) {
-		ROS_INFO_STREAM("x outside safety box");
-		return false;
-	}
-	if((setpoint.y < -y_size/2) or (setpoint.y > y_size/2)) {
-		ROS_INFO_STREAM("y outside safety box");
-		return false;
-	}
-	if((setpoint.z < 0) or (setpoint.z > z_size)) {
-		ROS_INFO_STREAM("z outside safety box");
-		return false;
-	}
-
-	return true;
-}
-
-
-
-
-
-
-
-
-// # Custom buttons for the REMOTE controller service
-void MainWindow::on_remote_subscribe_button_clicked()
-{
-    // Initialise the message
-    ViconSubscribeObjectName msg;
-    // Set the subscribe flag
-    msg.shouldSubscribe = true;
-    // Set the object name
-    msg.objectName = (ui->remote_object_name->text()).toUtf8().constData();
-    // Publish the message
-    this->remoteSubscribePublisher.publish(msg);
-}
-
-void MainWindow::on_remote_unsubscribe_button_clicked()
-{
-    // Initialise the message
-    ViconSubscribeObjectName msg;
-    // Set the subscribe flag
-    msg.shouldSubscribe = false;
-    // Set the object name
-    msg.objectName = (ui->remote_object_name->text()).toUtf8().constData();
-    // Publish the message
-    this->remoteSubscribePublisher.publish(msg);
-}
-
-void MainWindow::on_remote_activate_button_clicked()
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 1;
-    // Publish the message
-    this->remoteActivatePublisher.publish(msg);
-}
-
-void MainWindow::on_remote_deactivate_button_clicked()
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 0;
-    // Publish the message
-    this->remoteActivatePublisher.publish(msg);
-}
-
-void MainWindow::remoteDataCallback(const CrazyflieData& objectData)
-{
-    // Check if the object is occluded
-    if (objectData.occluded)
-    {
-        // Set the column heading label to have a red background
-        // > IMPORTANT: Set the background auto fill property to true
-        ui->remote_data_label->setAutoFillBackground(true);
-        // > Get the pallette currently set for the label
-        QPalette pal = ui->remote_roll_label->palette();
-        // > Set the palette property that will change the background
-        pal.setColor(QPalette::Window, QColor(Qt::red));
-        // > Update the palette for the label
-        ui->remote_data_label->setPalette(pal);
-    }
-    else
-    {
-        // Put the roll, pitch, yaw, and z data into the appropriate fields
-        ui->remote_data_roll ->setText(QString::number( objectData.roll  * RAD2DEG, 'f', 1));
-        ui->remote_data_pitch->setText(QString::number( objectData.pitch * RAD2DEG, 'f', 1));
-        ui->remote_data_yaw  ->setText(QString::number( objectData.yaw   * RAD2DEG, 'f', 1));
-        ui->remote_data_z    ->setText(QString::number( objectData.z,               'f', 2));
-
-        // Set the column heading label to have a "normal" background
-        // > IMPORTANT: Set the background auto fill property to true
-        ui->remote_data_label->setAutoFillBackground(false);
-        // > Get the pallette currently set for the roll label
-        QPalette pal = ui->remote_roll_label->palette();
-        // > Update the palette for the column heading label
-        ui->remote_data_label->setPalette(pal);
-    }
-}
-
-void MainWindow::remoteControlSetpointCallback(const CrazyflieData& setpointData)
-{
-    ui->remote_setpoint_roll ->setText(QString::number( setpointData.roll  * RAD2DEG, 'f', 1));
-    ui->remote_setpoint_pitch->setText(QString::number( setpointData.pitch * RAD2DEG, 'f', 1));
-    ui->remote_setpoint_yaw  ->setText(QString::number( setpointData.yaw   * RAD2DEG, 'f', 1));
-    ui->remote_setpoint_z    ->setText(QString::number( setpointData.z,               'f', 2));
-}
-
-
-
-
-
-
-// TUNING CONTROLLER TAB
-void MainWindow::on_tuning_test_horizontal_button_clicked()
-{
-	// Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 1;
-    // Publish the message
-    this->tuningActivateTestPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_test_vertical_button_clicked()
-{
-	// Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 2;
-    // Publish the message
-    this->tuningActivateTestPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_test_heading_button_clicked()
-{
-	// Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 3;
-    // Publish the message
-    this->tuningActivateTestPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_test_all_button_clicked()
-{
-	// Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 4;
-    // Publish the message
-    this->tuningActivateTestPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_test_circle_button_clicked()
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = 5;
-    // Publish the message
-    this->tuningActivateTestPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_slider_horizontal_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = value;
-    // Publish the message
-    this->tuningHorizontalGainPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_slider_vertical_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = value;
-    // Publish the message
-    this->tuningVerticalGainPublisher.publish(msg);
-}
-
-void MainWindow::on_tuning_slider_heading_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = value;
-    // Publish the message
-    this->tuningHeadingGainPublisher.publish(msg);
-}
-
-
-
-
-
-
-
-
-
-
-// PICKER CONTROLLER TAB
-
-// > FOR THE BUTTONS
-
-void MainWindow::send_picker_button_clicked_message(int button_index)
-{
-    // Initialise the message
-    std_msgs::Int32 msg;
-    // Set the msg data
-    msg.data = button_index;
-    // Publish the message
-    this->pickerButtonPressedPublisher.publish(msg);
-}
-
-void MainWindow::send_picker_button_clicked_message_with_setpoint(const SetpointV2& setpointV2_to_send)
-{
-    // Publish the message
-    this->pickerButtonPressedWithSetpointPublisher.publish(setpointV2_to_send);
-}
-
-void MainWindow::on_picker_gotostart_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_GOTOSTART);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_GOTOSTART;
-        msg_setpointV2.isChecked = ui->picker_gotostart_checkBox->isChecked();
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the (x,y,z) coordinates from the GUI
-        if(!ui->picker_gotostart_x->text().isEmpty())
-            msg_setpointV2.x = (ui->picker_gotostart_x->text()).toFloat();
-        if(!ui->picker_gotostart_y->text().isEmpty())
-            msg_setpointV2.y = (ui->picker_gotostart_y->text()).toFloat();
-        if(!ui->picker_gotostart_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_gotostart_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_attach_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_ATTACH);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_ATTACH;
-        msg_setpointV2.isChecked = ui->picker_attach_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the z coordinates from the GUI
-        if(!ui->picker_attach_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_attach_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_pickup_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_PICKUP);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_PICKUP;
-        msg_setpointV2.isChecked = ui->picker_pickup_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the z coordinates from the GUI
-        if(!ui->picker_pickup_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_pickup_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_gotoend_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_GOTOEND);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_GOTOEND;
-        msg_setpointV2.isChecked = ui->picker_gotoend_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the (x,y) coordinates from the GUI
-        if(!ui->picker_gotoend_x->text().isEmpty())
-            msg_setpointV2.x = (ui->picker_gotoend_x->text()).toFloat();
-        if(!ui->picker_gotoend_y->text().isEmpty())
-            msg_setpointV2.y = (ui->picker_gotoend_y->text()).toFloat();
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_putdown_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_PUTDOWN);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_PUTDOWN;
-        msg_setpointV2.isChecked = ui->picker_putdown_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the z coordinates from the GUI
-        if(!ui->picker_putdown_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_putdown_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_squat_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_SQUAT);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_SQUAT;
-        msg_setpointV2.isChecked = ui->picker_squat_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the z coordinates from the GUI
-        if(!ui->picker_squat_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_squat_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_jump_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_JUMP);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_JUMP;
-        msg_setpointV2.isChecked = ui->picker_jump_checkBox->isChecked();;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Get the z coordinates from the GUI
-        if(!ui->picker_jump_z->text().isEmpty())
-            msg_setpointV2.z = (ui->picker_jump_z->text()).toFloat();
-        // Update the z slider in the GUI
-        ui->picker_z_slider->setValue( int((msg_setpointV2.z+0.005)*100.0) );
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_1_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_1);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_1;
-        msg_setpointV2.isChecked = true;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_2_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_2);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_2;
-        msg_setpointV2.isChecked = true;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_3_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_3);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_3;
-        msg_setpointV2.isChecked = true;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-void MainWindow::on_picker_4_button_clicked()
-{
-    if (!shouldSendWithSetpoint_for_pickerButtons)
-    {
-        // Call the function that sends the message
-        send_picker_button_clicked_message(PICKER_BUTTON_4);
-    }
-    else
-    {
-        // Construct the setpoint
-        SetpointV2 msg_setpointV2;
-        msg_setpointV2.buttonID = PICKER_BUTTON_4;
-        msg_setpointV2.isChecked = true;
-        msg_setpointV2.x = 0.0;
-        msg_setpointV2.y = 0.0;
-        msg_setpointV2.z = 0.0;
-        msg_setpointV2.yaw = 0.0;
-        // Call the function that sends the message
-        send_picker_button_clicked_message_with_setpoint(msg_setpointV2);
-    }
-}
-
-
-
-// > FOR THE SLIDERS AND DIAL
-
-void MainWindow::on_picker_x_slider_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Float32 msg;
-    // Set the msg data
-    msg.data = float(value) / 100.0f;
-    // Publish the message
-    this->pickerXAdjustmentPublisher.publish(msg);
-}
-void MainWindow::on_picker_y_slider_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Float32 msg;
-    // Set the msg data
-    msg.data = float(value) / 100.0f;
-    // Publish the message
-    this->pickerYAdjustmentPublisher.publish(msg);
-}
-void MainWindow::on_picker_z_slider_valueChanged(int value)
-{
-    ROS_INFO_STREAM("[Student GUI] z slider int value " << value );
-    // Initialise the message
-    std_msgs::Float32 msg;
-    // Set the msg data
-    msg.data = float(value) / 100.0f;
-    // Publish the message
-    this->pickerZSetpointPublisher.publish(msg);
-}
-void MainWindow::on_picker_mass_slider_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Float32 msg;
-    // Set the msg data
-    msg.data = float(value);
-    // Publish the message
-    this->pickerMassPublisher.publish(msg);
-}
-void MainWindow::on_picker_yaw_dial_valueChanged(int value)
-{
-    // Initialise the message
-    std_msgs::Float32 msg;
-    // Set the msg data
-    msg.data = float(value) * DEG2RAD;
-    // Publish the message
-    this->pickerYawSetpointPublisher.publish(msg);
-}
-
-
-
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui
deleted file mode 100644
index 7890bdbb..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/MainWindow.ui
+++ /dev/null
@@ -1,5238 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<ui version="4.0">
- <class>MainWindow</class>
- <widget class="QMainWindow" name="MainWindow">
-  <property name="geometry">
-   <rect>
-    <x>0</x>
-    <y>0</y>
-    <width>1500</width>
-    <height>1000</height>
-   </rect>
-  </property>
-  <property name="sizePolicy">
-   <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
-    <horstretch>0</horstretch>
-    <verstretch>0</verstretch>
-   </sizepolicy>
-  </property>
-  <property name="maximumSize">
-   <size>
-    <width>1500</width>
-    <height>1000</height>
-   </size>
-  </property>
-  <property name="windowTitle">
-   <string>MainWindow</string>
-  </property>
-  <widget class="QWidget" name="centralWidget">
-   <layout class="QGridLayout" name="gridLayout">
-    <item row="1" column="1">
-     <layout class="QVBoxLayout" name="verticalLayout_4">
-      <property name="leftMargin">
-       <number>6</number>
-      </property>
-      <property name="topMargin">
-       <number>6</number>
-      </property>
-      <property name="rightMargin">
-       <number>6</number>
-      </property>
-      <property name="bottomMargin">
-       <number>6</number>
-      </property>
-      <item>
-       <widget class="QGroupBox" name="groupBox">
-        <property name="sizePolicy">
-         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Minimum">
-          <horstretch>0</horstretch>
-          <verstretch>0</verstretch>
-         </sizepolicy>
-        </property>
-        <property name="font">
-         <font>
-          <pointsize>18</pointsize>
-          <weight>50</weight>
-          <bold>false</bold>
-         </font>
-        </property>
-        <property name="title">
-         <string>StudentID # connected to CF #</string>
-        </property>
-        <property name="alignment">
-         <set>Qt::AlignCenter</set>
-        </property>
-        <layout class="QGridLayout" name="gridLayout_2"/>
-       </widget>
-      </item>
-      <item>
-       <widget class="Line" name="line_9">
-        <property name="orientation">
-         <enum>Qt::Horizontal</enum>
-        </property>
-       </widget>
-      </item>
-      <item>
-       <layout class="QHBoxLayout" name="horizontalLayout">
-        <property name="sizeConstraint">
-         <enum>QLayout::SetMaximumSize</enum>
-        </property>
-        <property name="leftMargin">
-         <number>6</number>
-        </property>
-        <property name="topMargin">
-         <number>6</number>
-        </property>
-        <property name="rightMargin">
-         <number>6</number>
-        </property>
-        <property name="bottomMargin">
-         <number>6</number>
-        </property>
-        <item>
-         <widget class="QPushButton" name="RF_disconnect_button">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>180</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>750</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="text">
-           <string>Disconnect</string>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QLabel" name="rf_status_label">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>95</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>95</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="text">
-           <string/>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QPushButton" name="RF_Connect_button">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>180</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>750</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="text">
-           <string>Connect</string>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QLineEdit" name="voltage_field">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>100</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>100</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="readOnly">
-           <bool>true</bool>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QLabel" name="battery_status_label">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>50</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>50</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-            <italic>true</italic>
-           </font>
-          </property>
-          <property name="text">
-           <string/>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QPushButton" name="take_off_button">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>180</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>750</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="text">
-           <string>Take Off</string>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QPushButton" name="land_button">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>180</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>750</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="text">
-           <string>Land</string>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QLabel" name="flying_state_label">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>90</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>90</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="text">
-           <string/>
-          </property>
-          <property name="alignment">
-           <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <widget class="QPushButton" name="motors_OFF_button">
-          <property name="sizePolicy">
-           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-            <horstretch>0</horstretch>
-            <verstretch>0</verstretch>
-           </sizepolicy>
-          </property>
-          <property name="minimumSize">
-           <size>
-            <width>180</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="maximumSize">
-           <size>
-            <width>750</width>
-            <height>70</height>
-           </size>
-          </property>
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-            <weight>75</weight>
-            <bold>true</bold>
-           </font>
-          </property>
-          <property name="text">
-           <string>Motors OFF</string>
-          </property>
-         </widget>
-        </item>
-       </layout>
-      </item>
-      <item>
-       <widget class="Line" name="line_8">
-        <property name="orientation">
-         <enum>Qt::Horizontal</enum>
-        </property>
-       </widget>
-      </item>
-      <item>
-       <layout class="QHBoxLayout" name="horizontalLayout_8">
-        <property name="leftMargin">
-         <number>6</number>
-        </property>
-        <property name="topMargin">
-         <number>6</number>
-        </property>
-        <property name="rightMargin">
-         <number>6</number>
-        </property>
-        <property name="bottomMargin">
-         <number>6</number>
-        </property>
-        <item>
-         <widget class="QTabWidget" name="tabWidget">
-          <property name="font">
-           <font>
-            <pointsize>16</pointsize>
-           </font>
-          </property>
-          <property name="currentIndex">
-           <number>3</number>
-          </property>
-          <property name="usesScrollButtons">
-           <bool>true</bool>
-          </property>
-          <property name="tabsClosable">
-           <bool>false</bool>
-          </property>
-          <widget class="QWidget" name="tab_safe">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <property name="font">
-            <font>
-             <pointsize>14</pointsize>
-            </font>
-           </property>
-           <attribute name="title">
-            <string>   Safe   </string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_5">
-            <item row="0" column="0">
-             <widget class="QGroupBox" name="groupBox_2">
-              <property name="title">
-               <string/>
-              </property>
-              <layout class="QGridLayout" name="gridLayout_3">
-               <item row="6" column="1">
-                <widget class="QLineEdit" name="current_roll_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="2" column="1">
-                <widget class="QLineEdit" name="current_y_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="1">
-                <widget class="QLineEdit" name="current_yaw_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="1">
-                <widget class="QLineEdit" name="current_z_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="0">
-                <widget class="QLabel" name="current_x_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>x [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="0">
-                <widget class="QLabel" name="current_z_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>z [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="2" column="0">
-                <widget class="QLabel" name="current_y_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>y [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="0">
-                <widget class="QLabel" name="current_yaw_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>yaw [deg] = </string>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="1">
-                <widget class="QLineEdit" name="current_x_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="5" column="0">
-                <widget class="QLabel" name="current_pitch_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>pitch [deg] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="6" column="0">
-                <widget class="QLabel" name="current_roll_label">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>roll [deg] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="5" column="1">
-                <widget class="QLineEdit" name="current_pitch_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="0" column="1">
-                <widget class="QLabel" name="label_4">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>Current</string>
-                 </property>
-                 <property name="alignment">
-                  <set>Qt::AlignCenter</set>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="2">
-                <widget class="QLineEdit" name="diff_x_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="2" column="2">
-                <widget class="QLineEdit" name="diff_y_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="2">
-                <widget class="QLineEdit" name="diff_z_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="2">
-                <widget class="QLineEdit" name="diff_yaw_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="0" column="2">
-                <widget class="QLabel" name="label_5">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>Difference</string>
-                 </property>
-                 <property name="alignment">
-                  <set>Qt::AlignCenter</set>
-                 </property>
-                </widget>
-               </item>
-              </layout>
-             </widget>
-            </item>
-            <item row="0" column="1">
-             <widget class="QGroupBox" name="groupBox_3">
-              <property name="title">
-               <string/>
-              </property>
-              <layout class="QGridLayout" name="gridLayout_4">
-               <item row="2" column="2">
-                <widget class="QLineEdit" name="new_setpoint_y_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="2">
-                <widget class="QLineEdit" name="new_setpoint_yaw_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="2">
-                <widget class="QLineEdit" name="new_setpoint_x_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                </widget>
-               </item>
-               <item row="2" column="1">
-                <widget class="QLineEdit" name="current_setpoint_y_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="1">
-                <widget class="QLineEdit" name="current_setpoint_x_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="0">
-                <widget class="QLabel" name="label_11">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>yaw [deg] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="0" column="1">
-                <widget class="QLabel" name="label_12">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>Current</string>
-                 </property>
-                 <property name="alignment">
-                  <set>Qt::AlignCenter</set>
-                 </property>
-                </widget>
-               </item>
-               <item row="1" column="0">
-                <widget class="QLabel" name="label_7">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>x [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="1">
-                <widget class="QLineEdit" name="current_setpoint_z_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="0">
-                <widget class="QLabel" name="label_9">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>z [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="2" column="0">
-                <widget class="QLabel" name="label_8">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>y [m] =</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="4" column="1">
-                <widget class="QLineEdit" name="current_setpoint_yaw_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="readOnly">
-                  <bool>true</bool>
-                 </property>
-                </widget>
-               </item>
-               <item row="5" column="2">
-                <widget class="QPushButton" name="set_setpoint_button_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>Set setpoint</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="3" column="2">
-                <widget class="QLineEdit" name="new_setpoint_z_safe">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                </widget>
-               </item>
-               <item row="0" column="0">
-                <widget class="QLabel" name="label_3">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>Setpoint:</string>
-                 </property>
-                </widget>
-               </item>
-               <item row="0" column="2">
-                <widget class="QLabel" name="label_13">
-                 <property name="sizePolicy">
-                  <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                   <horstretch>0</horstretch>
-                   <verstretch>0</verstretch>
-                  </sizepolicy>
-                 </property>
-                 <property name="font">
-                  <font>
-                   <pointsize>14</pointsize>
-                  </font>
-                 </property>
-                 <property name="text">
-                  <string>New</string>
-                 </property>
-                 <property name="alignment">
-                  <set>Qt::AlignCenter</set>
-                 </property>
-                </widget>
-               </item>
-               <item row="5" column="1">
-                <widget class="QLabel" name="error_label">
-                 <property name="text">
-                  <string/>
-                 </property>
-                </widget>
-               </item>
-              </layout>
-             </widget>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab_picker">
-           <attribute name="title">
-            <string>Picker</string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_19">
-            <item row="0" column="0">
-             <layout class="QGridLayout" name="gridLayout_18">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item row="0" column="2">
-               <layout class="QHBoxLayout" name="horizontalLayout_2">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <layout class="QVBoxLayout" name="verticalLayout_5">
-                  <property name="leftMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="topMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="rightMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="bottomMargin">
-                   <number>6</number>
-                  </property>
-                  <item>
-                   <widget class="QLabel" name="label_47">
-                    <property name="text">
-                     <string>Yaw</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_54">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>+ve x-axis</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QDial" name="picker_yaw_dial">
-                    <property name="sizePolicy">
-                     <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-                      <horstretch>0</horstretch>
-                      <verstretch>0</verstretch>
-                     </sizepolicy>
-                    </property>
-                    <property name="minimum">
-                     <number>-180</number>
-                    </property>
-                    <property name="maximum">
-                     <number>180</number>
-                    </property>
-                    <property name="singleStep">
-                     <number>5</number>
-                    </property>
-                    <property name="pageStep">
-                     <number>15</number>
-                    </property>
-                    <property name="value">
-                     <number>0</number>
-                    </property>
-                    <property name="sliderPosition">
-                     <number>0</number>
-                    </property>
-                    <property name="tracking">
-                     <bool>false</bool>
-                    </property>
-                    <property name="wrapping">
-                     <bool>true</bool>
-                    </property>
-                    <property name="notchTarget">
-                     <double>6.000000000000000</double>
-                    </property>
-                    <property name="notchesVisible">
-                     <bool>true</bool>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_55">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>-ve x-axis</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                 </layout>
-                </item>
-                <item>
-                 <layout class="QVBoxLayout" name="verticalLayout_6">
-                  <property name="leftMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="topMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="rightMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="bottomMargin">
-                   <number>6</number>
-                  </property>
-                  <item>
-                   <widget class="QLabel" name="label_48">
-                    <property name="text">
-                     <string>z</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_51">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>1.0</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <layout class="QHBoxLayout" name="horizontalLayout_9">
-                    <property name="leftMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="topMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="rightMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="bottomMargin">
-                     <number>6</number>
-                    </property>
-                    <item>
-                     <widget class="QSlider" name="picker_z_slider">
-                      <property name="maximum">
-                       <number>100</number>
-                      </property>
-                      <property name="singleStep">
-                       <number>1</number>
-                      </property>
-                      <property name="pageStep">
-                       <number>2</number>
-                      </property>
-                      <property name="tracking">
-                       <bool>false</bool>
-                      </property>
-                      <property name="orientation">
-                       <enum>Qt::Vertical</enum>
-                      </property>
-                      <property name="invertedAppearance">
-                       <bool>false</bool>
-                      </property>
-                      <property name="invertedControls">
-                       <bool>false</bool>
-                      </property>
-                      <property name="tickPosition">
-                       <enum>QSlider::TicksBothSides</enum>
-                      </property>
-                      <property name="tickInterval">
-                       <number>10</number>
-                      </property>
-                     </widget>
-                    </item>
-                   </layout>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_50">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>0.0</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                 </layout>
-                </item>
-                <item>
-                 <layout class="QVBoxLayout" name="verticalLayout_7">
-                  <property name="leftMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="topMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="rightMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="bottomMargin">
-                   <number>6</number>
-                  </property>
-                  <item>
-                   <widget class="QLabel" name="label_49">
-                    <property name="text">
-                     <string>Mass</string>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_53">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>38</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <layout class="QHBoxLayout" name="horizontalLayout_11">
-                    <property name="leftMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="topMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="rightMargin">
-                     <number>6</number>
-                    </property>
-                    <property name="bottomMargin">
-                     <number>6</number>
-                    </property>
-                    <item>
-                     <widget class="QSlider" name="picker_mass_slider">
-                      <property name="minimum">
-                       <number>28</number>
-                      </property>
-                      <property name="maximum">
-                       <number>38</number>
-                      </property>
-                      <property name="pageStep">
-                       <number>1</number>
-                      </property>
-                      <property name="tracking">
-                       <bool>false</bool>
-                      </property>
-                      <property name="orientation">
-                       <enum>Qt::Vertical</enum>
-                      </property>
-                      <property name="tickPosition">
-                       <enum>QSlider::TicksBothSides</enum>
-                      </property>
-                      <property name="tickInterval">
-                       <number>1</number>
-                      </property>
-                     </widget>
-                    </item>
-                   </layout>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_52">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>28</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                 </layout>
-                </item>
-               </layout>
-              </item>
-              <item row="1" column="0">
-               <layout class="QVBoxLayout" name="verticalLayout_8">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QPushButton" name="picker_1_button">
-                  <property name="text">
-                   <string>Button 1</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="picker_2_button">
-                  <property name="text">
-                   <string>Button 2</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="picker_3_button">
-                  <property name="text">
-                   <string>Button 3</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="picker_4_button">
-                  <property name="text">
-                   <string>Button 4</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item row="1" column="2">
-               <layout class="QVBoxLayout" name="verticalLayout_9">
-                <item>
-                 <widget class="QLabel" name="label_56">
-                  <property name="text">
-                   <string>x-axis adjustment</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <layout class="QHBoxLayout" name="horizontalLayout_12">
-                  <property name="leftMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="topMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="rightMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="bottomMargin">
-                   <number>6</number>
-                  </property>
-                  <item>
-                   <widget class="QLabel" name="label_60">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>-0.1</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QSlider" name="picker_x_slider">
-                    <property name="minimum">
-                     <number>-10</number>
-                    </property>
-                    <property name="maximum">
-                     <number>10</number>
-                    </property>
-                    <property name="pageStep">
-                     <number>1</number>
-                    </property>
-                    <property name="tracking">
-                     <bool>false</bool>
-                    </property>
-                    <property name="orientation">
-                     <enum>Qt::Horizontal</enum>
-                    </property>
-                    <property name="tickPosition">
-                     <enum>QSlider::TicksBothSides</enum>
-                    </property>
-                    <property name="tickInterval">
-                     <number>1</number>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_58">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>0.1</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                 </layout>
-                </item>
-                <item>
-                 <widget class="QLabel" name="label_57">
-                  <property name="text">
-                   <string>y-axis adjustment</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <layout class="QHBoxLayout" name="horizontalLayout_13">
-                  <property name="leftMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="topMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="rightMargin">
-                   <number>6</number>
-                  </property>
-                  <property name="bottomMargin">
-                   <number>6</number>
-                  </property>
-                  <item>
-                   <widget class="QLabel" name="label_61">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>-0.1</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QSlider" name="picker_y_slider">
-                    <property name="minimum">
-                     <number>-10</number>
-                    </property>
-                    <property name="maximum">
-                     <number>10</number>
-                    </property>
-                    <property name="pageStep">
-                     <number>1</number>
-                    </property>
-                    <property name="tracking">
-                     <bool>false</bool>
-                    </property>
-                    <property name="orientation">
-                     <enum>Qt::Horizontal</enum>
-                    </property>
-                    <property name="tickPosition">
-                     <enum>QSlider::TicksBothSides</enum>
-                    </property>
-                    <property name="tickInterval">
-                     <number>1</number>
-                    </property>
-                   </widget>
-                  </item>
-                  <item>
-                   <widget class="QLabel" name="label_59">
-                    <property name="font">
-                     <font>
-                      <family>Courier</family>
-                     </font>
-                    </property>
-                    <property name="text">
-                     <string>0.1</string>
-                    </property>
-                    <property name="alignment">
-                     <set>Qt::AlignCenter</set>
-                    </property>
-                   </widget>
-                  </item>
-                 </layout>
-                </item>
-               </layout>
-              </item>
-              <item row="0" column="0">
-               <layout class="QGridLayout" name="gridLayout_20">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>6</number>
-                </property>
-                <item row="3" column="0">
-                 <widget class="QPushButton" name="picker_pickup_button">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="text">
-                   <string>Pick-up</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="2" column="1">
-                 <widget class="QCheckBox" name="picker_attach_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="6" column="1">
-                 <widget class="QCheckBox" name="picker_squat_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="5" column="1">
-                 <widget class="QCheckBox" name="picker_putdown_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="4" column="1">
-                 <widget class="QCheckBox" name="picker_gotoend_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="3" column="1">
-                 <widget class="QCheckBox" name="picker_pickup_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="7" column="1">
-                 <widget class="QCheckBox" name="picker_jump_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="0" column="3">
-                 <widget class="QLabel" name="label_63">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="text">
-                   <string>y[m]</string>
-                  </property>
-                  <property name="alignment">
-                   <set>Qt::AlignCenter</set>
-                  </property>
-                 </widget>
-                </item>
-                <item row="1" column="1">
-                 <widget class="QCheckBox" name="picker_gotostart_checkBox">
-                  <property name="styleSheet">
-                   <string notr="true">QCheckBox::indicator{ width:30px ; height:30px }</string>
-                  </property>
-                  <property name="text">
-                   <string/>
-                  </property>
-                 </widget>
-                </item>
-                <item row="0" column="2">
-                 <widget class="QLabel" name="label_62">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="text">
-                   <string>x[m]</string>
-                  </property>
-                  <property name="alignment">
-                   <set>Qt::AlignCenter</set>
-                  </property>
-                 </widget>
-                </item>
-                <item row="1" column="0">
-                 <widget class="QPushButton" name="picker_gotostart_button">
-                  <property name="text">
-                   <string>Goto Start</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="4" column="0">
-                 <widget class="QPushButton" name="picker_gotoend_button">
-                  <property name="text">
-                   <string>Goto End</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="2" column="0">
-                 <widget class="QPushButton" name="picker_attach_button">
-                  <property name="text">
-                   <string>Attach</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="1" column="2">
-                 <widget class="QLineEdit" name="picker_gotostart_x">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="0" column="0">
-                 <widget class="QLabel" name="label_64">
-                  <property name="text">
-                   <string>Function:</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="6" column="0">
-                 <widget class="QPushButton" name="picker_squat_button">
-                  <property name="text">
-                   <string>Squat</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="7" column="0">
-                 <widget class="QPushButton" name="picker_jump_button">
-                  <property name="text">
-                   <string>Jump</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="5" column="0">
-                 <widget class="QPushButton" name="picker_putdown_button">
-                  <property name="text">
-                   <string>Put down</string>
-                  </property>
-                 </widget>
-                </item>
-                <item row="1" column="4">
-                 <widget class="QLineEdit" name="picker_gotostart_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="1" column="3">
-                 <widget class="QLineEdit" name="picker_gotostart_y">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="2" column="4">
-                 <widget class="QLineEdit" name="picker_attach_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="0" column="4">
-                 <widget class="QLabel" name="label_65">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="text">
-                   <string>z[m]</string>
-                  </property>
-                  <property name="alignment">
-                   <set>Qt::AlignCenter</set>
-                  </property>
-                 </widget>
-                </item>
-                <item row="3" column="4">
-                 <widget class="QLineEdit" name="picker_pickup_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="4" column="2">
-                 <widget class="QLineEdit" name="picker_gotoend_x">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="4" column="3">
-                 <widget class="QLineEdit" name="picker_gotoend_y">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="5" column="4">
-                 <widget class="QLineEdit" name="picker_putdown_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="6" column="4">
-                 <widget class="QLineEdit" name="picker_squat_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="7" column="4">
-                 <widget class="QLineEdit" name="picker_jump_z">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>100</width>
-                    <height>16777215</height>
-                   </size>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <family>Courier 10 Pitch</family>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-                <item row="0" column="1">
-                 <widget class="QLabel" name="label_66">
-                  <property name="text">
-                   <string>Smooth</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-             </layout>
-            </item>
-            <item row="1" column="0">
-             <spacer name="verticalSpacer_7">
-              <property name="orientation">
-               <enum>Qt::Vertical</enum>
-              </property>
-              <property name="sizeHint" stdset="0">
-               <size>
-                <width>20</width>
-                <height>40</height>
-               </size>
-              </property>
-             </spacer>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab_demo">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <attribute name="title">
-            <string>  Demo  </string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_9">
-            <item row="0" column="0">
-             <layout class="QVBoxLayout" name="verticalLayout_3">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item>
-               <layout class="QHBoxLayout" name="horizontalLayout_3">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QGroupBox" name="groupBox_5">
-                  <property name="title">
-                   <string/>
-                  </property>
-                  <layout class="QGridLayout" name="gridLayout_7">
-                   <item row="1" column="2">
-                    <widget class="QLineEdit" name="diff_x_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="6" column="1">
-                    <widget class="QLineEdit" name="current_roll_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="2" column="1">
-                    <widget class="QLineEdit" name="current_y_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="1">
-                    <widget class="QLineEdit" name="current_yaw_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="1">
-                    <widget class="QLineEdit" name="current_z_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="1" column="0">
-                    <widget class="QLabel" name="current_x_label_2">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>x [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="0">
-                    <widget class="QLabel" name="current_z_label_2">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>z [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="1" column="1">
-                    <widget class="QLineEdit" name="current_x_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="2" column="0">
-                    <widget class="QLabel" name="current_y_label_2">
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>y [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="0">
-                    <widget class="QLabel" name="current_yaw_label_2">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>yaw [deg] = </string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="5" column="1">
-                    <widget class="QLineEdit" name="current_pitch_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="5" column="0">
-                    <widget class="QLabel" name="current_pitch_label_2">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>pitch [deg] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="6" column="0">
-                    <widget class="QLabel" name="current_roll_label_2">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>roll [deg] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="0" column="1">
-                    <widget class="QLabel" name="label_6">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>Current</string>
-                     </property>
-                     <property name="alignment">
-                      <set>Qt::AlignCenter</set>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="2">
-                    <widget class="QLineEdit" name="diff_z_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="2" column="2">
-                    <widget class="QLineEdit" name="diff_y_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="2">
-                    <widget class="QLineEdit" name="diff_yaw_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="0" column="2">
-                    <widget class="QLabel" name="label_10">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>Difference</string>
-                     </property>
-                     <property name="alignment">
-                      <set>Qt::AlignCenter</set>
-                     </property>
-                    </widget>
-                   </item>
-                  </layout>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QGroupBox" name="groupBox_6">
-                  <property name="title">
-                   <string/>
-                  </property>
-                  <layout class="QGridLayout" name="gridLayout_8">
-                   <item row="2" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_y_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_yaw_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="1" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_x_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="2" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_y_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="1" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_x_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="0">
-                    <widget class="QLabel" name="label_14">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>yaw [deg] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="0" column="1">
-                    <widget class="QLabel" name="label_15">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>Current</string>
-                     </property>
-                     <property name="alignment">
-                      <set>Qt::AlignCenter</set>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="1" column="0">
-                    <widget class="QLabel" name="label_16">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>x [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="0">
-                    <widget class="QLabel" name="label_17">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>z [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="2" column="0">
-                    <widget class="QLabel" name="label_18">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>y [m] =</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_z_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="5" column="2">
-                    <widget class="QPushButton" name="set_setpoint_button_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>Set setpoint</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="4" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_yaw_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="readOnly">
-                      <bool>true</bool>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="3" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_z_demo">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="0" column="0">
-                    <widget class="QLabel" name="label_19">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>Setpoint:</string>
-                     </property>
-                    </widget>
-                   </item>
-                   <item row="0" column="2">
-                    <widget class="QLabel" name="label_20">
-                     <property name="sizePolicy">
-                      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                       <horstretch>0</horstretch>
-                       <verstretch>0</verstretch>
-                      </sizepolicy>
-                     </property>
-                     <property name="font">
-                      <font>
-                       <pointsize>14</pointsize>
-                      </font>
-                     </property>
-                     <property name="text">
-                      <string>New</string>
-                     </property>
-                     <property name="alignment">
-                      <set>Qt::AlignCenter</set>
-                     </property>
-                    </widget>
-                   </item>
-                  </layout>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item>
-               <layout class="QHBoxLayout" name="horizontalLayout_5">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QPushButton" name="demoButton_1">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <pointsize>14</pointsize>
-                   </font>
-                  </property>
-                  <property name="text">
-                   <string>Command 1</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="demoButton_2">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <pointsize>14</pointsize>
-                   </font>
-                  </property>
-                  <property name="text">
-                   <string>Command 2</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="demoButton_3">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="font">
-                   <font>
-                    <pointsize>14</pointsize>
-                   </font>
-                  </property>
-                  <property name="text">
-                   <string>Command 3</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QLineEdit" name="demoField_3">
-                  <property name="font">
-                   <font>
-                    <pointsize>14</pointsize>
-                   </font>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-             </layout>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab_student">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <attribute name="title">
-            <string>Student</string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_11">
-            <item row="0" column="0">
-             <layout class="QGridLayout" name="gridLayout_6">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item row="15" column="0">
-               <widget class="QLabel" name="label_72">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>roll [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="0">
-               <widget class="QLabel" name="label_67">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>x [m]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="0">
-               <widget class="QLabel" name="label_68">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>y [m]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="3">
-               <widget class="QLabel" name="label_25">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>yaw [deg] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="5">
-               <widget class="QLabel" name="label_27">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>New</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="14" column="5">
-               <widget class="QPushButton" name="set_setpoint_button_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>16</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Set setpoint</string>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="4">
-               <widget class="QLabel" name="label_26">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Current</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="3">
-               <widget class="QLabel" name="label_28">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Setpoint:</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="3">
-               <widget class="QLabel" name="label_29">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>x [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="3">
-               <widget class="QLabel" name="label_24">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>z [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="3">
-               <widget class="QLabel" name="label_23">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>y [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="5">
-               <widget class="QLineEdit" name="new_setpoint_x_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="5">
-               <widget class="QLineEdit" name="new_setpoint_yaw_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="4">
-               <widget class="QLineEdit" name="current_setpoint_x_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="4">
-               <widget class="QLineEdit" name="current_setpoint_y_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="4">
-               <widget class="QLineEdit" name="current_setpoint_yaw_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="4">
-               <widget class="QLineEdit" name="current_setpoint_z_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="5">
-               <widget class="QLineEdit" name="new_setpoint_z_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="5">
-               <widget class="QLineEdit" name="new_setpoint_y_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="1">
-               <widget class="QLabel" name="label_73">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>Current</string>
-                </property>
-               </widget>
-              </item>
-              <item row="14" column="0">
-               <widget class="QLabel" name="label_71">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>pitch [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="0">
-               <widget class="QLabel" name="label_70">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>yaw [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="0">
-               <widget class="QLabel" name="label_69">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>z [m]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="2">
-               <widget class="QLabel" name="label_74">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="text">
-                 <string>Difference</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="1">
-               <widget class="QLineEdit" name="current_x_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="2">
-               <widget class="QLineEdit" name="diff_x_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="1">
-               <widget class="QLineEdit" name="current_y_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="2">
-               <widget class="QLineEdit" name="diff_y_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="1">
-               <widget class="QLineEdit" name="current_z_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="2">
-               <widget class="QLineEdit" name="diff_z_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="1">
-               <widget class="QLineEdit" name="current_yaw_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="2">
-               <widget class="QLineEdit" name="diff_yaw_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="14" column="1">
-               <widget class="QLineEdit" name="current_pitch_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="15" column="1">
-               <widget class="QLineEdit" name="current_roll_student">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-               </widget>
-              </item>
-              <item row="16" column="2">
-               <widget class="QPushButton" name="studentButton_1">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="minimumSize">
-                 <size>
-                  <width>0</width>
-                  <height>40</height>
-                 </size>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Command 1</string>
-                </property>
-               </widget>
-              </item>
-              <item row="16" column="3">
-               <widget class="QPushButton" name="studentButton_2">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="minimumSize">
-                 <size>
-                  <width>0</width>
-                  <height>40</height>
-                 </size>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Commnd 2</string>
-                </property>
-               </widget>
-              </item>
-              <item row="16" column="4">
-               <widget class="QPushButton" name="studentButton_3">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="minimumSize">
-                 <size>
-                  <width>0</width>
-                  <height>40</height>
-                 </size>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Command 3</string>
-                </property>
-               </widget>
-              </item>
-              <item row="16" column="5">
-               <widget class="QLineEdit" name="studentField_3">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="minimumSize">
-                 <size>
-                  <width>0</width>
-                  <height>40</height>
-                 </size>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-               </widget>
-              </item>
-             </layout>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab_mpc">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <attribute name="title">
-            <string>MPC</string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_13">
-            <item row="0" column="0">
-             <layout class="QGridLayout" name="gridLayout_12">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item row="1" column="2">
-               <widget class="QLabel" name="label_30">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>New</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="14" column="2">
-               <widget class="QPushButton" name="set_setpoint_button_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Set setpoint</string>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="1">
-               <widget class="QLabel" name="label_31">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Current</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="0">
-               <widget class="QLabel" name="label_32">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>Setpoint:</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="0">
-               <widget class="QLabel" name="label_33">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>x [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="0">
-               <widget class="QLabel" name="label_34">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>yaw [deg] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="0">
-               <widget class="QLabel" name="label_35">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>z [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="0">
-               <widget class="QLabel" name="label_36">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="text">
-                 <string>y [m] =</string>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="2">
-               <widget class="QLineEdit" name="new_setpoint_x_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="2">
-               <widget class="QLineEdit" name="new_setpoint_yaw_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="1">
-               <widget class="QLineEdit" name="current_setpoint_x_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="1">
-               <widget class="QLineEdit" name="current_setpoint_y_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="1">
-               <widget class="QLineEdit" name="current_setpoint_yaw_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="1">
-               <widget class="QLineEdit" name="current_setpoint_z_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="9" column="2">
-               <widget class="QLineEdit" name="new_setpoint_z_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="2">
-               <widget class="QLineEdit" name="new_setpoint_y_mpc">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="font">
-                 <font>
-                  <pointsize>14</pointsize>
-                 </font>
-                </property>
-               </widget>
-              </item>
-             </layout>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab_remote">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <attribute name="title">
-            <string>Remote</string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_14">
-            <item row="0" column="0">
-             <layout class="QGridLayout" name="gridLayout_10">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item row="0" column="0">
-               <widget class="QLineEdit" name="remote_object_name">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-               </widget>
-              </item>
-              <item row="5" column="1">
-               <widget class="QLineEdit" name="remote_data_pitch">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="0" column="2">
-               <widget class="QPushButton" name="remote_unsubscribe_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>UN-subscribe</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="2">
-               <widget class="QLineEdit" name="remote_setpoint_z">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="0" column="1">
-               <widget class="QPushButton" name="remote_subscribe_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Subscribe</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="1">
-               <widget class="QLineEdit" name="remote_data_z">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="6" column="2">
-               <widget class="QLineEdit" name="remote_setpoint_yaw">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="6" column="1">
-               <widget class="QLineEdit" name="remote_data_yaw">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="2">
-               <widget class="Line" name="line_12">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="0">
-               <widget class="Line" name="line_10">
-                <property name="frameShadow">
-                 <enum>QFrame::Sunken</enum>
-                </property>
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="5" column="2">
-               <widget class="QLineEdit" name="remote_setpoint_pitch">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-               </widget>
-              </item>
-              <item row="4" column="1">
-               <widget class="QLineEdit" name="remote_data_roll">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="1" column="1">
-               <widget class="Line" name="line_11">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="4" column="2">
-               <widget class="QLineEdit" name="remote_setpoint_roll">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="font">
-                 <font>
-                  <family>Monospace</family>
-                 </font>
-                </property>
-                <property name="readOnly">
-                 <bool>true</bool>
-                </property>
-               </widget>
-              </item>
-              <item row="2" column="1">
-               <widget class="QLabel" name="remote_data_label">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Remote</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="2" column="2">
-               <widget class="QLabel" name="label_38">
-                <property name="text">
-                 <string>Setpoint</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="4" column="0">
-               <widget class="QLabel" name="remote_roll_label">
-                <property name="text">
-                 <string>Roll [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="5" column="0">
-               <widget class="QLabel" name="remote_pitch_label">
-                <property name="text">
-                 <string>Pitch [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="6" column="0">
-               <widget class="QLabel" name="remote_yaw_label">
-                <property name="text">
-                 <string>Yaw [deg]</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="0">
-               <widget class="QLabel" name="remote_z_label">
-                <property name="text">
-                 <string>z [m]</string>
-                </property>
-               </widget>
-              </item>
-             </layout>
-            </item>
-            <item row="0" column="1">
-             <layout class="QVBoxLayout" name="verticalLayout_2">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>6</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>6</number>
-              </property>
-              <item>
-               <spacer name="verticalSpacer_2">
-                <property name="orientation">
-                 <enum>Qt::Vertical</enum>
-                </property>
-                <property name="sizeHint" stdset="0">
-                 <size>
-                  <width>20</width>
-                  <height>40</height>
-                 </size>
-                </property>
-               </spacer>
-              </item>
-              <item>
-               <widget class="QPushButton" name="remote_activate_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>100</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Activate</string>
-                </property>
-               </widget>
-              </item>
-              <item>
-               <widget class="QPushButton" name="remote_deactivate_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>16777215</width>
-                  <height>100</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>DE-activate</string>
-                </property>
-               </widget>
-              </item>
-              <item>
-               <spacer name="verticalSpacer_3">
-                <property name="orientation">
-                 <enum>Qt::Vertical</enum>
-                </property>
-                <property name="sizeHint" stdset="0">
-                 <size>
-                  <width>20</width>
-                  <height>40</height>
-                 </size>
-                </property>
-               </spacer>
-              </item>
-             </layout>
-            </item>
-           </layout>
-          </widget>
-          <widget class="QWidget" name="tab">
-           <property name="sizePolicy">
-            <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
-             <horstretch>0</horstretch>
-             <verstretch>0</verstretch>
-            </sizepolicy>
-           </property>
-           <attribute name="title">
-            <string>Tuning</string>
-           </attribute>
-           <layout class="QGridLayout" name="gridLayout_16">
-            <item row="0" column="0">
-             <layout class="QGridLayout" name="gridLayout_15">
-              <property name="leftMargin">
-               <number>6</number>
-              </property>
-              <property name="topMargin">
-               <number>0</number>
-              </property>
-              <property name="rightMargin">
-               <number>6</number>
-              </property>
-              <property name="bottomMargin">
-               <number>0</number>
-              </property>
-              <item row="4" column="0">
-               <widget class="QLabel" name="label_45">
-                <property name="text">
-                 <string>Vertical Controller Gain   (Vertikal Regler Verstaekung)</string>
-                </property>
-               </widget>
-              </item>
-              <item row="2" column="0">
-               <widget class="Line" name="line_13">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="2" column="1">
-               <widget class="Line" name="line_15">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="11" column="0">
-               <spacer name="verticalSpacer_4">
-                <property name="orientation">
-                 <enum>Qt::Vertical</enum>
-                </property>
-                <property name="sizeType">
-                 <enum>QSizePolicy::Minimum</enum>
-                </property>
-                <property name="sizeHint" stdset="0">
-                 <size>
-                  <width>20</width>
-                  <height>10</height>
-                 </size>
-                </property>
-               </spacer>
-              </item>
-              <item row="1" column="1">
-               <widget class="QPushButton" name="tuning_test_horizontal_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>160</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Test</string>
-                </property>
-               </widget>
-              </item>
-              <item row="6" column="1">
-               <widget class="Line" name="line_16">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="8" column="0">
-               <widget class="QLabel" name="label_46">
-                <property name="text">
-                 <string>Heading Controller Gain   (Orientierung Regler Verstaekung)</string>
-                </property>
-               </widget>
-              </item>
-              <item row="12" column="0">
-               <layout class="QHBoxLayout" name="horizontalLayout_10">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="topMargin">
-                 <number>0</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <property name="bottomMargin">
-                 <number>0</number>
-                </property>
-                <item>
-                 <widget class="QPushButton" name="tuning_test_all_button">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="minimumSize">
-                   <size>
-                    <width>0</width>
-                    <height>0</height>
-                   </size>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>340</width>
-                    <height>50</height>
-                   </size>
-                  </property>
-                  <property name="text">
-                   <string>Test All</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QPushButton" name="tuning_test_circle_button">
-                  <property name="sizePolicy">
-                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                    <horstretch>0</horstretch>
-                    <verstretch>0</verstretch>
-                   </sizepolicy>
-                  </property>
-                  <property name="maximumSize">
-                   <size>
-                    <width>340</width>
-                    <height>50</height>
-                   </size>
-                  </property>
-                  <property name="text">
-                   <string>Fly a circle</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item row="6" column="0">
-               <widget class="Line" name="line_14">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="3" column="0">
-               <spacer name="verticalSpacer_5">
-                <property name="orientation">
-                 <enum>Qt::Vertical</enum>
-                </property>
-                <property name="sizeType">
-                 <enum>QSizePolicy::Minimum</enum>
-                </property>
-                <property name="sizeHint" stdset="0">
-                 <size>
-                  <width>20</width>
-                  <height>5</height>
-                 </size>
-                </property>
-               </spacer>
-              </item>
-              <item row="9" column="1">
-               <widget class="QPushButton" name="tuning_test_heading_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>160</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Test</string>
-                </property>
-               </widget>
-              </item>
-              <item row="0" column="0">
-               <widget class="QLabel" name="label_37">
-                <property name="text">
-                 <string>Horizontal Controller Gain   (Horizontal Regler Verstaekung)</string>
-                </property>
-                <property name="alignment">
-                 <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
-                </property>
-               </widget>
-              </item>
-              <item row="5" column="0">
-               <layout class="QHBoxLayout" name="horizontalLayout_4">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QLabel" name="label_39">
-                  <property name="text">
-                   <string>Min</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QSlider" name="tuning_slider_vertical">
-                  <property name="maximum">
-                   <number>1000</number>
-                  </property>
-                  <property name="value">
-                   <number>100</number>
-                  </property>
-                  <property name="tracking">
-                   <bool>false</bool>
-                  </property>
-                  <property name="orientation">
-                   <enum>Qt::Horizontal</enum>
-                  </property>
-                  <property name="tickPosition">
-                   <enum>QSlider::TicksAbove</enum>
-                  </property>
-                  <property name="tickInterval">
-                   <number>100</number>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QLabel" name="label_40">
-                  <property name="text">
-                   <string>Max</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item row="5" column="1">
-               <widget class="QPushButton" name="tuning_test_vertical_button">
-                <property name="sizePolicy">
-                 <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-                  <horstretch>0</horstretch>
-                  <verstretch>0</verstretch>
-                 </sizepolicy>
-                </property>
-                <property name="maximumSize">
-                 <size>
-                  <width>160</width>
-                  <height>50</height>
-                 </size>
-                </property>
-                <property name="text">
-                 <string>Test</string>
-                </property>
-               </widget>
-              </item>
-              <item row="7" column="0">
-               <spacer name="verticalSpacer_6">
-                <property name="orientation">
-                 <enum>Qt::Vertical</enum>
-                </property>
-                <property name="sizeType">
-                 <enum>QSizePolicy::Minimum</enum>
-                </property>
-                <property name="sizeHint" stdset="0">
-                 <size>
-                  <width>20</width>
-                  <height>5</height>
-                 </size>
-                </property>
-               </spacer>
-              </item>
-              <item row="9" column="0">
-               <layout class="QHBoxLayout" name="horizontalLayout_6">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QLabel" name="label_41">
-                  <property name="text">
-                   <string>Min</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QSlider" name="tuning_slider_heading">
-                  <property name="maximum">
-                   <number>1000</number>
-                  </property>
-                  <property name="value">
-                   <number>100</number>
-                  </property>
-                  <property name="tracking">
-                   <bool>false</bool>
-                  </property>
-                  <property name="orientation">
-                   <enum>Qt::Horizontal</enum>
-                  </property>
-                  <property name="tickPosition">
-                   <enum>QSlider::TicksAbove</enum>
-                  </property>
-                  <property name="tickInterval">
-                   <number>100</number>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QLabel" name="label_42">
-                  <property name="text">
-                   <string>Max</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item row="1" column="0">
-               <layout class="QHBoxLayout" name="horizontalLayout_7">
-                <property name="leftMargin">
-                 <number>6</number>
-                </property>
-                <property name="rightMargin">
-                 <number>6</number>
-                </property>
-                <item>
-                 <widget class="QLabel" name="label_43">
-                  <property name="text">
-                   <string>Min</string>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QSlider" name="tuning_slider_horizontal">
-                  <property name="maximum">
-                   <number>1000</number>
-                  </property>
-                  <property name="value">
-                   <number>100</number>
-                  </property>
-                  <property name="tracking">
-                   <bool>false</bool>
-                  </property>
-                  <property name="orientation">
-                   <enum>Qt::Horizontal</enum>
-                  </property>
-                  <property name="tickPosition">
-                   <enum>QSlider::TicksAbove</enum>
-                  </property>
-                  <property name="tickInterval">
-                   <number>100</number>
-                  </property>
-                 </widget>
-                </item>
-                <item>
-                 <widget class="QLabel" name="label_44">
-                  <property name="text">
-                   <string>Max</string>
-                  </property>
-                 </widget>
-                </item>
-               </layout>
-              </item>
-              <item row="10" column="0">
-               <widget class="Line" name="line_17">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-              <item row="10" column="1">
-               <widget class="Line" name="line_18">
-                <property name="lineWidth">
-                 <number>5</number>
-                </property>
-                <property name="orientation">
-                 <enum>Qt::Horizontal</enum>
-                </property>
-               </widget>
-              </item>
-             </layout>
-            </item>
-           </layout>
-          </widget>
-         </widget>
-        </item>
-        <item>
-         <widget class="Line" name="line">
-          <property name="orientation">
-           <enum>Qt::Vertical</enum>
-          </property>
-         </widget>
-        </item>
-        <item>
-         <layout class="QGridLayout" name="gridLayout_17">
-          <property name="leftMargin">
-           <number>6</number>
-          </property>
-          <property name="topMargin">
-           <number>6</number>
-          </property>
-          <property name="rightMargin">
-           <number>6</number>
-          </property>
-          <property name="bottomMargin">
-           <number>6</number>
-          </property>
-          <item row="8" column="1">
-           <widget class="Line" name="line_20">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="9" column="2">
-           <widget class="QPushButton" name="load_tuning_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Tuning</string>
-            </property>
-           </widget>
-          </item>
-          <item row="7" column="1">
-           <widget class="Line" name="line_21">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="6" column="1">
-           <widget class="Line" name="line_22">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="7" column="2">
-           <widget class="QPushButton" name="load_mpc_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>MPC</string>
-            </property>
-           </widget>
-          </item>
-          <item row="8" column="2">
-           <widget class="QPushButton" name="load_remote_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Remote</string>
-            </property>
-           </widget>
-          </item>
-          <item row="6" column="2">
-           <widget class="QPushButton" name="load_student_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Student</string>
-            </property>
-           </widget>
-          </item>
-          <item row="6" column="0">
-           <widget class="QPushButton" name="enable_student_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Student</string>
-            </property>
-           </widget>
-          </item>
-          <item row="0" column="2">
-           <widget class="QLabel" name="label_2">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>16</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Load</string>
-            </property>
-            <property name="alignment">
-             <set>Qt::AlignCenter</set>
-            </property>
-           </widget>
-          </item>
-          <item row="0" column="0">
-           <widget class="QLabel" name="label_21">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>16</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Controller</string>
-            </property>
-            <property name="alignment">
-             <set>Qt::AlignCenter</set>
-            </property>
-           </widget>
-          </item>
-          <item row="1" column="0">
-           <widget class="QLabel" name="label">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>16</pointsize>
-              <weight>75</weight>
-              <bold>true</bold>
-             </font>
-            </property>
-            <property name="text">
-             <string>Enable</string>
-            </property>
-            <property name="alignment">
-             <set>Qt::AlignCenter</set>
-            </property>
-           </widget>
-          </item>
-          <item row="5" column="0">
-           <widget class="QPushButton" name="enable_demo_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Demo</string>
-            </property>
-           </widget>
-          </item>
-          <item row="10" column="0">
-           <spacer name="verticalSpacer">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-            <property name="sizeHint" stdset="0">
-             <size>
-              <width>20</width>
-              <height>40</height>
-             </size>
-            </property>
-           </spacer>
-          </item>
-          <item row="3" column="2">
-           <widget class="QPushButton" name="load_safe_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Safe</string>
-            </property>
-           </widget>
-          </item>
-          <item row="3" column="0">
-           <widget class="QPushButton" name="enable_safe_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Safe</string>
-            </property>
-           </widget>
-          </item>
-          <item row="5" column="2">
-           <widget class="QPushButton" name="load_demo_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Demo</string>
-            </property>
-           </widget>
-          </item>
-          <item row="3" column="1">
-           <widget class="Line" name="line_3">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="1" column="2">
-           <widget class="QLabel" name="label_22">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>30</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>16</pointsize>
-              <weight>75</weight>
-              <bold>true</bold>
-             </font>
-            </property>
-            <property name="text">
-             <string>YAML</string>
-            </property>
-            <property name="alignment">
-             <set>Qt::AlignCenter</set>
-            </property>
-           </widget>
-          </item>
-          <item row="5" column="1">
-           <widget class="Line" name="line_4">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="0" column="1">
-           <widget class="Line" name="line_7">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="1" column="1">
-           <widget class="Line" name="line_6">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="10" column="1">
-           <widget class="Line" name="line_5">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="7" column="0">
-           <widget class="QPushButton" name="enable_mpc_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>MPC</string>
-            </property>
-           </widget>
-          </item>
-          <item row="8" column="0">
-           <widget class="QPushButton" name="enable_remote_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Remote</string>
-            </property>
-           </widget>
-          </item>
-          <item row="9" column="1">
-           <widget class="Line" name="line_19">
-            <property name="orientation">
-             <enum>Qt::Vertical</enum>
-            </property>
-           </widget>
-          </item>
-          <item row="9" column="0">
-           <widget class="QPushButton" name="enable_tuning_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Tuning</string>
-            </property>
-           </widget>
-          </item>
-          <item row="4" column="0">
-           <widget class="QPushButton" name="enable_picker_controller">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Picker</string>
-            </property>
-           </widget>
-          </item>
-          <item row="4" column="2">
-           <widget class="QPushButton" name="load_picker_yaml_button">
-            <property name="sizePolicy">
-             <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-              <horstretch>0</horstretch>
-              <verstretch>0</verstretch>
-             </sizepolicy>
-            </property>
-            <property name="minimumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="maximumSize">
-             <size>
-              <width>180</width>
-              <height>50</height>
-             </size>
-            </property>
-            <property name="font">
-             <font>
-              <pointsize>14</pointsize>
-             </font>
-            </property>
-            <property name="text">
-             <string>Picker</string>
-            </property>
-           </widget>
-          </item>
-         </layout>
-        </item>
-        <item>
-         <widget class="Line" name="line_2">
-          <property name="orientation">
-           <enum>Qt::Vertical</enum>
-          </property>
-         </widget>
-        </item>
-       </layout>
-      </item>
-     </layout>
-    </item>
-   </layout>
-  </widget>
-  <widget class="QMenuBar" name="menuBar">
-   <property name="geometry">
-    <rect>
-     <x>0</x>
-     <y>0</y>
-     <width>1500</width>
-     <height>25</height>
-    </rect>
-   </property>
-  </widget>
-  <widget class="QToolBar" name="mainToolBar">
-   <attribute name="toolBarArea">
-    <enum>TopToolBarArea</enum>
-   </attribute>
-   <attribute name="toolBarBreak">
-    <bool>false</bool>
-   </attribute>
-  </widget>
-  <widget class="QStatusBar" name="statusBar"/>
- </widget>
- <layoutdefault spacing="6" margin="11"/>
- <resources/>
- <connections/>
-</ui>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp
deleted file mode 100644
index 27bdde98..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/main.cpp
+++ /dev/null
@@ -1,42 +0,0 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Angel Romero
-//
-//    This file is part of D-FaLL-System.
-//    
-//    D-FaLL-System is free software: you can redistribute it and/or modify
-//    it under the terms of the GNU General Public License as published by
-//    the Free Software Foundation, either version 3 of the License, or
-//    (at your option) any later version.
-//    
-//    D-FaLL-System is distributed in the hope that it will be useful,
-//    but WITHOUT ANY WARRANTY; without even the implied warranty of
-//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-//    GNU General Public License for more details.
-//    
-//    You should have received a copy of the GNU General Public License
-//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
-//    
-//
-//    ----------------------------------------------------------------------------------
-//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
-//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
-//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
-//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
-//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
-//
-//
-//    DESCRIPTION:
-//    Main program of the Student's GUI
-//
-//    ----------------------------------------------------------------------------------
-
-
-#include "MainWindow.h"
-#include <QApplication>
-
-int main(int argc, char *argv[])
-{
-    QApplication a(argc, argv);
-    MainWindow w(argc, argv);
-    w.show();
-    return a.exec();
-}
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
deleted file mode 100644
index ed87c889..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/src/rosNodeThread_for_studentGUI.cpp
+++ /dev/null
@@ -1,114 +0,0 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Angel Romero
-//
-//    This file is part of D-FaLL-System.
-//    
-//    D-FaLL-System is free software: you can redistribute it and/or modify
-//    it under the terms of the GNU General Public License as published by
-//    the Free Software Foundation, either version 3 of the License, or
-//    (at your option) any later version.
-//    
-//    D-FaLL-System is distributed in the hope that it will be useful,
-//    but WITHOUT ANY WARRANTY; without even the implied warranty of
-//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-//    GNU General Public License for more details.
-//    
-//    You should have received a copy of the GNU General Public License
-//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
-//    
-//
-//    ----------------------------------------------------------------------------------
-//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
-//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
-//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
-//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
-//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
-//
-//
-//    DESCRIPTION:
-//    Takes care of creating a ros node thread.
-//
-//    ----------------------------------------------------------------------------------
-
-
-#include "rosNodeThread_for_studentGUI.h"
-
-#include "dfall_pkg/CMRead.h"
-#include "dfall_pkg/CMUpdate.h"
-#include "dfall_pkg/CMCommand.h"
-
-
-rosNodeThread::rosNodeThread(int argc, char** pArgv, const char * node_name, QObject* parent)
-    :   QObject(parent),
-        m_Init_argc(argc),
-        m_pInit_argv(pArgv),
-        m_node_name(node_name)
-
-{
-    /** Constructor for the node thread **/
-}
-
-rosNodeThread::~rosNodeThread()
-{
-    if (ros::isStarted())
-    {
-        ros::shutdown();
-        ros::waitForShutdown();
-    } // end if
-    m_pThread->wait();
-} // end destructor
-
-bool rosNodeThread::init()
-{
-    m_pThread = new QThread();
-    this->moveToThread(m_pThread); // QObject method
-
-    connect(m_pThread, SIGNAL(started()), this, SLOT(run()));
-    ros::init(m_Init_argc, m_pInit_argv, m_node_name); // student_GUI is the name of this node
-
-    if (!ros::master::check())
-    {
-        ROS_ERROR("Master not found, please check teacher computer is running and try again");
-        return false;           // do not start without ros.
-    }
-
-    ros::start();
-    ros::Time::init();
-    ros::NodeHandle nh("~");
-
-    m_vicon_subscriber = nh.subscribe("/ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this);
-
-    // clients for db services:
-    m_read_db_client = nh.serviceClient<CMRead>("/CentralManagerService/Read", false);
-    m_update_db_client = nh.serviceClient<CMUpdate>("/CentralManagerService/Update", false);
-    m_command_db_client = nh.serviceClient<CMCommand>("/CentralManagerService/Command", false);
-
-    m_pThread->start();
-    return true;
-} // set up the thread
-
-void rosNodeThread::messageCallback(const ptrToMessage& p_msg) // When a message arrives to the topic, this callback is executed
-{
-    emit newViconData(p_msg);   //pass the message to other places
-}
-
-void rosNodeThread::run()
-{
-    ros::Rate loop_rate(100);
-    QMutex * pMutex;
-    while (ros::ok())
-    {
-        pMutex = new QMutex();
-
-        // geometry_msgs::Twist cmd_msg;
-        pMutex->lock();
-        // cmd_msg.linear.x = m_speed;
-        // cmd_msg.angular.z = m_angle;
-        pMutex->unlock();
-        // ROS_INFO("RUNNING");
-
-        // sim_velocity.publish(cmd_msg);
-        ros::spinOnce();
-        loop_rate.sleep();
-        delete pMutex;
-    } // do ros things.
-}
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro
deleted file mode 100644
index 215f47e8..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentGUI.pro
+++ /dev/null
@@ -1,28 +0,0 @@
-#-------------------------------------------------
-#
-# Project created by QtCreator 2017-08-21T11:01:25
-#
-#-------------------------------------------------
-
-QT       += core gui
-
-greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
-
-TARGET = studentGUI
-TEMPLATE = app
-
-INCLUDEPATH += $$PWD/include
-CONFIG += c++11
-
-SOURCES += \
-         src/main.cpp \
-         src/MainWindow.cpp
-
-HEADERS  += \
-         include/MainWindow.h \
-
-FORMS    += \
-         src/MainWindow.ui
-
-RESOURCES += \
-    studentgui.qrc
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc b/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc
deleted file mode 100644
index 0f6e7d8e..00000000
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/studentGUI/studentgui.qrc
+++ /dev/null
@@ -1,19 +0,0 @@
-<RCC>
-    <qresource prefix="/">
-        <file>images/battery_20.png</file>
-        <file>images/battery_40.png</file>
-        <file>images/battery_60.png</file>
-        <file>images/battery_80.png</file>
-        <file>images/battery_empty.png</file>
-        <file>images/battery_full.png</file>
-        <file>images/rf_connected.png</file>
-        <file>images/rf_connecting.png</file>
-        <file>images/rf_disconnected.png</file>
-        <file>images/battery_unknown.png</file>
-        <file>images/flying_state_disabling.png</file>
-        <file>images/flying_state_enabling.png</file>
-        <file>images/flying_state_flying.png</file>
-        <file>images/flying_state_off.png</file>
-        <file>images/flying_state_unknown.png</file>
-    </qresource>
-</RCC>
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index eadb4743..159faa7d 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -710,7 +710,8 @@ void loadPickerController()
 
 void sendMessageUsingController(int controller)
 {
-    // send a message in topic for the studentGUI to read it
+    // Send a message on the topic for informing the Flying
+    // Agent GUI about this update
     std_msgs::Int32 controller_used_msg;
     controller_used_msg.data = controller;
     controllerUsedPublisher.publish(controller_used_msg);
-- 
GitLab


From 9e640f930b296f31996510b6a8ea8c053467afa9 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 13:29:53 +0100
Subject: [PATCH 66/87] Added/Updated licensing headers

---
 ...PickerControllerConstants_for_Qt_compile.h |  2 +-
 .../include/connectstartstopbar.h             |  6 ++-
 .../flyingAgentGUI/include/controllertabs.h   | 36 ++++++++++++++++++
 .../flyingAgentGUI/include/coordinator.h      | 37 +++++++++++++++++++
 .../flyingAgentGUI/include/coordinatorrow.h   |  9 ++++-
 .../include/defaultcontrollertab.h            | 35 ++++++++++++++++++
 .../include/enablecontrollerloadyamlbar.h     | 37 +++++++++++++++++++
 .../flyingAgentGUI/include/mainwindow.h       |  7 +++-
 .../include/pickercontrollertab.h             | 35 ++++++++++++++++++
 .../rosNodeThread_for_flyingAgentGUI.h        |  5 ++-
 .../include/studentcontrollertab.h            | 35 ++++++++++++++++++
 .../GUI_Qt/flyingAgentGUI/include/topbanner.h |  4 +-
 .../include/tuningcontrollertab.h             | 35 ++++++++++++++++++
 .../src/connectstartstopbar.cpp               |  2 +-
 .../flyingAgentGUI/src/controllertabs.cpp     | 36 ++++++++++++++++++
 .../GUI_Qt/flyingAgentGUI/src/coordinator.cpp | 37 +++++++++++++++++++
 .../flyingAgentGUI/src/coordinatorrow.cpp     |  6 ++-
 .../src/defaultcontrollertab.cpp              | 35 ++++++++++++++++++
 .../src/enablecontrollerloadyamlbar.cpp       | 37 +++++++++++++++++++
 .../GUI_Qt/flyingAgentGUI/src/main.cpp        |  4 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  8 +++-
 .../src/pickercontrollertab.cpp               | 35 ++++++++++++++++++
 .../src/rosNodeThread_for_flyingAgentGUI.cpp  |  5 ++-
 .../src/studentcontrollertab.cpp              | 35 ++++++++++++++++++
 .../GUI_Qt/flyingAgentGUI/src/topbanner.cpp   |  4 +-
 .../src/tuningcontrollertab.cpp               | 35 ++++++++++++++++++
 .../classes/GetParamtersAndNamespaces.h       |  2 +-
 .../dfall_pkg/include/nodes/BatteryMonitor.h  |  2 +-
 .../include/nodes/DefaultControllerService.h  |  2 +-
 .../include/nodes/ParameterService.h          |  2 +-
 .../include/nodes/PickerControllerConstants.h |  2 +-
 .../include/nodes/PickerControllerService.h   |  2 +-
 .../include/nodes/StudentControllerService.h  |  2 +-
 .../include/nodes/TuningControllerService.h   |  2 +-
 .../src/classes/GetParamtersAndNamespaces.cpp |  2 +-
 .../dfall_pkg/src/nodes/BatteryMonitor.cpp    |  2 +-
 .../src/nodes/DefaultControllerService.cpp    |  2 +-
 .../dfall_pkg/src/nodes/ParameterService.cpp  |  2 +-
 .../src/nodes/PickerControllerService.cpp     |  2 +-
 .../src/nodes/StudentControllerService.cpp    |  2 +-
 .../src/nodes/TuningControllerService.cpp     |  2 +-
 .../src/nodes/ViconDataPublisher.cpp          |  2 +-
 42 files changed, 559 insertions(+), 35 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
index 3b1c36cd..556373ce 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/PickerControllerConstants_for_Qt_compile.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
index 71d42945..ac223f9b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/connectstartstopbar.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2018, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -27,9 +27,13 @@
 //    DESCRIPTION:
 //    The bar of the GUI for (dis-)connecting (from)to the Crazyradio
 //    and for sending the {take-off,land,motors-off} commands//
+//
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #ifndef CONNECTSTARTSTOPBAR_H
 #define CONNECTSTARTSTOPBAR_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 8cf19970..609a6882 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -1,3 +1,39 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The tab wdiget that contains and manages the individual tabs used
+//    to interface with each separate controller.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef CONTROLLERTABS_H
 #define CONTROLLERTABS_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h
index c4f21a83..54635ca2 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/coordinator.h
@@ -1,3 +1,40 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The coordinator part of the Flying Agent GUI that allows multiple
+//    flying agents to be controller from one place, and keeps track
+//    of which subset of flying agents to control.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef COORDINATOR_H
 #define COORDINATOR_H
 
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 efce79c5..9174ef6c 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
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -25,11 +25,16 @@
 //
 //
 //    DESCRIPTION:
-//    Coordinator Row GUI heder.
+//    An individual row in the coordinator part of the Flying Agent
+//    GUI. This is essentially a condensed version of the
+//    "Connect Start Stop Bar"
 //
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #ifndef COORDINATORROW_H
 #define COORDINATORROW_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 1e6ed40c..c454832d 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Default Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef DEFAULTCONTROLLERTAB_H
 #define DEFAULTCONTROLLERTAB_H
 
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 c8a54e33..babe4cba 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
@@ -1,3 +1,40 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI bar for selecting which controller is active, and
+//    for request that paramters are loaded from the respective
+//    YAML files.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef ENABLECONTROLLERLOADYAMLBAR_H
 #define ENABLECONTROLLERLOADYAMLBAR_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 2f929f1d..e1c67caf 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -25,11 +25,14 @@
 //
 //
 //    DESCRIPTION:
-//    Coordinator GUI main window header.
+//    The Flying Agent GUI main window.
 //
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #ifndef MAINWINDOW_FLYINGAGENTGUI_H
 #define MAINWINDOW_FLYINGAGENTGUI_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
index 54585fbf..52b79e13 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/pickercontrollertab.h
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Picker Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef PICKERCONTROLLERTAB_H
 #define PICKERCONTROLLERTAB_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
index fc331115..79c447e8 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/rosNodeThread_for_flyingAgentGUI.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -30,6 +30,9 @@
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #ifndef ___ROSNODETHREAD_FOR_FLYINGAGENTGUI_H___
 #define ___ROSNODETHREAD_FOR_FLYINGAGENTGUI_H___
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 01376a3c..94f6021f 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Student Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef STUDENTCONTROLLERTAB_H
 #define STUDENTCONTROLLERTAB_H
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h
index b3ff17a9..f33161ef 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/topbanner.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -25,7 +25,7 @@
 //
 //
 //    DESCRIPTION:
-//    The title displayed at the top of the GUI
+//    The title displayed at the top of the Flying Agent GUI
 //
 //    ----------------------------------------------------------------------------------
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
index 2e763165..cf8ecf05 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/tuningcontrollertab.h
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Tuning Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef TUNINGCONTROLLERTAB_H
 #define TUNINGCONTROLLERTAB_H
 
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 0d8c8bfd..c82fc96b 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
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
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 38f9d5d9..39a23530 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
@@ -1,3 +1,39 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The tab wdiget that contains and manages the individual tabs used
+//    to interface with each separate controller.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "controllertabs.h"
 #include "ui_controllertabs.h"
 
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 af56b464..f7f25b16 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
@@ -1,3 +1,40 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The coordinator part of the Flying Agent GUI that allows multiple
+//    flying agents to be controller from one place, and keeps track
+//    of which subset of flying agents to control.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "coordinator.h"
 #include "ui_coordinator.h"
 
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 2492c229..21585a85 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
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -25,7 +25,9 @@
 //
 //
 //    DESCRIPTION:
-//    Coordinator Row GUI.
+//    An individual row in the coordinator part of the Flying Agent
+//    GUI. This is essentially a condensed version of the
+//    "Connect Start Stop Bar"
 //
 //    ----------------------------------------------------------------------------------
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index f43d15fe..c4ad82b4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Default Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "defaultcontrollertab.h"
 #include "ui_defaultcontrollertab.h"
 
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 00b09c8a..14396c70 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
@@ -1,3 +1,40 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI bar for selecting which controller is active, and
+//    for request that paramters are loaded from the respective
+//    YAML files.
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "enablecontrollerloadyamlbar.h"
 #include "ui_enablecontrollerloadyamlbar.h"
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp
index ceb21be3..4d01be0b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/main.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -25,7 +25,7 @@
 //
 //
 //    DESCRIPTION:
-//    Main file of the Qt project for the Coordinator GUI.
+//    Main file of the Qt project for the Flying Agent GUI.
 //
 //    ----------------------------------------------------------------------------------
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 45c3fee7..254a0907 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //
@@ -25,10 +25,14 @@
 //
 //
 //    DESCRIPTION:
-//    Coordinator GUI main window.
+//    The Flying Agent GUI main window.
 //
 //    ----------------------------------------------------------------------------------
 
+
+
+
+
 #include "mainwindow.h"
 #include "ui_mainwindow.h"
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index 455a77b4..60c5ada3 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Picker Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "pickercontrollertab.h"
 #include "ui_pickercontrollertab.h"
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
index b9704007..161b03ac 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/rosNodeThread_for_flyingAgentGUI.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -30,6 +30,9 @@
 //    ----------------------------------------------------------------------------------
 
 
+
+
+
 #include "rosNodeThread_for_flyingAgentGUI.h"
 
 // #include "dfall_pkg/CMRead.h"
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index c7547f9d..cc9b3503 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Student Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "studentcontrollertab.h"
 #include "ui_studentcontrollertab.h"
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
index 9990e51c..2b299750 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -25,7 +25,7 @@
 //
 //
 //    DESCRIPTION:
-//    The title displayed at the top of the GUI
+//    The title displayed at the top of the Flying Agent GUI
 //
 //    ----------------------------------------------------------------------------------
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
index b2b101c8..ad36c34d 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for the Tuning Controller
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "tuningcontrollertab.h"
 #include "ui_tuningcontrollertab.h"
 
diff --git a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
index 9bc7a6e8..f3f96349 100644
--- a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
+++ b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h b/dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h
index 43f3740b..8cffa07a 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/BatteryMonitor.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 23450feb..00dc4219 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h b/dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h
index 92dda4e3..d298e9e2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/ParameterService.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h
index 41ab3321..05e62b80 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerConstants.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
index fa7c40f3..b8263334 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
index 820cacfb..e7263ac2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
index b7f2002e..d6eed836 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/TuningControllerService.h
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
index 9c7fdcaf..2d48a221 100644
--- a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
+++ b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
index f9ea5fbf..80ddc1da 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 234299b9..505bdc0c 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
index 8be89f51..854b71ac 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index b581597e..deda6de0 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index 2cb30434..a974ef3b 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
index 3e2d5fd4..8da3969f 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //
 //    This file is part of D-FaLL-System.
 //    
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
index 6107a8e3..1361db48 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/ViconDataPublisher.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Dusan Zikovic, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Angel Romero, Dusan Zikovic, Cyrill Burgener, Marco Mueller, Philipp Friedli
 //
 //    This file is part of D-FaLL-System.
 //    
-- 
GitLab


From ae2cb346f9e0973494728f3d2899ce652ac8af03 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Sun, 10 Feb 2019 15:44:33 +0100
Subject: [PATCH 67/87] Started process of adding a template controller. Still
 need to connect the GUI elements and add the ROS Controller Service node

---
 .../GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro  |  12 +-
 .../flyingAgentGUI/forms/controllertabs.ui    |  22 +-
 .../forms/enablecontrollerloadyamlbar.ui      |   8 +-
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |  13 +-
 .../forms/templatecontrollertab.ui            | 872 ++++++++++++++++++
 .../include/Constants_for_Qt_compile.h        |   7 +-
 .../flyingAgentGUI/include/controllertabs.h   |   2 +-
 .../include/enablecontrollerloadyamlbar.h     |  19 +-
 .../flyingAgentGUI/include/mainwindow.h       |   2 +-
 .../include/templatecontrollertab.h           |  22 +
 .../flyingAgentGUI/src/controllertabs.cpp     |  18 +-
 .../src/enablecontrollerloadyamlbar.cpp       |  68 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |  11 +-
 .../src/templatecontrollertab.cpp             |  14 +
 .../src/dfall_pkg/include/nodes/Constants.h   |   8 +-
 15 files changed, 1029 insertions(+), 69 deletions(-)
 create mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
 create mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
 create mode 100644 dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
index 69b60535..529942c8 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/flyingAgentGUI.pro
@@ -28,7 +28,9 @@ SOURCES += src/main.cpp\
     src/studentcontrollertab.cpp \
     src/defaultcontrollertab.cpp \
     src/pickercontrollertab.cpp \
-    src/tuningcontrollertab.cpp
+    src/templatecontrollertab.cpp \
+    src/tuningcontrollertab.cpp \
+
 
 HEADERS  += include/mainwindow.h \
     include/topbanner.h \
@@ -41,8 +43,10 @@ HEADERS  += include/mainwindow.h \
     include/studentcontrollertab.h \
     include/defaultcontrollertab.h \
     include/pickercontrollertab.h \
+    include/templatecontrollertab.h \
     include/tuningcontrollertab.h \
-    include/Constants_for_Qt_compile.h
+    include/Constants_for_Qt_compile.h \
+
 
 
 FORMS    += forms/mainwindow.ui \
@@ -56,7 +60,9 @@ FORMS    += forms/mainwindow.ui \
     forms/studentcontrollertab.ui \
     forms/defaultcontrollertab.ui \
     forms/pickercontrollertab.ui \
-    forms/tuningcontrollertab.ui
+    forms/templatecontrollertab.ui \
+    forms/tuningcontrollertab.ui \
+
 
 RESOURCES += \
     flyingagentgui.qrc
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
index 75157907..471a55f3 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/controllertabs.ui
@@ -28,7 +28,7 @@
    <item row="0" column="0">
     <widget class="QTabWidget" name="controller_tabs_widget">
      <property name="currentIndex">
-      <number>3</number>
+      <number>4</number>
      </property>
      <property name="movable">
       <bool>true</bool>
@@ -73,13 +73,13 @@
        </item>
       </layout>
      </widget>
-     <widget class="QWidget" name="safe_tab">
+     <widget class="QWidget" name="template_tab">
       <attribute name="title">
-       <string>Safe</string>
+       <string>Template</string>
       </attribute>
-      <layout class="QGridLayout" name="gridLayout_3">
+      <layout class="QGridLayout" name="gridLayout_7">
        <item row="0" column="0">
-        <widget class="SafeControllerTab" name="safe_controller_tab_widget" native="true"/>
+        <widget class="TemplateControllerTab" name="template_controller_tab_widget" native="true"/>
        </item>
       </layout>
      </widget>
@@ -88,12 +88,6 @@
   </layout>
  </widget>
  <customwidgets>
-  <customwidget>
-   <class>SafeControllerTab</class>
-   <extends>QWidget</extends>
-   <header>safecontrollertab.h</header>
-   <container>1</container>
-  </customwidget>
   <customwidget>
    <class>StudentControllerTab</class>
    <extends>QWidget</extends>
@@ -118,6 +112,12 @@
    <header>tuningcontrollertab.h</header>
    <container>1</container>
   </customwidget>
+  <customwidget>
+   <class>TemplateControllerTab</class>
+   <extends>QWidget</extends>
+   <header>templatecontrollertab.h</header>
+   <container>1</container>
+  </customwidget>
  </customwidgets>
  <resources/>
  <connections/>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
index b11f354f..c358d8be 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/enablecontrollerloadyamlbar.ui
@@ -109,7 +109,7 @@
       </spacer>
      </item>
      <item row="0" column="5">
-      <widget class="QPushButton" name="enable_safe_button">
+      <widget class="QPushButton" name="enable_template_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -135,7 +135,7 @@
         </font>
        </property>
        <property name="text">
-        <string>Safe</string>
+        <string>Template</string>
        </property>
       </widget>
      </item>
@@ -255,7 +255,7 @@
       </widget>
      </item>
      <item row="1" column="5">
-      <widget class="QPushButton" name="load_yaml_safe_button">
+      <widget class="QPushButton" name="load_yaml_template_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -275,7 +275,7 @@
         </size>
        </property>
        <property name="text">
-        <string>Safe</string>
+        <string>Template</string>
        </property>
       </widget>
      </item>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index 2a7f180b..bd79177a 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -214,7 +214,7 @@
     <addaction name="action_showHideController_student"/>
     <addaction name="action_showHideController_picker"/>
     <addaction name="action_showHideController_tuning"/>
-    <addaction name="action_showHideController_safe"/>
+    <addaction name="action_showHideController_template"/>
    </widget>
    <addaction name="menuFile"/>
    <addaction name="menuLoad_YAML"/>
@@ -302,6 +302,17 @@
     <string>Tuning</string>
    </property>
   </action>
+  <action name="action_showHideController_template">
+   <property name="checkable">
+    <bool>true</bool>
+   </property>
+   <property name="checked">
+    <bool>true</bool>
+   </property>
+   <property name="text">
+    <string>Template</string>
+   </property>
+  </action>
  </widget>
  <layoutdefault spacing="6" margin="11"/>
  <customwidgets>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
new file mode 100644
index 00000000..fd7da271
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
@@ -0,0 +1,872 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>TemplateControllerTab</class>
+ <widget class="QWidget" name="TemplateControllerTab">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1335</width>
+    <height>937</height>
+   </rect>
+  </property>
+  <property name="font">
+   <font>
+    <pointsize>16</pointsize>
+   </font>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <layout class="QGridLayout" name="gridLayout_2">
+   <item row="2" column="0">
+    <spacer name="verticalSpacer_2">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeType">
+      <enum>QSizePolicy::Fixed</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>20</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="4" column="0">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
+     </property>
+     <property name="sizeHint" stdset="0">
+      <size>
+       <width>20</width>
+       <height>40</height>
+      </size>
+     </property>
+    </spacer>
+   </item>
+   <item row="3" column="0">
+    <layout class="QGridLayout" name="gridLayout_3">
+     <property name="topMargin">
+      <number>6</number>
+     </property>
+     <property name="bottomMargin">
+      <number>6</number>
+     </property>
+     <item row="0" column="3">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="0" column="1">
+      <widget class="QPushButton" name="pushButton_2">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Button 2</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="2">
+      <widget class="QPushButton" name="pushButton_3">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Button 3</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="0">
+      <widget class="QPushButton" name="pushButton">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Button 1</string>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="2">
+      <layout class="QHBoxLayout" name="horizontalLayout_2">
+       <property name="leftMargin">
+        <number>0</number>
+       </property>
+       <property name="rightMargin">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_9">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>16777215</width>
+           <height>16777215</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="1" column="1">
+      <layout class="QHBoxLayout" name="horizontalLayout_3">
+       <property name="leftMargin">
+        <number>0</number>
+       </property>
+       <property name="rightMargin">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_8">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>16777215</width>
+           <height>16777215</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="1" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_4">
+       <property name="leftMargin">
+        <number>0</number>
+       </property>
+       <property name="rightMargin">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_7">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>16777215</width>
+           <height>16777215</height>
+          </size>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+    </layout>
+   </item>
+   <item row="1" column="0">
+    <widget class="Line" name="line">
+     <property name="orientation">
+      <enum>Qt::Horizontal</enum>
+     </property>
+    </widget>
+   </item>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout">
+     <item row="3" column="3">
+      <widget class="QLineEdit" name="lineEdit_15">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="3">
+      <widget class="QLabel" name="label_12">
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="2">
+      <widget class="QLineEdit" name="lineEdit_13">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="1">
+      <widget class="QLabel" name="label_row_x">
+       <property name="text">
+        <string>x [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="3">
+      <widget class="QLabel" name="label_11">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>New</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="4">
+      <spacer name="horizontalSpacer_2">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="3" column="2">
+      <widget class="QLineEdit" name="lineEdit_11">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="label_measured_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Measured</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="3">
+      <widget class="QLineEdit" name="lineEdit_16">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="2">
+      <widget class="QLineEdit" name="lineEdit_12">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="1">
+      <widget class="QLabel" name="label_row_y">
+       <property name="text">
+        <string>y [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_5">
+       <property name="spacing">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QFrame" name="red_frame_position_left">
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLabel" name="label_measured_title_line2">
+         <property name="text">
+          <string>Position</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QFrame" name="red_frame_position_right">
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="4" column="1">
+      <widget class="QLabel" name="label_row_z">
+       <property name="text">
+        <string>z [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="2">
+      <widget class="QLineEdit" name="lineEdit_10">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="3">
+      <widget class="QLineEdit" name="lineEdit_17">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="5" column="1">
+      <widget class="QLabel" name="label_row_yaw">
+       <property name="text">
+        <string>yaw [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="3">
+      <widget class="QPushButton" name="pushButton_5">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Set New</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="2">
+      <widget class="QLabel" name="label_9">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Current</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="1">
+      <widget class="QLabel" name="label_row_pitch">
+       <property name="text">
+        <string>pitch [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="3">
+      <widget class="QLineEdit" name="lineEdit_14">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="2">
+      <widget class="QLabel" name="label_10">
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="2">
+      <widget class="QPushButton" name="pushButton_4">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Default</string>
+       </property>
+      </widget>
+     </item>
+     <item row="7" column="1">
+      <widget class="QLabel" name="label_row_roll">
+       <property name="text">
+        <string>roll [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_7">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_8">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="4" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_9">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="5" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_10">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="6" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_11">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_pitch">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="7" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_12">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_roll">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+    </layout>
+   </item>
+  </layout>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
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 b361da05..716a287f 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
@@ -114,6 +114,7 @@
 #define REMOTE_CONTROLLER    5
 #define TUNING_CONTROLLER    6
 #define PICKER_CONTROLLER    7
+#define TEMPLATE_CONTROLLER  8
 
 // The constants that "command" changes in the
 // operation state of this agent
@@ -124,6 +125,7 @@
 #define CMD_USE_REMOTE_CONTROLLER    5
 #define CMD_USE_TUNING_CONTROLLER    6
 #define CMD_USE_PICKER_CONTROLLER    7
+#define CMD_USE_TEMPLATE_CONTROLLER  8
 
 
 #define CMD_CRAZYFLY_TAKE_OFF        11
@@ -252,6 +254,7 @@
 #define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
 #define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
 #define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
+#define LOAD_YAML_TEMPLATE_CONTROLLER_AGENT         8
 
 #define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
 #define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
@@ -260,6 +263,7 @@
 #define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
 #define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
 #define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
+#define LOAD_YAML_TEMPLATE_CONTROLLER_COORDINATOR   18
 
 
 // For sending commands to the controller node informing
@@ -276,6 +280,7 @@
 #define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
 #define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
 #define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
+#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_OWN_AGENT  8
 
 #define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
 #define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
@@ -283,4 +288,4 @@
 #define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
 #define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
 #define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
\ No newline at end of file
+#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_COORDINATOR  18
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 609a6882..51c29e93 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -90,7 +90,7 @@ public:
     void showHideController_student_changed();
     void showHideController_picker_changed();
     void showHideController_tuning_changed();
-    void showHideController_safe_changed();
+    void showHideController_template_changed();
 
 
 public slots:
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 babe4cba..6699aa3b 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
@@ -102,7 +102,7 @@ public:
     void showHideController_student_changed();
     void showHideController_picker_changed();
     void showHideController_tuning_changed();
-    void showHideController_safe_changed();
+    void showHideController_template_changed();
 
 
 public slots:
@@ -112,18 +112,19 @@ public slots:
 private slots:
 
     // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
-    void on_enable_safe_button_clicked();
-    void on_enable_tuning_button_clicked();
-    void on_enable_picker_button_clicked();
-    void on_enable_student_button_clicked();
     void on_enable_default_button_clicked();
+    void on_enable_student_button_clicked();
+    void on_enable_picker_button_clicked();
+    void on_enable_tuning_button_clicked();
+    void on_enable_template_button_clicked();
 
     // LOAD YAML BUTTONS ON-CLICK CALLBACK
-    void on_load_yaml_safe_button_clicked();
-    void on_load_yaml_tuning_button_clicked();
-    void on_load_yaml_picker_button_clicked();
-    void on_load_yaml_student_button_clicked();
     void on_load_yaml_default_button_clicked();
+    void on_load_yaml_student_button_clicked();
+    void on_load_yaml_picker_button_clicked();
+    void on_load_yaml_tuning_button_clicked();
+    void on_load_yaml_template_button_clicked();
+
 
 private:
     Ui::EnableControllerLoadYamlBar *ui;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index e1c67caf..2cfdc268 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -131,7 +131,7 @@ private slots:
     void on_action_showHideController_student_changed();
     void on_action_showHideController_picker_changed();
     void on_action_showHideController_tuning_changed();
-    void on_action_showHideController_safe_changed();
+    void on_action_showHideController_template_changed();
 
 };
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
new file mode 100644
index 00000000..dd781546
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
@@ -0,0 +1,22 @@
+#ifndef TEMPLATECONTROLLERTAB_H
+#define TEMPLATECONTROLLERTAB_H
+
+#include <QWidget>
+
+namespace Ui {
+class TemplateControllerTab;
+}
+
+class TemplateControllerTab : public QWidget
+{
+    Q_OBJECT
+
+public:
+    explicit TemplateControllerTab(QWidget *parent = 0);
+    ~TemplateControllerTab();
+
+private:
+    Ui::TemplateControllerTab *ui;
+};
+
+#endif // TEMPLATECONTROLLERTAB_H
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 39a23530..d3cae357 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
@@ -232,9 +232,9 @@ void ControllerTabs::showHideController_tuning_changed()
     showHideController_toggle("Tuning",ui->tuning_tab);
 }
 
-void ControllerTabs::showHideController_safe_changed()
+void ControllerTabs::showHideController_template_changed()
 {
-    showHideController_toggle("Safe",ui->safe_tab);
+    showHideController_toggle("Template",ui->template_tab);
 }
 
 
@@ -384,9 +384,14 @@ void ControllerTabs::setControllerEnabled(int new_controller)
     {
         case SAFE_CONTROLLER:
         {
-            //ui->controller_enabled_label->setText("Safe");
+            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->default_tab );
             break;
         }
+//        case DEFAULT_CONTROLLER:
+//        {
+//            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->default_tab );
+//            break;
+//        }
         case DEMO_CONTROLLER:
         {
             //ui->controller_enabled_label->setText("Demo");
@@ -417,6 +422,11 @@ void ControllerTabs::setControllerEnabled(int new_controller)
             setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->picker_tab );
             break;
         }
+        case TEMPLATE_CONTROLLER:
+        {
+            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->template_tab );
+            break;
+        }
         default:
         {
             //ui->controller_enabled_label->setText("Unknown");
@@ -432,7 +442,7 @@ void ControllerTabs::setAllTabLabelsToNormalColouring()
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->student_tab );
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->picker_tab );
     setTextColourOfTabLabel( m_tab_text_colour_normal , ui->tuning_tab );
-    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->safe_tab );
+    setTextColourOfTabLabel( m_tab_text_colour_normal , ui->template_tab );
 }
 
 void ControllerTabs::setTextColourOfTabLabel(QColor color , QWidget * tab_widget)
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 14396c70..30468755 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
@@ -108,20 +108,19 @@ void EnableControllerLoadYamlBar::showHideController_tuning_changed()
     ui->load_yaml_tuning_button->setHidden( !(ui->load_yaml_tuning_button->isHidden()) );
 }
 
-void EnableControllerLoadYamlBar::showHideController_safe_changed()
+void EnableControllerLoadYamlBar::showHideController_template_changed()
 {
-    ui->enable_safe_button   ->setHidden( !(ui->enable_safe_button->isHidden()) );
-    ui->load_yaml_safe_button->setHidden( !(ui->load_yaml_safe_button->isHidden()) );
+    ui->enable_template_button   ->setHidden( !(ui->enable_template_button->isHidden()) );
+    ui->load_yaml_template_button->setHidden( !(ui->load_yaml_template_button->isHidden()) );
 }
 
 
 
 
 
-
 // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK
 
-void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
+void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
@@ -132,14 +131,14 @@ void EnableControllerLoadYamlBar::on_enable_safe_button_clicked()
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_enable_tuning_button_clicked()
+void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
-    msg.data = CMD_USE_TUNING_CONTROLLER;
+    msg.data = CMD_USE_STUDENT_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Tuning Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Student Controller");
 #endif
 }
 
@@ -154,39 +153,53 @@ void EnableControllerLoadYamlBar::on_enable_picker_button_clicked()
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_enable_student_button_clicked()
+void EnableControllerLoadYamlBar::on_enable_tuning_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
-    msg.data = CMD_USE_STUDENT_CONTROLLER;
+    msg.data = CMD_USE_TUNING_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Student Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Tuning Controller");
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
+void EnableControllerLoadYamlBar::on_enable_template_button_clicked()
 {
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
-    msg.data = CMD_USE_SAFE_CONTROLLER;
+    msg.data = CMD_USE_TEMPLATE_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Template Controller");
 #endif
 }
 
 
+
+
+
+
+
 // LOAD YAML BUTTONS ON-CLICK CALLBACK
 
-void EnableControllerLoadYamlBar::on_load_yaml_safe_button_clicked()
+void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 {
-#ifdef CATKIN_MAKE
-
+    #ifdef CATKIN_MAKE
+    // Create a local variable for the message
+    dfall_pkg::StringWithHeader yaml_filename_msg;
+    // Set for whom this applies to
+    fillStringMessageHeader(yaml_filename_msg);
+    // Specify the data
+    yaml_filename_msg.data = "DefaultController";
+    // Send the message
+    m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
+    // Inform the user that the menu item was selected
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Default Controller YAML was clicked.");
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_load_yaml_tuning_button_clicked()
+void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
@@ -194,11 +207,11 @@ void EnableControllerLoadYamlBar::on_load_yaml_tuning_button_clicked()
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
-    yaml_filename_msg.data = "TuningController";
+    yaml_filename_msg.data = "StudentController";
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
     // Inform the user that the menu item was selected
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Tuning Controller YAML was clicked.");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Student Controller YAML was clicked.");
 #endif
 }
 
@@ -218,7 +231,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_picker_button_clicked()
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
+void EnableControllerLoadYamlBar::on_load_yaml_tuning_button_clicked()
 {
 #ifdef CATKIN_MAKE
     // Create a local variable for the message
@@ -226,27 +239,27 @@ void EnableControllerLoadYamlBar::on_load_yaml_student_button_clicked()
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
-    yaml_filename_msg.data = "StudentController";
+    yaml_filename_msg.data = "TuningController";
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
     // Inform the user that the menu item was selected
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Student Controller YAML was clicked.");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Tuning Controller YAML was clicked.");
 #endif
 }
 
-void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
+void EnableControllerLoadYamlBar::on_load_yaml_template_button_clicked()
 {
-    #ifdef CATKIN_MAKE
+#ifdef CATKIN_MAKE
     // Create a local variable for the message
     dfall_pkg::StringWithHeader yaml_filename_msg;
     // Set for whom this applies to
     fillStringMessageHeader(yaml_filename_msg);
     // Specify the data
-    yaml_filename_msg.data = "DefaultController";
+    yaml_filename_msg.data = "TemplateController";
     // Send the message
     m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg);
     // Inform the user that the menu item was selected
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Default Controller YAML was clicked.");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Load Template Controller YAML was clicked.");
 #endif
 }
 
@@ -254,6 +267,7 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_button_clicked()
 
 
 
+
 //    ----------------------------------------------------------------------------------
 //      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
 //     A A   G      E      NN  N    T        I   D   D  S
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 254a0907..239aa269 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -145,9 +145,8 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     ui->action_showHideController_picker->trigger();
     // > For the tuning controller
     ui->action_showHideController_tuning->trigger();
-    // > For the safe controller
-    ui->action_showHideController_safe->trigger();
-
+    // > For the template controller
+    ui->action_showHideController_template->trigger();
 
 }
 
@@ -246,11 +245,11 @@ void MainWindow::on_action_showHideController_tuning_changed()
     ui->customWidget_controller_tabs->showHideController_tuning_changed();
 }
 
-void MainWindow::on_action_showHideController_safe_changed()
+void MainWindow::on_action_showHideController_template_changed()
 {
     // Notify the UI elements of this change
-    ui->customWidget_enableControllerLoadYamlBar->showHideController_safe_changed();
-    ui->customWidget_controller_tabs->showHideController_safe_changed();
+    ui->customWidget_enableControllerLoadYamlBar->showHideController_template_changed();
+    ui->customWidget_controller_tabs->showHideController_template_changed();
 }
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
new file mode 100644
index 00000000..f16cdf5d
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
@@ -0,0 +1,14 @@
+#include "templatecontrollertab.h"
+#include "ui_templatecontrollertab.h"
+
+TemplateControllerTab::TemplateControllerTab(QWidget *parent) :
+    QWidget(parent),
+    ui(new Ui::TemplateControllerTab)
+{
+    ui->setupUi(this);
+}
+
+TemplateControllerTab::~TemplateControllerTab()
+{
+    delete ui;
+}
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/Constants.h b/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
index fd4d1d4f..71507435 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
@@ -127,6 +127,7 @@
 #define REMOTE_CONTROLLER    5
 #define TUNING_CONTROLLER    6
 #define PICKER_CONTROLLER    7
+#define TEMPLATE_CONTROLLER  8
 
 // The constants that "command" changes in the
 // operation state of this agent
@@ -137,6 +138,7 @@
 #define CMD_USE_REMOTE_CONTROLLER    5
 #define CMD_USE_TUNING_CONTROLLER    6
 #define CMD_USE_PICKER_CONTROLLER    7
+#define CMD_USE_TEMPLATE_CONTROLLER  8
 
 
 #define CMD_CRAZYFLY_TAKE_OFF        11
@@ -266,6 +268,7 @@
 #define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
 #define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
 #define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
+#define LOAD_YAML_TEMPLATE_CONTROLLER_AGENT         7
 
 #define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
 #define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
@@ -274,6 +277,7 @@
 #define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
 #define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
 #define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
+#define LOAD_YAML_TEMPLATE_CONTROLLER_COORDINATOR   18
 
 
 // For sending commands to the controller node informing
@@ -290,6 +294,7 @@
 #define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
 #define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
 #define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
+#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_OWN_AGENT  8
 
 #define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
 #define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
@@ -297,4 +302,5 @@
 #define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
 #define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
 #define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
\ No newline at end of file
+#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
+#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_COORDINATOR  18
\ No newline at end of file
-- 
GitLab


From eac28fac956674cd283ac1286dcd9fc99fd384f8 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 09:05:05 +0100
Subject: [PATCH 68/87] Finished integrating the Template Controller into Qt.
 Next Step is to add a ROS node for it

---
 .../forms/templatecontrollertab.ui            |  40 +-
 .../include/studentcontrollertab.h            |   4 +-
 .../include/templatecontrollertab.h           | 154 ++++
 .../flyingAgentGUI/src/controllertabs.cpp     |  15 +
 .../src/studentcontrollertab.cpp              |  33 +-
 .../src/templatecontrollertab.cpp             | 682 ++++++++++++++++++
 6 files changed, 884 insertions(+), 44 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
index fd7da271..7ffe2b17 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/templatecontrollertab.ui
@@ -70,7 +70,7 @@
       </spacer>
      </item>
      <item row="0" column="1">
-      <widget class="QPushButton" name="pushButton_2">
+      <widget class="QPushButton" name="custom_button_2">
        <property name="sizePolicy">
         <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -83,7 +83,7 @@
       </widget>
      </item>
      <item row="0" column="2">
-      <widget class="QPushButton" name="pushButton_3">
+      <widget class="QPushButton" name="custom_button_3">
        <property name="sizePolicy">
         <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -96,7 +96,7 @@
       </widget>
      </item>
      <item row="0" column="0">
-      <widget class="QPushButton" name="pushButton">
+      <widget class="QPushButton" name="custom_button_1">
        <property name="sizePolicy">
         <sizepolicy hsizetype="Minimum" vsizetype="Fixed">
          <horstretch>0</horstretch>
@@ -117,7 +117,7 @@
         <number>0</number>
        </property>
        <item>
-        <widget class="QLineEdit" name="lineEdit_9">
+        <widget class="QLineEdit" name="lineEdit_custom_3">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -143,7 +143,7 @@
         <number>0</number>
        </property>
        <item>
-        <widget class="QLineEdit" name="lineEdit_8">
+        <widget class="QLineEdit" name="lineEdit_custom_2">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -169,7 +169,7 @@
         <number>0</number>
        </property>
        <item>
-        <widget class="QLineEdit" name="lineEdit_7">
+        <widget class="QLineEdit" name="lineEdit_custom_1">
          <property name="sizePolicy">
           <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
            <horstretch>0</horstretch>
@@ -198,7 +198,7 @@
    <item row="0" column="0">
     <layout class="QGridLayout" name="gridLayout">
      <item row="3" column="3">
-      <widget class="QLineEdit" name="lineEdit_15">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -225,7 +225,7 @@
       </widget>
      </item>
      <item row="1" column="3">
-      <widget class="QLabel" name="label_12">
+      <widget class="QLabel" name="label_new_title_line2">
        <property name="text">
         <string>Setpoint</string>
        </property>
@@ -235,7 +235,7 @@
       </widget>
      </item>
      <item row="5" column="2">
-      <widget class="QLineEdit" name="lineEdit_13">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -275,7 +275,7 @@
       </widget>
      </item>
      <item row="0" column="3">
-      <widget class="QLabel" name="label_11">
+      <widget class="QLabel" name="label_new_title">
        <property name="font">
         <font>
          <weight>75</weight>
@@ -304,7 +304,7 @@
       </spacer>
      </item>
      <item row="3" column="2">
-      <widget class="QLineEdit" name="lineEdit_11">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -350,7 +350,7 @@
       </widget>
      </item>
      <item row="4" column="3">
-      <widget class="QLineEdit" name="lineEdit_16">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -377,7 +377,7 @@
       </widget>
      </item>
      <item row="4" column="2">
-      <widget class="QLineEdit" name="lineEdit_12">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -482,7 +482,7 @@
       </widget>
      </item>
      <item row="2" column="2">
-      <widget class="QLineEdit" name="lineEdit_10">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -512,7 +512,7 @@
       </widget>
      </item>
      <item row="5" column="3">
-      <widget class="QLineEdit" name="lineEdit_17">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -549,7 +549,7 @@
       </widget>
      </item>
      <item row="6" column="3">
-      <widget class="QPushButton" name="pushButton_5">
+      <widget class="QPushButton" name="set_setpoint_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -568,7 +568,7 @@
       </widget>
      </item>
      <item row="0" column="2">
-      <widget class="QLabel" name="label_9">
+      <widget class="QLabel" name="label_current_title">
        <property name="font">
         <font>
          <weight>75</weight>
@@ -594,7 +594,7 @@
       </widget>
      </item>
      <item row="2" column="3">
-      <widget class="QLineEdit" name="lineEdit_14">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
@@ -621,7 +621,7 @@
       </widget>
      </item>
      <item row="1" column="2">
-      <widget class="QLabel" name="label_10">
+      <widget class="QLabel" name="label_current_title_line2">
        <property name="text">
         <string>Setpoint</string>
        </property>
@@ -631,7 +631,7 @@
       </widget>
      </item>
      <item row="6" column="2">
-      <widget class="QPushButton" name="pushButton_4">
+      <widget class="QPushButton" name="default_setpoint_button">
        <property name="sizePolicy">
         <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
index 94f6021f..be7ed5f4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/studentcontrollertab.h
@@ -177,9 +177,9 @@ private:
     bool getTypeAndIDParameters();
 #endif
 
-    void publishSetpoint(float x, float y, float z, float yaw);
+    void publishSetpoint(float x, float y, float z, float yaw_degrees);
 
-    void increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc);
+    void increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc_degrees);
 
 };
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
index dd781546..0f9377bb 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/templatecontrollertab.h
@@ -1,7 +1,80 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for a Template Controller for students build from
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #ifndef TEMPLATECONTROLLERTAB_H
 #define TEMPLATECONTROLLERTAB_H
 
 #include <QWidget>
+#include <QMutex>
+#include <QVector>
+#include <QLineEdit>
+#include <QTextStream>
+
+#ifdef CATKIN_MAKE
+#include <ros/ros.h>
+#include <ros/network.h>
+#include <ros/package.h>
+
+// Include the standard message types
+//#include "std_msgs/Int32.h"
+//#include "std_msgs/Float32.h"
+//#include <std_msgs/String.h>
+
+// Include the DFALL message types
+//#include "dfall_pkg/IntWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
+
+// Include the DFALL service types
+#include "dfall_pkg/GetSetpointService.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// SPECIFY THE PACKAGE NAMESPACE
+//using namespace dfall_pkg;
+
+#else
+// Include the shared definitions
+#include "include/Constants_for_Qt_compile.h"
+
+#endif
+
+
+
+
 
 namespace Ui {
 class TemplateControllerTab;
@@ -15,8 +88,89 @@ public:
     explicit TemplateControllerTab(QWidget *parent = 0);
     ~TemplateControllerTab();
 
+
+
+public slots:
+    void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll);
+    void setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded);
+    void poseDataUnavailableSlot();
+
+
+
+private slots:
+    void on_lineEdit_setpoint_new_x_returnPressed();
+    void on_lineEdit_setpoint_new_y_returnPressed();
+    void on_lineEdit_setpoint_new_z_returnPressed();
+    void on_lineEdit_setpoint_new_yaw_returnPressed();
+
+    void on_set_setpoint_button_clicked();
+
+    void on_default_setpoint_button_clicked();
+
+    void on_custom_button_1_clicked();
+    void on_custom_button_2_clicked();
+    void on_custom_button_3_clicked();
+
+
+
+
+
 private:
     Ui::TemplateControllerTab *ui;
+
+    // --------------------------------------------------- //
+    // PRIVATE VARIABLES
+
+    // The type of this node, i.e., agent or a coordinator,
+    // specified as a parameter in the "*.launch" file
+    int m_type = 0;
+
+    // The ID  of this node
+    int m_ID;
+
+    // For coordinating multiple agents
+    std::vector<int> m_vector_of_agentIDs_toCoordinate;
+    bool m_shouldCoordinateAll = true;
+    QMutex m_agentIDs_toCoordinate_mutex;
+
+
+
+#ifdef CATKIN_MAKE
+    // PUBLISHER
+    // > For requesting the setpoint to be changed
+    ros::Publisher requestSetpointChangePublisher;
+
+    // SUBSCRIBER
+    // > For being notified when the setpoint is changed
+    ros::Subscriber setpointChangedSubscriber;
+
+    // PUBLISHER
+    // > For notifying that a custom button is pressed
+    ros::Publisher customButtonPublisher;
+#endif
+
+
+
+    // --------------------------------------------------- //
+    // PRIVATE FUNCTIONS
+
+#ifdef CATKIN_MAKE
+    // For receiving message that the setpoint was changed
+    void setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint);
+
+    // Publish a message when a custom button is pressed
+    void publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer);
+
+    // Fill the header for a message
+    void fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg );
+    void fillCustomButtonMessageHeader( dfall_pkg::CustomButtonWithHeader & msg );
+
+    // Get the paramters that specify the type and ID
+    bool getTypeAndIDParameters();
+#endif
+
+    void publishSetpoint(float x, float y, float z, float yaw_degrees);
+
 };
 
 #endif // TEMPLATECONTROLLERTAB_H
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 d3cae357..ec83ca37 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
@@ -77,6 +77,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->tuning_controller_tab_widget , &TuningControllerTab::setMeasuredPose
         );
 
+    QObject::connect(
+            this , &ControllerTabs::measuredPoseValueChanged ,
+            ui->template_controller_tab_widget , &TemplateControllerTab::setMeasuredPose
+        );
+
 
 
     // CONNECT THE "MEASUREMENTS UNAVAILABLE" SIGNAL TO
@@ -101,6 +106,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->tuning_controller_tab_widget , &TuningControllerTab::poseDataUnavailableSlot
         );
 
+    QObject::connect(
+            this , &ControllerTabs::poseDataUnavailableSignal ,
+            ui->template_controller_tab_widget , &TemplateControllerTab::poseDataUnavailableSlot
+        );
+
 
     // CONNECT TO THE COORDINATOR SIGNAL TO BE ALWAYS UPDATED
     // WITH THE LIST OF AGENT IDs TO COORDINATE
@@ -127,6 +137,11 @@ ControllerTabs::ControllerTabs(QWidget *parent) :
             ui->tuning_controller_tab_widget , &TuningControllerTab::setAgentIDsToCoordinate
         );
 
+    QObject::connect(
+            this , &ControllerTabs::agentIDsToCoordinateChanged ,
+            ui->template_controller_tab_widget , &TemplateControllerTab::setAgentIDsToCoordinate
+        );
+
     
 
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index cc9b3503..e89ddaff 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -329,7 +329,7 @@ void StudentControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWith
     ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3));
 
     if (yaw < 0.0f) qstr = ""; else qstr = "+";
-    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 3));
+    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1));
 }
 #endif
 
@@ -357,7 +357,7 @@ void StudentControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWith
 //    ----------------------------------------------------------------------------------
 
 
-void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw)
+void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw_degrees)
 {
 #ifdef CATKIN_MAKE
     // Initialise the message as a local variable
@@ -370,16 +370,16 @@ void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw)
     msg.x   = x;
     msg.y   = y;
     msg.z   = z;
-    msg.yaw = yaw * DEG2RAD;
+    msg.yaw = yaw_degrees * DEG2RAD;
 
     // Publish the setpoint
     this->requestSetpointChangePublisher.publish(msg);
 
     // Inform the user about the change
-    ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]");
+    ROS_INFO_STREAM("[STUDENT CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw_degrees << "]");
 #else
     // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
-    QTextStream(stdout) << "[STUDENT CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw << "]";
+    QTextStream(stdout) << "[STUDENT CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw_degrees << "]";
 #endif
 }
 
@@ -388,12 +388,6 @@ void StudentControllerTab::publishSetpoint(float x, float y, float z, float yaw)
 void StudentControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
 {
     ui->set_setpoint_button->animateClick();
-
-#ifdef CATKIN_MAKE
-#else
-    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
-    QTextStream(stdout) << "[STUDENT CONTROLLER TAB] return pressed for x setpoint";
-#endif
 }
 
 void StudentControllerTab::on_lineEdit_setpoint_new_y_returnPressed()
@@ -423,29 +417,24 @@ void StudentControllerTab::on_set_setpoint_button_clicked()
         x = (ui->lineEdit_setpoint_new_x->text()).toFloat();
     else
         x = (ui->lineEdit_setpoint_current_x->text()).toFloat();
-    // > For x
+    // > For y
     if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
         y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
     else
         y = (ui->lineEdit_setpoint_current_y->text()).toFloat();
-    // > For x
+    // > For z
     if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
         z = (ui->lineEdit_setpoint_new_z->text()).toFloat();
     else
         z = (ui->lineEdit_setpoint_current_z->text()).toFloat();
-    // > For x
+    // > For yaws
     if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty())
         yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat();
     else
         yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
-#ifdef CATKIN_MAKE
     // Call the function to publish the setpoint
     publishSetpoint(x,y,z,yaw);
-#else
-    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
-    QTextStream(stdout) << "[STUDENT CONTROLLER TAB] set setpoint button clicked";
-#endif
 }
 
 void StudentControllerTab::on_default_setpoint_button_clicked()
@@ -604,7 +593,7 @@ void StudentControllerTab::on_yaw_increment_minus_button_clicked()
 }
 
 
-void StudentControllerTab::increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc)
+void StudentControllerTab::increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc_degrees)
 {
 	
     if (m_type == TYPE_AGENT)
@@ -616,7 +605,7 @@ void StudentControllerTab::increment_setpoint_by(float x_inc, float y_inc, float
                 (ui->lineEdit_setpoint_current_x->text()  ).toFloat() + x_inc,
                 (ui->lineEdit_setpoint_current_y->text()  ).toFloat() + y_inc,
                 (ui->lineEdit_setpoint_current_z->text()  ).toFloat() + z_inc,
-                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + yaw_inc
+                (ui->lineEdit_setpoint_current_yaw->text()).toFloat() + yaw_inc_degrees
             );
     }
     else if (m_type == TYPE_COORDINATOR)
@@ -645,7 +634,7 @@ void StudentControllerTab::increment_setpoint_by(float x_inc, float y_inc, float
 	    float x_new   = x   + x_inc;
 	    float y_new   = y   + y_inc;
 	    float z_new   = z   + z_inc;
-	    float yaw_new = yaw + yaw_inc;
+        float yaw_new = yaw + yaw_inc_degrees;
 
         // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
     	QString qstr = "";
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
index f16cdf5d..b0da98f0 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/templatecontrollertab.cpp
@@ -1,3 +1,38 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    The GUI for a Template Controller for students build from
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
 #include "templatecontrollertab.h"
 #include "ui_templatecontrollertab.h"
 
@@ -6,9 +41,656 @@ TemplateControllerTab::TemplateControllerTab(QWidget *parent) :
     ui(new Ui::TemplateControllerTab)
 {
     ui->setupUi(this);
+
+    // Hide the two red frames that are used to indcated
+    // when pose data is occluded
+    ui->red_frame_position_left->setVisible(false);
+    ui->red_frame_position_right->setVisible(false);
+
+
+
+#ifdef CATKIN_MAKE
+
+    //ros::init();
+
+    // Get the namespace of this node
+    std::string this_namespace = ros::this_node::getNamespace();
+    ROS_INFO_STREAM("[TEMPLATE CONTROLLER TAB GUI] ros::this_node::getNamespace() =  " << this_namespace);
+
+    // Get the type and ID of this flying agent GUI
+    bool isValid_type_and_ID = getTypeAndIDParameters();
+
+    // Stall if the node IDs are not valid
+    if ( !isValid_type_and_ID )
+    {
+        ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] Node NOT FUNCTIONING :-)");
+        ros::spin();
+    }
+
+
+    // CREATE A NODE HANDLE TO THIS GUI
+    ros::NodeHandle nodeHandle_for_this_gui(this_namespace);
+
+    // CREATE THE REQUEST SETPOINT CHANGE PUBLISHER
+    requestSetpointChangePublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::SetpointWithHeader>("TemplateControllerService/RequestSetpointChange", 1);
+
+    // SUBSCRIBE TO SETPOINT CHANGES
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("TemplateControllerService/SetpointChanged", 1, &TemplateControllerTab::setpointChangedCallback, this);
+    }
+
+    // CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
+    customButtonPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::CustomButtonWithHeader>("TemplateControllerService/CustomButtonPressed", 1);
+
+    // GET THE CURRENT SETPOINT
+    // Only if this is an agent GUI
+    if (m_type == TYPE_AGENT)
+    {
+        // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = nodeHandle_for_this_gui.serviceClient<dfall_pkg::GetSetpointService>("TemplateControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[TEMPLATE CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+    }
+
+#endif
+
 }
 
 TemplateControllerTab::~TemplateControllerTab()
 {
     delete ui;
 }
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC  U   U   SSSS  TTTTT   OOO   M   M
+//    C      U   U  S        T    O   O  MM MM
+//    C      U   U   SSS     T    O   O  M M M
+//    C      U   U      S    T    O   O  M   M
+//     CCCC   UUU   SSSS     T     OOO   M   M
+//
+//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
+//    B   B  U   U    T      T    O   O  NN  N  S
+//    BBBB   U   U    T      T    O   O  N N N   SSS
+//    B   B  U   U    T      T    O   O  N  NN      S
+//    BBBB    UUU     T      T     OOO   N   N  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void TemplateControllerTab::publish_custom_button_command(int button_index , QLineEdit * lineEdit_pointer)
+{
+    // Initialise the message as a local variable
+    dfall_pkg::CustomButtonWithHeader msg;
+    // Fill the header of the message
+    fillCustomButtonMessageHeader( msg );
+    // Fill in the button index
+    msg.button_index = button_index;
+    // Get the line edit data, as a float if possible
+    bool isValidFloat = false;
+    float lineEdit_as_float = (lineEdit_pointer->text()).toFloat(&isValidFloat);
+    // Fill in the data
+    if (isValidFloat)
+        msg.float_data = lineEdit_as_float;
+    else
+        msg.string_data = (lineEdit_pointer->text()).toStdString();
+    // Publish the setpoint
+    this->customButtonPublisher.publish(msg);
+    // Inform the user about the change
+    ROS_INFO_STREAM("[TEMPLATE CONTROLLER TAB GUI] button " << button_index << " clicked.");
+}
+#endif
+
+
+void TemplateControllerTab::on_custom_button_1_clicked()
+{
+#ifdef CATKIN_MAKE
+    publish_custom_button_command(1,ui->lineEdit_custom_1);
+#endif
+}
+
+void TemplateControllerTab::on_custom_button_2_clicked()
+{
+#ifdef CATKIN_MAKE
+    publish_custom_button_command(2,ui->lineEdit_custom_2);
+#endif
+}
+
+void TemplateControllerTab::on_custom_button_3_clicked()
+{
+#ifdef CATKIN_MAKE
+    publish_custom_button_command(3,ui->lineEdit_custom_3);
+#endif
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    PPPP    OOO    SSSS  EEEEE     DDDD     A    TTTTT    A
+//    P   P  O   O  S      E         D   D   A A     T     A A
+//    PPPP   O   O   SSS   EEE       D   D  A   A    T    A   A
+//    P      O   O      S  E         D   D  AAAAA    T    AAAAA
+//    P       OOO   SSSS   EEEEE     DDDD   A   A    T    A   A
+//    ----------------------------------------------------------------------------------
+
+
+void TemplateControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool occluded)
+{
+    if (!occluded)
+    {
+        // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+        QString qstr = "";
+        // UPDATE THE MEASUREMENT COLUMN
+        if (x < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_x->setText(qstr + QString::number( x, 'f', 3));
+        if (y < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_y->setText(qstr + QString::number( y, 'f', 3));
+        if (z < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
+
+        if (roll < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        if (pitch < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
+        if (yaw < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
+
+        // Ensure the red frames are not visible
+        if ( ui->red_frame_position_left->isVisible() )
+            ui->red_frame_position_left->setVisible(false);
+        if ( ui->red_frame_position_right->isVisible() )
+            ui->red_frame_position_right->setVisible(false);
+    }
+    else
+    {
+        // Make visible the red frames to indicate occluded
+        if ( !(ui->red_frame_position_left->isVisible()) )
+            ui->red_frame_position_left->setVisible(true);
+        if ( !(ui->red_frame_position_right->isVisible()) )
+            ui->red_frame_position_right->setVisible(true);
+    }
+}
+
+
+void TemplateControllerTab::poseDataUnavailableSlot()
+{
+    ui->lineEdit_measured_x->setText("xx.xx");
+    ui->lineEdit_measured_y->setText("xx.xx");
+    ui->lineEdit_measured_z->setText("xx.xx");
+
+    ui->lineEdit_measured_roll->setText("xx.xx");
+    ui->lineEdit_measured_pitch->setText("xx.xx");
+    ui->lineEdit_measured_yaw->setText("xx.xx");
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC  H   H    A    N   N   GGGG  EEEEE  DDDD
+//    C      H   H   A A   NN  N  G      E      D   D
+//    C      HHHHH  A   A  N N N  G      EEE    D   D
+//    C      H   H  AAAAA  N  NN  G   G  E      D   D
+//     CCCC  H   H  A   A  N   N   GGGG  EEEEE  DDDD
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+#ifdef CATKIN_MAKE
+void TemplateControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
+{
+    // INITIALISE A STRING VARIABLE FOR ADDING THE "+"
+    QString qstr = "";
+
+    // EXTRACT THE SETPOINT
+    float x = newSetpoint.x;
+    float y = newSetpoint.y;
+    float z = newSetpoint.z;
+    float yaw = newSetpoint.yaw;
+
+    // UPDATE THE SETPOINT COLUMN
+    if (x < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_x->setText(qstr + QString::number( x, 'f', 3));
+    if (y < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_y->setText(qstr + QString::number( y, 'f', 3));
+    if (z < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_z->setText(qstr + QString::number( z, 'f', 3));
+
+    if (yaw < 0.0f) qstr = ""; else qstr = "+";
+    ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1));
+}
+#endif
+
+
+
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    RRRR   EEEEE   QQQ   U   U  EEEEE   SSSS  TTTTT     N   N  EEEEE  W     W
+//    R   R  E      Q   Q  U   U  E      S        T       NN  N  E      W     W
+//    RRRR   EEE    Q   Q  U   U  EEE     SSS     T       N N N  EEE    W     W
+//    R   R  E      Q  Q   U   U  E          S    T       N  NN  E       W W W
+//    R   R  EEEEE   QQ Q   UUU   EEEEE  SSSS     T       N   N  EEEEE    W W
+//
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//    ----------------------------------------------------------------------------------
+
+
+void TemplateControllerTab::publishSetpoint(float x, float y, float z, float yaw_degrees)
+{
+#ifdef CATKIN_MAKE
+    // Initialise the message as a local variable
+    dfall_pkg::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.x   = x;
+    msg.y   = y;
+    msg.z   = z;
+    msg.yaw = yaw_degrees * DEG2RAD;
+
+    // Publish the setpoint
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[TEMPLATE CONTROLLER GUI] Published request for setpoint change to: [" << x << ", "<< y << ", "<< z << ", "<< yaw_degrees << "]");
+#else
+    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
+    QTextStream(stdout) << "[TEMPLATE CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw_degrees << "]";
+#endif
+}
+
+
+
+void TemplateControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void TemplateControllerTab::on_lineEdit_setpoint_new_y_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void TemplateControllerTab::on_lineEdit_setpoint_new_z_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void TemplateControllerTab::on_lineEdit_setpoint_new_yaw_returnPressed()
+{
+    ui->set_setpoint_button->animateClick();
+}
+
+void TemplateControllerTab::on_set_setpoint_button_clicked()
+{
+
+    // Initialise local variable for each of (x,y,z,yaw)
+    float x = 0.0f, y = 0.0f, z = 0.0f, yaw = 0.0f;
+
+    // Take the new value if available, otherwise use the old value
+    // > For x
+    if(!ui->lineEdit_setpoint_new_x->text().isEmpty())
+        x = (ui->lineEdit_setpoint_new_x->text()).toFloat();
+    else
+        x = (ui->lineEdit_setpoint_current_x->text()).toFloat();
+    // > For y
+    if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
+        y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
+    else
+        y = (ui->lineEdit_setpoint_current_y->text()).toFloat();
+    // > For z
+    if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
+        z = (ui->lineEdit_setpoint_new_z->text()).toFloat();
+    else
+        z = (ui->lineEdit_setpoint_current_z->text()).toFloat();
+    // > For yaw
+    if(!ui->lineEdit_setpoint_new_yaw->text().isEmpty())
+        yaw = (ui->lineEdit_setpoint_new_yaw->text()).toFloat();
+    else
+        yaw = (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+    // Call the function to publish the setpoint
+    publishSetpoint(x,y,z,yaw);
+}
+
+void TemplateControllerTab::on_default_setpoint_button_clicked()
+{
+#ifdef CATKIN_MAKE
+    // Publish this as a blank setpoint with the
+    // "buttonID" field set appropriately
+
+    // Initialise the message as a local variable
+    dfall_pkg::SetpointWithHeader msg;
+
+    // Fill the header of the message
+    fillSetpointMessageHeader( msg );
+
+    // Fill in the (x,y,z,yaw) values
+    msg.buttonID = REQUEST_DEFAULT_SETPOINT_BUTTON_ID;
+
+    // Publish the default setpoint button press
+    this->requestSetpointChangePublisher.publish(msg);
+
+    // Inform the user about the change
+    ROS_INFO_STREAM("[TEMPLATE CONTROLLER GUI] Published request for setpoint change to the default");
+#endif
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
+//     A A   G      E      NN  N    T        I   D   D  S
+//    A   A  G      EEE    N N N    T        I   D   D   SSS
+//    AAAAA  G   G  E      N  NN    T        I   D   D      S
+//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
+//    ----------------------------------------------------------------------------------
+
+
+void TemplateControllerTab::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
+{
+
+    // Lock the mutex
+    m_agentIDs_toCoordinate_mutex.lock();
+    // Add the "coordinate all" flag
+    m_shouldCoordinateAll = shouldCoordinateAll;
+    // Clear the previous list of agent IDs
+    m_vector_of_agentIDs_toCoordinate.clear();
+    // Copy across the agent IDs, if necessary
+    if (!shouldCoordinateAll)
+    {
+        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
+        {
+            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
+        }
+    }
+    // Unlock the mutex
+    m_agentIDs_toCoordinate_mutex.unlock();
+
+
+#ifdef CATKIN_MAKE
+    // If there is only one agent to coordinate,
+    // then subscribe to the relevant data
+    if (agentIDs.length() == 1)
+    {
+
+        // // > Create the appropriate node handle
+        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
+        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
+
+        // // > Request the current setpoint
+        ros::ServiceClient getCurrentSetpointServiceClient = agent_base_nodeHandle.serviceClient<dfall_pkg::GetSetpointService>("TemplateControllerService/GetCurrentSetpoint", false);
+        dfall_pkg::GetSetpointService getSetpointCall;
+        getSetpointCall.request.data = 0;
+        getCurrentSetpointServiceClient.waitForExistence(ros::Duration(2.0));
+        if(getCurrentSetpointServiceClient.call(getSetpointCall))
+        {
+            setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
+        }
+        else
+        {
+            // Inform the user
+            ROS_INFO("[TEMPLATE CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
+        }
+
+        // SUBSCRIBERS
+        // > For receiving message that the setpoint was changed
+        setpointChangedSubscriber = agent_base_nodeHandle.subscribe("TemplateControllerService/SetpointChanged", 1, &TemplateControllerTab::setpointChangedCallback, this);
+    }
+    else
+    {
+        // Unsubscribe
+        setpointChangedSubscriber.shutdown();
+
+        // Set information back to the default
+        ui->lineEdit_setpoint_current_x->setText("xx.xx");
+        ui->lineEdit_setpoint_current_y->setText("xx.xx");
+        ui->lineEdit_setpoint_current_z->setText("xx.xx");
+        ui->lineEdit_setpoint_current_yaw->setText("xx.xx");
+
+    }
+#endif
+}
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
+//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
+//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
+//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
+//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void TemplateControllerTab::fillSetpointMessageHeader( dfall_pkg::SetpointWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+}
+#endif
+
+
+
+#ifdef CATKIN_MAKE
+// Fill the header for a message
+void TemplateControllerTab::fillCustomButtonMessageHeader( dfall_pkg::CustomButtonWithHeader & msg )
+{
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            msg.shouldCheckForAgentID = false;
+            break;
+        }
+        case TYPE_COORDINATOR:
+        {
+            // Lock the mutex
+            m_agentIDs_toCoordinate_mutex.lock();
+            // Add the "coordinate all" flag
+            msg.shouldCheckForAgentID = !(m_shouldCoordinateAll);
+            // Add the agent IDs if necessary
+            if (!m_shouldCoordinateAll)
+            {
+                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
+                {
+                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
+                }
+            }
+            // Unlock the mutex
+            m_agentIDs_toCoordinate_mutex.unlock();
+            break;
+        }
+
+        default:
+        {
+            msg.shouldCheckForAgentID = true;
+            ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+}
+#endif
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
+//     I   D   D     &           T     Y Y   P   P  E
+//     I   D   D      &          T      Y    PPPP   EEE
+//     I   D   D     & & &       T      Y    P      E
+//    III  DDDD       &&&        T      Y    P      EEEEE
+//    ----------------------------------------------------------------------------------
+
+
+
+#ifdef CATKIN_MAKE
+bool TemplateControllerTab::getTypeAndIDParameters()
+{
+    // Initialise the return variable as success
+    bool return_was_successful = true;
+
+    // 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 value of the "type" parameter into a local string variable
+    std::string type_string;
+    if(!nodeHandle.getParam("type", type_string))
+    {
+        // Throw an error if the agent ID parameter could not be obtained
+        ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] Failed to get type");
+    }
+
+    // Set the "m_type" class variable based on this string loaded
+    if ((!type_string.compare("coordinator")))
+    {
+        m_type = TYPE_COORDINATOR;
+    }
+    else if ((!type_string.compare("agent")))
+    {
+        m_type = TYPE_AGENT;
+    }
+    else
+    {
+        // Set "m_type" to the value indicating that it is invlid
+        m_type = TYPE_INVALID;
+        return_was_successful = false;
+        ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] The 'type' parameter retrieved was not recognised.");
+    }
+
+
+    // Construct the string to the namespace of this Paramater Service
+    switch (m_type)
+    {
+        case TYPE_AGENT:
+        {
+            // Get the value of the "agentID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("agentID", m_ID))
+            {
+                // Throw an error if the agent ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] Failed to get agentID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[TEMPLATE CONTROLLER TAB GUI] Is of type AGENT with ID = " << m_ID);
+            }
+            break;
+        }
+
+        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
+        // > The master GUI
+        case TYPE_COORDINATOR:
+        {
+            // Get the value of the "coordID" parameter into the class variable "m_Id"
+            if(!nodeHandle.getParam("coordID", m_ID))
+            {
+                // Throw an error if the coord ID parameter could not be obtained
+                return_was_successful = false;
+                ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] Failed to get coordID");
+            }
+            else
+            {
+                // Inform the user about the type and ID
+                ROS_INFO_STREAM("[TEMPLATE CONTROLLER TAB GUI] Is of type COORDINATOR with ID = " << m_ID);
+            }
+            break;
+        }
+
+        default:
+        {
+            // Throw an error if the type is not recognised
+            return_was_successful = false;
+            ROS_ERROR("[TEMPLATE CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
+            break;
+        }
+    }
+
+    // Return
+    return return_was_successful;
+}
+#endif
-- 
GitLab


From 849e238798baa833788eb90f6fee86cf6e0a2b48 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 10:03:08 +0100
Subject: [PATCH 69/87] Added the Template Controller ROS node. Needs to be
 compiled and tested.

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt         |   7 +
 .../include/nodes/FlyingAgentClient.h         |   3 +
 .../include/nodes/PickerControllerService.h   |   9 +-
 .../include/nodes/TemplateControllerService.h | 237 +++++
 dfall_ws/src/dfall_pkg/launch/Agent.launch    |  14 +
 .../src/dfall_pkg/param/ClientConfig.yaml     |  18 +-
 .../dfall_pkg/param/TemplateController.yaml   |  28 +
 .../src/nodes/DefaultControllerService.cpp    |   6 +-
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp |  28 +
 .../src/nodes/RemoteControllerService.cpp     |   6 +-
 .../src/nodes/StudentControllerService.cpp    |  12 +-
 .../src/nodes/TemplateControllerService.cpp   | 994 ++++++++++++++++++
 .../src/nodes/TuningControllerService.cpp     |   8 -
 13 files changed, 1331 insertions(+), 39 deletions(-)
 create mode 100644 dfall_ws/src/dfall_pkg/include/nodes/TemplateControllerService.h
 create mode 100644 dfall_ws/src/dfall_pkg/param/TemplateController.yaml
 create mode 100644 dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index 5e4e44e1..5c26fb13 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -117,6 +117,7 @@ set(SRC_HDRS_QOBJECT_FLYING_AGENT_GUI
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/rosNodeThread_for_flyingAgentGUI.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/safecontrollertab.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/studentcontrollertab.h
+  ${FLYING_AGENT_GUI_LIB_PATH_INC}/templatecontrollertab.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/topbanner.h
   ${FLYING_AGENT_GUI_LIB_PATH_INC}/tuningcontrollertab.h
   )
@@ -132,6 +133,7 @@ qt5_wrap_ui(UIS_HDRS_FLYING_AGENT_GUI
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/pickercontrollertab.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/safecontrollertab.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/studentcontrollertab.ui
+  ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/templatecontrollertab.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/topbanner.ui
   ${FLYING_AGENT_GUI_LIB_PATH_FORMS}/tuningcontrollertab.ui
   )
@@ -324,6 +326,8 @@ add_executable(TuningControllerService   src/nodes/TuningControllerService.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(PickerControllerService   src/nodes/PickerControllerService.cpp
                                          src/classes/GetParamtersAndNamespaces.cpp)
+add_executable(TemplateControllerService src/nodes/TemplateControllerService.cpp
+                                         src/classes/GetParamtersAndNamespaces.cpp)
 add_executable(CentralManagerService     src/nodes/CentralManagerService.cpp src/CrazyflieIO.cpp)
 add_executable(ParameterService          src/nodes/ParameterService.cpp)
 
@@ -365,6 +369,7 @@ set(FLYING_AGENT_GUI_CPP_SOURCES         # compilation of sources
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/pickercontrollertab.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/safecontrollertab.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/studentcontrollertab.cpp
+    ${FLYING_AGENT_GUI_LIB_PATH_SRC}/templatecontrollertab.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/topbanner.cpp
     ${FLYING_AGENT_GUI_LIB_PATH_SRC}/tuningcontrollertab.cpp
     )
@@ -397,6 +402,7 @@ add_dependencies(MpcControllerService      dfall_pkg_generate_messages_cpp ${cat
 add_dependencies(RemoteControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(TuningControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(PickerControllerService   dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(TemplateControllerService dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(CentralManagerService     dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 add_dependencies(ParameterService          dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
@@ -448,6 +454,7 @@ endif()
 target_link_libraries(RemoteControllerService   ${catkin_LIBRARIES})
 target_link_libraries(TuningControllerService   ${catkin_LIBRARIES})
 target_link_libraries(PickerControllerService   ${catkin_LIBRARIES})
+target_link_libraries(TemplateControllerService ${catkin_LIBRARIES})
 target_link_libraries(CentralManagerService     ${catkin_LIBRARIES})
 target_link_libraries(ParameterService          ${catkin_LIBRARIES})
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index d39549bc..9e1d64e2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -135,6 +135,8 @@ ros::ServiceClient remoteController;
 ros::ServiceClient tuningController;
 // The Picker controller specified in the ClientConfig.yaml
 ros::ServiceClient pickerController;
+// The Template controller specified in the ClientConfig.yaml
+ros::ServiceClient templateController;
 
 
 //values for safteyCheck
@@ -289,6 +291,7 @@ void loadMpcController();
 void loadRemoteController();
 void loadTuningController();
 void loadPickerController();
+void loadTemplateController();
 
 void sendMessageUsingController(int controller);
 void setInstantController(int controller);
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
index b8263334..fab684a8 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
@@ -213,10 +213,11 @@ float m_weight_cf_in_newtons = 0.0;
 std::vector<float> m_previous_stateErrorInertial = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
 
 // The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
-std::vector<float> yaml_gainMatrixThrust_NineStateVector (9,0.0);
-std::vector<float> yaml_gainMatrixRollRate               (9,0.0);
-std::vector<float> yaml_gainMatrixPitchRate              (9,0.0);
-std::vector<float> yaml_gainMatrixYawRate                (9,0.0);
+std::vector<float> yaml_gainMatrixThrust_NineStateVector  =  { 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixRollRate                =  { 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixPitchRate               =  { 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00};
+std::vector<float> yaml_gainMatrixYawRate                 =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30};
+
 
 // The 16-bit command limits
 float yaml_cmd_sixteenbit_min = 1000;
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/TemplateControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/TemplateControllerService.h
new file mode 100644
index 00000000..d7e69289
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/include/nodes/TemplateControllerService.h
@@ -0,0 +1,237 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    A Template Controller for students build from
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    III  N   N   CCCC  L      U   U  DDDD   EEEEE   SSSS
+//     I   NN  N  C      L      U   U  D   D  E      S
+//     I   N N N  C      L      U   U  D   D  EEE     SSS
+//     I   N  NN  C      L      U   U  D   D  E          S
+//    III  N   N   CCCC  LLLLL   UUU   DDDD   EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These various headers need to be included so that this controller service can be
+// connected with the D-FaLL system.
+
+//some useful libraries
+#include <math.h>
+#include <stdlib.h>
+#include "ros/ros.h"
+#include <ros/package.h>
+
+// Include the standard message types
+#include "std_msgs/Int32.h"
+#include "std_msgs/Float32.h"
+#include <std_msgs/String.h>
+
+// Include the DFALL message types
+#include "dfall_pkg/IntWithHeader.h"
+//#include "dfall_pkg/StringWithHeader.h"
+#include "dfall_pkg/SetpointWithHeader.h"
+#include "dfall_pkg/CustomButtonWithHeader.h"
+#include "dfall_pkg/ViconData.h"
+#include "dfall_pkg/Setpoint.h"
+#include "dfall_pkg/ControlCommand.h"
+#include "dfall_pkg/Controller.h"
+#include "dfall_pkg/DebugMsg.h"
+
+// Include the DFALL service types
+#include "dfall_pkg/LoadYamlFromFilename.h"
+#include "dfall_pkg/GetSetpointService.h"
+
+// Include the shared definitions
+#include "nodes/Constants.h"
+
+// Include other classes
+#include "classes/GetParamtersAndNamespaces.h"
+
+// Need for having a ROS "bag" to store data for post-analysis
+//#include <rosbag/bag.h>
+
+
+
+
+
+// Namespacing the package
+using namespace dfall_pkg;
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    DDDD   EEEEE  FFFFF  III  N   N  EEEEE   SSSS
+//    D   D  E      F       I   NN  N  E      S
+//    D   D  EEE    FFF     I   N N N  EEE     SSS
+//    D   D  E      F       I   N  NN  E          S
+//    DDDD   EEEEE  F      III  N   N  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These constants are defined to make the code more readable and adaptable.
+
+// NOTE: many constants are already defined in the
+//       "Constant.h" header file
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    V   V    A    RRRR   III    A    BBBB   L      EEEEE   SSSS
+//    V   V   A A   R   R   I    A A   B   B  L      E      S
+//    V   V  A   A  RRRR    I   A   A  BBBB   L      EEE     SSS
+//     V V   AAAAA  R  R    I   AAAAA  B   B  L      E          S
+//      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+// The ID of the agent that this node is monitoring
+int m_agentID;
+
+// The ID of the agent that can coordinate this node
+int m_coordID;
+
+// NAMESPACES FOR THE PARAMETER SERVICES
+// > For the paramter service of this agent
+std::string m_namespace_to_own_agent_parameter_service;
+// > For the parameter service of the coordinator
+std::string m_namespace_to_coordinator_parameter_service;
+
+
+
+// VARAIBLES FOR VALUES LOADED FROM THE YAML FILE
+// > the mass of the crazyflie, in [grams]
+float yaml_cf_mass_in_grams = 25.0;
+
+// > the frequency at which the controller is running
+float yaml_control_frequency = 200.0;
+
+// > the coefficients of the 16-bit command to thrust conversion
+//std::vector<float> yaml_motorPoly(3);
+std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
+
+
+// The min and max for saturating 16 bit thrust commands
+float yaml_command_sixteenbit_min = 1000;
+float yaml_command_sixteenbit_max = 60000;
+
+// > the default setpoint, the ordering is (x,y,z,yaw),
+//   with units [meters,meters,meters,radians]
+std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
+
+// Boolean indiciating whether the "Debug Message" of this agent should be published or not
+bool yaml_shouldPublishDebugMessage = false;
+
+// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
+bool yaml_shouldDisplayDebugInfo = false;
+
+// The LQR Controller parameters for "LQR_RATE_MODE"
+std::vector<float> yaml_gainMatrixThrust_NineStateVector  =  { 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixRollRate                =  { 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixPitchRate               =  { 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00};
+std::vector<float> yaml_gainMatrixYawRate                 =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30};
+
+
+
+// The weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = 0.0;
+
+// The location error of the Crazyflie at the "previous" time step
+float m_previous_stateErrorInertial[9];
+
+// The setpoint to be tracked, the ordering is (x,y,z,yaw),
+// with units [meters,meters,meters,radians]
+std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
+
+
+
+
+// ROS Publisher for debugging variables
+ros::Publisher m_debugPublisher;
+
+// ROS Publisher for inform the network about
+// changes to the setpoin
+ros::Publisher m_setpointChangedPublisher;
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    PPPP   RRRR    OOO   TTTTT   OOO   TTTTT  Y   Y  PPPP   EEEEE   SSSS
+//    P   P  R   R  O   O    T    O   O    T     Y Y   P   P  E      S
+//    PPPP   RRRR   O   O    T    O   O    T      Y    PPPP   EEE     SSS
+//    P      R  R   O   O    T    O   O    T      Y    P      E          S
+//    P      R   R   OOO     T     OOO     T      Y    P      EEEEE  SSSS
+//    ----------------------------------------------------------------------------------
+
+// These function prototypes are not strictly required for this code to
+// complile, but adding the function prototypes here means the the functions
+// can be written below in any order. If the function prototypes are not
+// included then the function need to written below in an order that ensure
+// each function is implemented before it is called from another function,
+// hence why the "main" function is at the bottom.
+
+// CONTROLLER COMPUTATIONS
+bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
+
+// TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR
+// INTO AN (x,y) BODY FRAME ERROR
+void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured);
+
+// CONVERSION FROM THRUST IN NEWTONS TO 16-BIT COMMAND
+float computeMotorPolyBackward(float thrust);
+
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint);
+
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw);
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
+
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
+
+// FOR LOADING THE YAML PARAMETERS
+void isReadyTemplateControllerYamlCallback(const IntWithHeader & msg);
+void fetchTemplateControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/launch/Agent.launch b/dfall_ws/src/dfall_pkg/launch/Agent.launch
index 33b24834..b97eae9a 100755
--- a/dfall_ws/src/dfall_pkg/launch/Agent.launch
+++ b/dfall_ws/src/dfall_pkg/launch/Agent.launch
@@ -110,6 +110,15 @@
 			>
 		</node>
 
+		<!-- TEMPLATE CONTROLLER -->
+		<node
+			pkg    = "dfall_pkg"
+			name   = "TemplateControllerService"
+			output = "screen"
+			type   = "TemplateControllerService"
+			>
+		</node>
+
 		<!-- PARAMETER SERVICE -->
 		<node
 			pkg    = "dfall_pkg"
@@ -149,6 +158,11 @@
 				file    = "$(find dfall_pkg)/param/PickerController.yaml"
 				ns      = "PickerController"
 			/>
+			<rosparam
+				command = "load"
+				file    = "$(find dfall_pkg)/param/TemplateController.yaml"
+				ns      = "TemplateController"
+			/>
 		</node>
 
 
diff --git a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
index d348c138..779d2461 100755
--- a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
@@ -1,10 +1,11 @@
-safeController:    "SafeControllerService/RateController"
-demoController:    "DemoControllerService/DemoController"
-studentController: "StudentControllerService/StudentController"
-mpcController:     "MpcControllerService/MpcController"
-remoteController:  "RemoteControllerService/RemoteController"
-tuningController:  "TuningControllerService/TuningController"
-pickerController:  "PickerControllerService/PickerController"
+safeController:     "SafeControllerService/RateController"
+demoController:     "DemoControllerService/DemoController"
+studentController:  "StudentControllerService/StudentController"
+mpcController:      "MpcControllerService/MpcController"
+remoteController:   "RemoteControllerService/RemoteController"
+tuningController:   "TuningControllerService/TuningController"
+pickerController:   "PickerControllerService/PickerController"
+templateController: "TemplateControllerService/TemplateController"
 
 # Flag for whether to use angle for switching to the Safe Controller
 strictSafety: false
@@ -12,5 +13,4 @@ angleMargin: 0.8
 
 battery_threshold_while_flying: 2.60       # in V
 battery_threshold_while_motors_off: 3.30   # in V
-battery_polling_period: 200                # in ms
-
+battery_polling_period: 200                # in ms
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/TemplateController.yaml b/dfall_ws/src/dfall_pkg/param/TemplateController.yaml
new file mode 100644
index 00000000..b7bbda03
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/param/TemplateController.yaml
@@ -0,0 +1,28 @@
+# Mass of the crazyflie
+mass : 28
+
+# Frequency of the controller, in hertz
+control_frequency : 200
+
+# Quadratic motor regression equation (a0, a1, a2)
+motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
+
+# The min and max for saturating 16 bit thrust commands
+command_sixteenbit_min : 1000
+command_sixteenbit_max : 60000
+
+# The default setpoint, the ordering is (x,y,z,yaw),
+# with unit [meters,meters,meters,radians]
+default_setpoint : [0.0, 0.0, 0.4, 0.0]
+
+# Boolean indiciating whether the "Debug Message" of this agent should be published or not
+shouldPublishDebugMessage : false
+
+# Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
+shouldDisplayDebugInfo : false
+
+# The LQR Controller parameters for rate mode
+gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00]
+gainMatrixRollRate                  :  [ 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00]
+gainMatrixPitchRate                 :  [ 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00]
+gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30]
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 505bdc0c..7f455863 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -975,11 +975,7 @@ int main(int argc, char* argv[])
 	// and the message received is passed as an input argument to the callback function.
 	ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
 
-	// Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-	// to the name space of this node, i.e., "dfall_pkg" as specified by the line:
-	//     "using namespace dfall_pkg;"
-	// in the "DEFINES" section at the top of this file.
-	//ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
 
 	// Print out some information to the user.
 	ROS_INFO("[DEFAULT CONTROLLER] Service ready :-)");
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 159faa7d..e4fab28c 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -307,6 +307,9 @@ void viconCallback(const ViconData& viconData)
                             case PICKER_CONTROLLER:
                                 success = pickerController.call(controllerCall);
                                 break;
+                            case TEMPLATE_CONTROLLER:
+                                success = templateController.call(controllerCall);
+                                break;
                             default:
                                 ROS_ERROR("[FLYING AGENT CLIENT] the current controller was not recognised");
                                 break;
@@ -482,6 +485,11 @@ void commandCallback(const IntWithHeader & msg) {
                 setControllerUsed(PICKER_CONTROLLER);
                 break;
 
+            case CMD_USE_TEMPLATE_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_TEMPLATE_CONTROLLER Command received");
+                setControllerUsed(TEMPLATE_CONTROLLER);
+                break;
+
         	case CMD_CRAZYFLY_TAKE_OFF:
                 ROS_INFO("[FLYING AGENT CLIENT] TAKE_OFF Command received");
                 if(flying_state == STATE_MOTORS_OFF)
@@ -708,6 +716,23 @@ void loadPickerController()
     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded picker controller " << pickerController.getService());
 }
 
+void loadTemplateController()
+{
+    //ros::NodeHandle nodeHandle("~");
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+    std::string templateControllerName;
+    if(!nodeHandle.getParam("templateController", templateControllerName))
+    {
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get template controller name");
+        return;
+    }
+
+    templateController = ros::service::createClient<Controller>(templateControllerName, true);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded template controller " << templateController.getService());
+}
+
 void sendMessageUsingController(int controller)
 {
     // Send a message on the topic for informing the Flying
@@ -744,6 +769,9 @@ void setInstantController(int controller) //for right now, temporal use
         case PICKER_CONTROLLER:
             loadPickerController();
             break;
+        case TEMPLATE_CONTROLLER:
+            loadTemplateController();
+            break;
         default:
             break;
     }
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
index 93f7d6cc..2b980cbf 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
@@ -1641,11 +1641,7 @@ int main(int argc, char* argv[]) {
     // of this service the "calculateControlOutput" function is called.
     ros::ServiceServer service = nodeHandle.advertiseService("RemoteController", calculateControlOutput);
 
-    // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
-    //     "using namespace dfall_pkg;"
-    // in the "DEFINES" section at the top of this file.
-    ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
 
     // Print out some information to the user.
     ROS_INFO("[REMOTE CONTROLLER] Service ready :-)");
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index a974ef3b..e3209a6b 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -342,8 +342,8 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	
 	// PREPARE AND RETURN THE VARIABLE "response"
 
-	/*choosing the Crazyflie onBoard controller type.
-	it can either be Motor, Rate or Angle based */
+	// Choose the controller type use on-board the Crazyflie,
+	// it can be either be Motor, Rate, or Angle based
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
 	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
@@ -685,7 +685,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			default:
 			{
 				// Let the user know that the command was not recognised
-				ROS_INFO_STREAM("[DEMO CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.float_data = " << float_data );
+				ROS_INFO_STREAM("[STUDENT CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.float_data = " << float_data );
 				break;
 			}
 		}
@@ -1039,11 +1039,7 @@ int main(int argc, char* argv[]) {
 	// And now we can instantiate the subscriber:
 	ros::Subscriber customCommandReceivedSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("StudentControllerService/CustomButtonPressed", 1, customCommandReceivedCallback);
 
-    // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
-    //     "using namespace dfall_pkg;"
-    // in the "DEFINES" section at the top of this file.
-    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
+
 
     // Print out some information to the user.
     ROS_INFO("[STUDENT CONTROLLER] Service ready :-)");
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
new file mode 100644
index 00000000..7b96ba94
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
@@ -0,0 +1,994 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    A Template Controller for students build from
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+// INCLUDE THE HEADER
+#include "nodes/TemplateControllerService.h"
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
+//    F      U   U  NN  N  C        T     I   O   O  NN  N
+//    FFF    U   U  N N N  C        T     I   O   O  N N N
+//    F      U   U  N  NN  C        T     I   O   O  N  NN
+//    F       UUU   N   N   CCCC    T    III   OOO   N   N
+//
+//    III M   M PPPP  L     EEEEE M   M EEEEE N   N TTTTT   A   TTTTT III  OOO  N   N
+//     I  MM MM P   P L     E     MM MM E     NN  N   T    A A    T    I  O   O NN  N
+//     I  M M M PPPP  L     EEE   M M M EEE   N N N   T   A   A   T    I  O   O N N N
+//     I  M   M P     L     E     M   M E     N  NN   T   AAAAA   T    I  O   O N  NN
+//    III M   M P     LLLLL EEEEE M   M EEEEE N   N   T   A   A   T   III  OOO  N   N
+//    ----------------------------------------------------------------------------------
+
+
+
+
+
+//    ------------------------------------------------------------------------------
+//     OOO   U   U  TTTTT  EEEEE  RRRR 
+//    O   O  U   U    T    E      R   R
+//    O   O  U   U    T    EEE    RRRR
+//    O   O  U   U    T    E      R  R
+//     OOO    UUU     T    EEEEE  R   R
+//
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L           L       OOO    OOO   PPPP
+//    C      O   O  NN  N    T    R   R  O   O  L           L      O   O  O   O  P   P
+//    C      O   O  N N N    T    RRRR   O   O  L           L      O   O  O   O  PPPP
+//    C      O   O  N  NN    T    R  R   O   O  L           L      O   O  O   O  P
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL       LLLLL   OOO    OOO   P
+//    ----------------------------------------------------------------------------------
+
+// This function is the callback that is linked to the "TemplateController"
+// service that is advertised in the main function. This must have arguments
+// that match the "input-output" behaviour defined in the "Controller.srv"
+// file (located in the "srv" folder)
+//
+// The arument "request" is a structure provided to this service with the
+// following two properties:
+//
+// >> request.ownCrazyflie
+// This property is itself a structure of type "CrazyflieData",  which is
+// defined in the file "CrazyflieData.msg", and has the following properties
+// string crazyflieName
+//     float64 x                         The x position of the Crazyflie [metres]
+//     float64 y                         The y position of the Crazyflie [metres]
+//     float64 z                         The z position of the Crazyflie [metres]
+//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
+//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
+//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
+//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
+//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
+// The values in these properties are directly the measurement taken by the
+// motion capture system of the Crazyflie that is to be controlled by this
+// service.
+//
+// >> request.otherCrazyflies
+// This property is an array of "CrazyflieData" structures, what allows access
+// to the motion capture measurements of other Crazyflies.
+//
+// The argument "response" is a structure that is expected to be filled in by
+// this service by this function, it has only the following property
+//
+// >> response.ControlCommand
+// This property is iteself a structure of type "ControlCommand", which is
+// defined in the file "ControlCommand.msg", and has the following properties:
+//     float32 roll                      The command sent to the Crazyflie for the body frame x-axis
+//     float32 pitch                     The command sent to the Crazyflie for the body frame y-axis
+//     float32 yaw                       The command sent to the Crazyflie for the body frame z-axis
+//     uint16 motorCmd1                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd2                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd3                  The command sent to the Crazyflie for motor 1
+//     uint16 motorCmd4                  The command sent to the Crazyflie for motor 1
+//     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
+// 
+// IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
+// > The allowed values for "onboardControllerType" are in the "Defines"
+//   section in the header file, they are:
+//   - CF_COMMAND_TYPE_MOTORS
+//   - CF_COMMAND_TYPE_RATE
+//   - CF_COMMAND_TYPE_ANGLE
+//
+// > For most common option to use is CF_COMMAND_TYPE_RATE option.
+//
+// > For the CF_COMMAND_TYPE_RATE optoin:
+//   1) 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.
+//   2) the ".motorCmd1" to ".motorCmd4" properties of
+//      "response.ControlCommand" are the baseline motor commands
+//      requested from the Crazyflie, with the adjustment for body rates
+//      being added on top of this in the firmware (i.e., as per the
+//      code of the "distribute_power" found in the firmware).
+//   3) the axis convention for the roll, pitch, and yaw body rates
+//      returned in "response.ControlCommand" should use right-hand
+//      coordinate axes with x-forward and z-upwards (i.e., the positive
+//      z-axis is aligned with the direction of positive thrust). To
+//      assist, the following is an ASCII art of this convention.
+//
+// ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
+//
+//  > This is a top view,
+//  > M1 to M4 stand for Motor 1 to Motor 4,
+//  > "CW"  indicates that the motor rotates Clockwise,
+//  > "CCW" indicates that the motor rotates Counter-Clockwise,
+//  > By right-hand axis convention, the positive z-direction points out
+//    of the screen,
+//  > This being a "top view" means that the direction of positive thrust
+//    produced by the propellers is also out of the screen.
+//
+//        ____                         ____
+//       /    \                       /    \
+//  (CW) | M4 |           x           | M1 | (CCW)
+//       \____/\          ^          /\____/
+//            \ \         |         / /
+//             \ \        |        / /
+//              \ \______ | ______/ /
+//               \        |        /
+//                |       |       |
+//        y <-------------o       |
+//                |               |
+//               / _______________ \
+//              / /               \ \
+//             / /                 \ \
+//        ____/ /                   \ \____
+//       /    \/                     \/    \
+// (CCW) | M3 |                       | M2 | (CW)
+//       \____/                       \____/
+//
+//
+//
+//
+bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
+{
+
+	// This is the "start" of the outer loop controller, add all your control
+	// computation here, or you may find it convienient to create functions
+	// to keep you code cleaner
+
+
+	// Define a local array to fill in with the state error
+	float stateErrorInertial[9];
+
+	// Fill in the (x,y,z) position error
+	stateErrorInertial[0] = request.ownCrazyflie.x - m_setpoint[0];
+	stateErrorInertial[1] = request.ownCrazyflie.y - m_setpoint[1];
+	stateErrorInertial[2] = request.ownCrazyflie.z - m_setpoint[2];
+
+	// Compute an estimate of the velocity
+	// > As simply the derivative between the current and previous position
+	stateErrorInertial[3] = (stateErrorInertial[0] - m_previous_stateErrorInertial[0]) * yaml_control_frequency;
+	stateErrorInertial[4] = (stateErrorInertial[1] - m_previous_stateErrorInertial[1]) * yaml_control_frequency;
+	stateErrorInertial[5] = (stateErrorInertial[2] - m_previous_stateErrorInertial[2]) * yaml_control_frequency;
+
+	// Fill in the roll and pitch angle measurements directly
+	stateErrorInertial[6] = request.ownCrazyflie.roll;
+	stateErrorInertial[7] = request.ownCrazyflie.pitch;
+
+	// Fill in the yaw angle error
+	// > This error should be "unwrapped" to be in the range
+	//   ( -pi , pi )
+	// > First, get the yaw error into a local variable
+	float yawError = request.ownCrazyflie.yaw - m_setpoint[3];
+	// > Second, "unwrap" the yaw error to the interval ( -pi , pi )
+	while(yawError > PI) {yawError -= 2 * PI;}
+	while(yawError < -PI) {yawError += 2 * PI;}
+	// > Third, put the "yawError" into the "stateError" variable
+	stateErrorInertial[8] = yawError;
+
+
+	// CONVERSION INTO BODY FRAME
+	// Conver the state erorr from the Inertial frame into the Body frame
+	// > 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 classroom exercise
+	float stateErrorBody[9];
+	convertIntoBodyFrame(stateErrorInertial, stateErrorBody, request.ownCrazyflie.yaw);
+
+
+	// SAVE THE STATE ERROR TO BE USED NEXT TIME THIS FUNCTION IS CALLED
+	// > as we have already used previous error we can now update it update it
+	for(int i = 0; i < 9; ++i)
+	{
+		m_previous_stateErrorInertial[i] = stateErrorInertial[i];
+	}
+
+
+	
+	// PERFORM THE "u=-Kx" CONTROLLER COMPUTATIONS
+
+	// Instantiate local variables for the responses
+	float thrustAdjustment = 0;
+	float rollRate_forResponse = 0;
+	float pitchRate_forResponse = 0;
+	float yawRate_forResponse = 0;
+
+	// Perform the "-Kx" LQR computation for the yaw rate to respoond with
+	for(int i = 0; i < 9; ++i)
+	{
+		// For the z-controller
+		thrustAdjustment -= yaml_gainMatrixThrust[i] * stateErrorBody[i];
+		// For the x-controller
+		pitchRate_forResponse -= yaml_gainMatrixPitchRate[i] * stateErrorBody[i];
+		// For the y-controller
+		rollRate_forResponse -= yaml_gainMatrixRollRate[i] * stateErrorBody[i];
+		// For the yaw-controller
+		yawRate_forResponse -= yaml_gainMatrixYawRate[i] * stateErrorBody[i];
+	}
+
+	// Put the computed body rate commands into the "response" variable
+	response.controlOutput.roll = rollRate_forResponse;
+	response.controlOutput.pitch = pitchRate_forResponse;
+	response.controlOutput.yaw = yawRate_forResponse;
+
+	// Put the thrust commands into the "response" variable.
+	// The thrust adjustment computed by the controller need to be added to the
+	// the feed-forward thrust that "counter-acts" gravity.
+	// > NOTE: remember that the thrust is commanded per motor, so you sohuld
+	//         consider whether the "thrustAdjustment" computed by your
+	//         controller needed to be divided by 4 or not.
+	// > NOTE: the "m_cf_weight_in_newtons" value is the total thrust required
+	//         as feed-forward. Assuming the the Crazyflie is symmetric, this
+	//         value is divided by four.
+	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
+	float thrust_request_per_motor = thrustAdjustment / 4.0 + feed_forward_thrust_per_motor;
+	// > NOTE: the function "computeMotorPolyBackward" converts the input argument
+	//         from Newtons to the 16-bit command expected by the Crazyflie.
+	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrust_request_per_motor);
+	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrust_request_per_motor);
+	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrust_request_per_motor);
+	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrust_request_per_motor);
+
+	
+	// PREPARE AND RETURN THE VARIABLE "response"
+
+	// Choose the controller type use on-board the Crazyflie,
+	// it can be either be Motor, Rate, or Angle based
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
+
+
+
+
+	if (yaml_shouldPublishDebugMessage)
+	{
+		//  ***********************************************************
+		//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
+		//  D   D  E      B   B  U   U  G           MM MM  S      G
+		//  D   D  EEE    BBBB   U   U  G           M M M   SSS   G
+		//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
+		//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
+
+		// DEBUGGING CODE:
+		// As part of the D-FaLL-System we have defined a message type names"DebugMsg".
+		// By fill this message with data and publishing it you can display the data in
+		// real time using rpt plots. Instructions for using rqt plots can be found on
+		// the wiki of the D-FaLL-System repository
+
+		// Instantiate a local variable of type "DebugMsg", see the file "DebugMsg.msg"
+		// (located in the "msg" folder) to see the full structure of this message.
+		DebugMsg debugMsg;
+
+		// Fill the debugging message with the data provided by Vicon
+		debugMsg.vicon_x = request.ownCrazyflie.x;
+		debugMsg.vicon_y = request.ownCrazyflie.y;
+		debugMsg.vicon_z = request.ownCrazyflie.z;
+		debugMsg.vicon_roll = request.ownCrazyflie.roll;
+		debugMsg.vicon_pitch = request.ownCrazyflie.pitch;
+		debugMsg.vicon_yaw = request.ownCrazyflie.yaw;
+
+		// Fill in the debugging message with any other data you would like to display
+		// in real time. For example, it might be useful to display the thrust
+		// adjustment computed by the z-altitude controller.
+		// The "DebugMsg" type has 10 properties from "value_1" to "value_10", all of
+		// type "float64" that you can fill in with data you would like to plot in
+		// real-time.
+		// debugMsg.value_1 = thrustAdjustment;
+		// ......................
+		// debugMsg.value_10 = your_variable_name;
+
+		// Publish the "debugMsg"
+		m_debugPublisher.publish(debugMsg);
+	}
+
+
+	if (yaml_shouldDisplayDebuginfo)
+	{
+		//  ***********************************************************
+		//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
+		//  D   D  E      B   B  U   U  G           MM MM  S      G
+		//  D   D  EEE    BBBB   U   U  G           M M M   SSS   G
+		//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
+		//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
+		// An alternate debugging technique is to print out data directly to the
+		// command line from which this node was launched.
+
+		// An example of "printing out" the data from the "request" argument to the
+		// command line. This might be useful for debugging.
+		ROS_INFO_STREAM("x-coordinates: " << request.ownCrazyflie.x);
+		ROS_INFO_STREAM("y-coordinates: " << request.ownCrazyflie.y);
+		ROS_INFO_STREAM("z-coordinates: " << request.ownCrazyflie.z);
+		ROS_INFO_STREAM("roll: " << request.ownCrazyflie.roll);
+		ROS_INFO_STREAM("pitch: " << request.ownCrazyflie.pitch);
+		ROS_INFO_STREAM("yaw: " << request.ownCrazyflie.yaw);
+		ROS_INFO_STREAM("Delta t: " << request.ownCrazyflie.acquiringTime);
+
+		// An example of "printing out" the control actions computed.
+		ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
+		ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
+		ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
+		ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
+
+		// An example of "printing out" the per motor 16-bit command computed.
+		ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
+		ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
+		ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
+		ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
+
+		// An example of "printing out" the "thrust-to-command" conversion parameters.
+		// ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
+		// ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
+		// ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
+	}
+
+	// Return "true" to indicate that the control computation was
+	// performed successfully
+	return true;
+}
+
+
+
+
+//    ------------------------------------------------------------------------------
+//    RRRR    OOO   TTTTT    A    TTTTT  EEEEE       III  N   N  TTTTT   OOO
+//    R   R  O   O    T     A A     T    E            I   NN  N    T    O   O
+//    RRRR   O   O    T    A   A    T    EEE          I   N N N    T    O   O
+//    R  R   O   O    T    AAAAA    T    E            I   N  NN    T    O   O
+//    R   R   OOO     T    A   A    T    EEEEE       III  N   N    T     OOO
+//
+//    BBBB    OOO   DDDD   Y   Y       FFFFF  RRRR     A    M   M  EEEEE
+//    B   B  O   O  D   D   Y Y        F      R   R   A A   MM MM  E
+//    BBBB   O   O  D   D    Y         FFF    RRRR   A   A  M M M  EEE
+//    B   B  O   O  D   D    Y         F      R  R   AAAAA  M   M  E
+//    BBBB    OOO   DDDD     Y         F      R   R  A   A  M   M  EEEEE
+//    ----------------------------------------------------------------------------------
+
+// The arguments for this function are as follows:
+// stateInertial
+// This is an array of length 9 with the estimates the error of of the following values
+// relative to the sepcifed setpoint:
+//     stateInertial[0]    x position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[1]    y position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[2]    z position of the Crazyflie relative to the inertial frame origin [meters]
+//     stateInertial[3]    x-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[4]    y-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[5]    z-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
+//     stateInertial[6]    The roll  component of the intrinsic Euler angles [radians]
+//     stateInertial[7]    The pitch component of the intrinsic Euler angles [radians]
+//     stateInertial[8]    The yaw   component of the intrinsic Euler angles [radians]
+// 
+// stateBody
+// This is an empty array of length 9, this function should fill in all elements of this
+// array with the same ordering as for the "stateInertial" argument, expect that the (x,y)
+// position and (x,y) velocities are rotated into the body frame.
+//
+// yaw_measured
+// This is the yaw component of the intrinsic Euler angles in [radians] as measured by
+// the Vicon motion capture system
+//
+void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
+{
+	float sinYaw = sin(yaw_measured);
+	float cosYaw = cos(yaw_measured);
+
+	// Fill in the (x,y,z) position estimates to be returned
+	stateBody[0] = stateInertial[0] * cosYaw  +  stateInertial[1] * sinYaw;
+	stateBody[1] = stateInertial[1] * cosYaw  -  stateInertial[0] * sinYaw;
+	stateBody[2] = stateInertial[2];
+
+	// Fill in the (x,y,z) velocity estimates to be returned
+	stateBody[3] = stateInertial[3] * cosYaw  +  stateInertial[4] * sinYaw;
+	stateBody[4] = stateInertial[4] * cosYaw  -  stateInertial[3] * sinYaw;
+	stateBody[5] = stateInertial[5];
+
+	// Fill in the (roll,pitch,yaw) estimates to be returned
+	stateBody[6] = stateInertial[6];
+	stateBody[7] = stateInertial[7];
+	stateBody[8] = stateInertial[8];
+}
+
+
+
+
+
+//    ------------------------------------------------------------------------------
+//    N   N  EEEEE  W     W   TTTTT   OOO   N   N        CCCC  M   M  DDDD
+//    NN  N  E      W     W     T    O   O  NN  N       C      MM MM  D   D
+//    N N N  EEE    W     W     T    O   O  N N N  -->  C      M M M  D   D
+//    N  NN  E       W W W      T    O   O  N  NN       C      M   M  D   D
+//    N   N  EEEEE    W W       T     OOO   N   N        CCCC  M   M  DDDD
+//
+//     CCCC   OOO   N   N  V   V  EEEEE  RRRR    SSSS  III   OOO   N   N
+//    C      O   O  NN  N  V   V  E      R   R  S       I   O   O  NN  N
+//    C      O   O  N N N  V   V  EEE    RRRR    SSS    I   O   O  N N N
+//    C      O   O  N  NN   V V   E      R  R       S   I   O   O  N  NN
+//     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
+//    ----------------------------------------------------------------------------------
+
+float computeMotorPolyBackward(float thrust)
+{
+	// Compute the 16-but command that would produce the requested
+	// "thrust" based on the quadratic mapping that is described
+	// by the coefficients in the "yaml_motorPoly" variable.
+	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
+
+	// Saturate the signal to be 0 or in the range [1000,65000]
+	if (cmd_16bit < yaml_cmd_sixteenbit_min)
+	{
+		cmd_16bit = 0;
+	}
+	else if (cmd > yaml_cmd_sixteenbit_max)
+	{
+		cmd_16bit = yaml_cmd_sixteenbit_max;
+	}
+	// Return the result
+	return cmd_16bit;
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    N   N  EEEEE  W     W        SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    NN  N  E      W     W       S      E        T    P   P  O   O   I   NN  N    T
+//    N N N  EEE    W     W        SSS   EEE      T    PPPP   O   O   I   N N N    T
+//    N  NN  E       W W W            S  E        T    P      O   O   I   N  NN    T
+//    N   N  EEEEE    W W         SSSS   EEEEE    T    P       OOO   III  N   N    T
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//    ----------------------------------------------------------------------------------
+
+
+// REQUEST SETPOINT CHANGE CALLBACK
+void requestSetpointChangeCallback(const SetpointWithHeader& newSetpoint)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , newSetpoint.shouldCheckForAgentID , newSetpoint.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Check if the request if for the default setpoint
+		if (newSetpoint.buttonID == REQUEST_DEFAULT_SETPOINT_BUTTON_ID)
+		{
+			setNewSetpoint(
+					yaml_default_setpoint[0],
+					yaml_default_setpoint[1],
+					yaml_default_setpoint[2],
+					yaml_default_setpoint[3]
+				);
+		}
+		else
+		{
+			// Call the function for actually setting the setpoint
+			setNewSetpoint(
+					newSetpoint.x,
+					newSetpoint.y,
+					newSetpoint.z,
+					newSetpoint.yaw
+				);
+		}
+	}
+}
+
+
+// CHANGE SETPOINT FUNCTION
+void setNewSetpoint(float x, float y, float z, float yaw)
+{
+	// Put the new setpoint into the class variable
+	m_setpoint[0] = x;
+	m_setpoint[1] = y;
+	m_setpoint[2] = z;
+	m_setpoint[3] = yaw;
+
+	// Publish the change so that the network is updated
+	// (mainly the "flying agent GUI" is interested in
+	// displaying this change to the user)
+
+	// Instantiate a local variable of type "SetpointWithHeader"
+	SetpointWithHeader msg;
+	// Fill in the setpoint
+	msg.x   = x;
+	msg.y   = y;
+	msg.z   = z;
+	msg.yaw = yaw;
+	// Publish the message
+	m_setpointChangedPublisher.publish(msg);
+}
+
+
+// GET CURRENT SETPOINT SERVICE CALLBACK
+bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response)
+{
+	// Directly put the current setpoint into the response
+	response.setpointWithHeader.x   = m_setpoint[0];
+	response.setpointWithHeader.y   = m_setpoint[1];
+	response.setpointWithHeader.z   = m_setpoint[2];
+	response.setpointWithHeader.yaw = m_setpoint[3];
+	// Return
+	return true;
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     CCCC  U   U   SSSS  TTTTT   OOO   M   M
+//    C      U   U  S        T    O   O  MM MM
+//    C      U   U   SSS     T    O   O  M M M
+//    C      U   U      S    T    O   O  M   M
+//     CCCC   UUU   SSSS     T     OOO   M   M
+//
+//     CCCC   OOO   M   M  M   M    A    N   N  DDDD
+//    C      O   O  MM MM  MM MM   A A   NN  N  D   D
+//    C      O   O  M M M  M M M  A   A  N N N  D   D
+//    C      O   O  M   M  M   M  AAAAA  N  NN  D   D
+//     CCCC   OOO   M   M  M   M  A   A  N   N  DDDD
+//    ----------------------------------------------------------------------------------
+
+// CUSTOM COMMAND RECEIVED CALLBACK
+void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , commandReceived.shouldCheckForAgentID , commandReceived.agentIDs );
+
+	if (isRevelant)
+	{
+		// Extract the data from the message
+		int custom_button_index = commandReceived.button_index;
+		float float_data        = commandReceived.float_data;
+		//std::string string_data = commandReceived.string_data;
+
+		// Switch between the button pressed
+		switch(custom_button_index)
+		{
+
+			// > FOR CUSTOM BUTTON 1
+			case 1:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO_STREAM("[TEMPLATE CONTROLLER] Button 1 received in controller, with message.float_data = " << float_data );
+				// Code here to respond to custom button 1
+				
+				break;
+			}
+
+			// > FOR CUSTOM BUTTON 2
+			case 2:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO_STREAM("[TEMPLATE CONTROLLER] Button 2 received in controller, with message.float_data = " << float_data );
+				// Code here to respond to custom button 2
+
+				break;
+			}
+
+			// > FOR CUSTOM BUTTON 3
+			case 3:
+			{
+				// Let the user know that this part of the code was triggered
+				ROS_INFO_STREAM("[TEMPLATE CONTROLLER] Button 3 received in controller, with message.float_data = " << float_data );
+				// Code here to respond to custom button 3
+
+				break;
+			}
+
+			default:
+			{
+				// Let the user know that the command was not recognised
+				ROS_INFO_STREAM("[TEMPLATE CONTROLLER] A button clicked command was received in the controller but not recognised, message.button_index = " << custom_button_index << ", and message.float_data = " << float_data );
+				break;
+			}
+		}
+	}
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//    PPPP     A    RRRR     A    M   M  EEEEE  TTTTT  EEEEE  RRRR    SSSS
+//    P   P   A A   R   R   A A   MM MM  E        T    E      R   R  S
+//    PPPP   A   A  RRRR   A   A  M M M  EEE      T    EEE    RRRR    SSS
+//    P      AAAAA  R  R   AAAAA  M   M  E        T    E      R  R       S
+//    P      A   A  R   R  A   A  M   M  EEEEE    T    EEEEE  R   R  SSSS
+//    ----------------------------------------------------------------------------------
+
+
+// CALLBACK NOTIFYING THAT THE YAML PARAMETERS ARE READY TO BE LOADED
+void isReadyTemplateControllerYamlCallback(const IntWithHeader & msg)
+{
+	// Check whether the message is relevant
+	bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
+
+	// Continue if the message is relevant
+	if (isRevelant)
+	{
+		// Extract the data
+		int parameter_service_to_load_from = msg.data;
+		// Initialise a local variable for the namespace
+		std::string namespace_to_use;
+		// Load from the respective parameter service
+		switch(parameter_service_to_load_from)
+		{
+			// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+			case LOAD_YAML_FROM_AGENT:
+			{
+				ROS_INFO("[TEMPLATE CONTROLLER] Now fetching the TemplateController 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("[TEMPLATE CONTROLLER] Now fetching the TemplateController YAML parameter values from this agent's coordinator.");
+				namespace_to_use = m_namespace_to_coordinator_parameter_service;
+				break;
+			}
+
+			default:
+			{
+				ROS_ERROR("[TEMPLATE CONTROLLER] Paramter service to load from was NOT recognised.");
+				namespace_to_use = m_namespace_to_own_agent_parameter_service;
+				break;
+			}
+		}
+		// Create a node handle to the selected parameter service
+		ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+		// Call the function that fetches the parameters
+		fetchTemplateControllerYamlParameters(nodeHandle_to_use);
+	}
+}
+
+
+// LOADING OF THE YAML PARAMTERS
+void fetchTemplateControllerYamlParameters(ros::NodeHandle& nodeHandle)
+{
+	// Here we load the parameters that are specified in the file:
+	// TemplateController.yaml
+
+	// Add the "TemplateController" namespace to the "nodeHandle"
+	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "TemplateController");
+
+
+
+	// GET THE PARAMETERS:
+
+	// > The mass of the crazyflie
+	yaml_cf_mass_in_grams = getParameterFloat(nodeHandle_for_paramaters , "mass");
+
+	// > The frequency at which the "computeControlOutput" is being called,
+	//   as determined by the frequency at which the motion capture system
+	//   provides position and attitude data
+	yaml_control_frequency = getParameterFloat(nodeHandle_for_paramaters, "control_frequency");
+
+	// > The co-efficients of the quadratic conversation from 16-bit motor
+	//   command to thrust force in Newtons
+	getParameterFloatVector(nodeHandle_for_paramaters, "motorPoly", yaml_motorPoly, 3);
+
+	// > The min and max for saturating 16 bit thrust commands
+	yaml_command_sixteenbit_min = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_min");
+	yaml_command_sixteenbit_max = getParameterFloat(nodeHandle_for_paramaters, "command_sixteenbit_max");
+
+	// The default setpoint, the ordering is (x,y,z,yaw),
+	// with unit [meters,meters,meters,radians]
+	getParameterFloatVector(nodeHandle_for_paramaters, "default_setpoint", yaml_default_setpoint, 4);
+
+	// Boolean indiciating whether the "Debug Message" of this agent
+	// should be published or not
+	yaml_shouldPublishDebugMessage = getParameterBool(nodeHandle_for_paramaters, "shouldPublishDebugMessage");
+
+	// Boolean indiciating whether the debugging ROS_INFO_STREAM should
+	// be displayed or not
+	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paramaters, "shouldDisplayDebugInfo");
+
+	// The LQR Controller parameters
+	// The LQR Controller parameters for "LQR_MODE_RATE"
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
+
+	// > DEBUGGING: Print out one of the parameters that was loaded to
+	//   debug if the fetching of parameters worked correctly
+	ROS_INFO_STREAM("[TEMPLATE CONTROLLER] DEBUGGING: the fetched TemplateController/mass = " << yaml_cf_mass_in_grams);
+
+
+
+	// PROCESS THE PARAMTERS
+
+	// > Compute the feed-forward force that we need to counteract
+	//   gravity (i.e., mg) in units of [Newtons]
+	m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81/1000.0;
+
+	// DEBUGGING: Print out one of the computed quantities
+	ROS_INFO_STREAM("[TEMPLATE CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << m_cf_weight_in_newtons);
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    M   M    A    III  N   N
+//    MM MM   A A    I   NN  N
+//    M M M  A   A   I   N N N
+//    M   M  AAAAA   I   N  NN
+//    M   M  A   A  III  N   N
+//    ----------------------------------------------------------------------------------
+
+
+// This function does NOT need to be edited 
+int main(int argc, char* argv[]) {
+
+	// Starting the ROS-node
+	ros::init(argc, argv, "TemplateControllerService");
+
+	// 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 "TemplateControllerService" node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[TEMPLATE CONTROLLER] ros::this_node::getNamespace() =  " << m_namespace);
+
+
+
+	// 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 + "/FlyingAgentClient" , &m_agentID , &m_coordID);
+
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[TEMPLATE CONTROLLER] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[TEMPLATE CONTROLLER] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+	}
+
+
+
+	// 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";
+
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+
+	// Inform the user of what namespaces are being used
+	ROS_INFO_STREAM("[TEMPLATE CONTROLLER] m_namespace_to_own_agent_parameter_service    =  " << m_namespace_to_own_agent_parameter_service);
+	ROS_INFO_STREAM("[TEMPLATE CONTROLLER] 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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+
+
+
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
+
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber safeContoller_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "TemplateController", 1, isReadyTemplateControllerYamlCallback);
+	ros::Subscriber safeContoller_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("TemplateController", 1, isReadyTemplateControllerYamlCallback);
+
+
+
+	// GIVE YAML VARIABLES AN INITIAL VALUE
+	// This can be done either here or as part of declaring the
+	// variables in the header file
+
+
+
+
+	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
+
+	// The yaml files for the controllers are not added to
+	// "Parameter Service" as part of launching.
+	// The process for loading the yaml parameters is to send a
+	// service call containing the filename of the *.yaml file,
+	// and then a message will be received on the above subscribers
+	// when the paramters are ready.
+	// > NOTE IMPORTANTLY that by using a serice client
+	//   we stall the availability of this node until the
+	//   paramter service is ready
+
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "TemplateController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyTemplateControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+		// Inform the user
+		ROS_ERROR("[TEMPLATE CONTROLLER] The request load yaml file service call failed.");
+	}
+
+
+
+
+    // PUBLISHERS AND SUBSCRIBERS
+
+    // Instantiate the class variable "m_debugPublisher" to be a
+    // "ros::Publisher". This variable advertises under the name
+    // "DebugTopic" and is a message with the structure defined
+    //  in the file "DebugMsg.msg" (located in the "msg" folder).
+    m_debugPublisher = nodeHandle.advertise<DebugMsg>("DebugTopic", 1);
+
+	// Instantiate the local variable "requestSetpointChangeSubscriber"
+	// to be a "ros::Subscriber" type variable that subscribes to the
+	// "RequestSetpointChange" topic and calls the class function
+	// "requestSetpointChangeCallback" each time a messaged is received
+	// on this topic and the message is passed as an input argument to
+	// the callback function. This subscriber will mainly receive
+	// messages from the "flying agent GUI" when the setpoint is changed
+	// by the user.
+	ros::Subscriber requestSetpointChangeSubscriber = nodeHandle.subscribe("RequestSetpointChange", 1, requestSetpointChangeCallback);
+
+	// Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber requestSetpointChangeSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("TemplateControllerService/RequestSetpointChange", 1, requestSetpointChangeCallback);
+
+	// Instantiate the class variable "m_setpointChangedPublisher" to
+	// be a "ros::Publisher". This variable advertises under the name
+	// "SetpointChanged" and is a message with the structure defined
+	// in the file "SetpointWithHeader.msg" (located in the "msg" folder).
+	// This publisher is used by the "flying agent GUI" to update the
+	// field that displays the current setpoint for this controller.
+	m_setpointChangedPublisher = nodeHandle.advertise<SetpointWithHeader>("SetpointChanged", 1);
+
+	// Instantiate the local variable "getCurrentSetpointService" to be
+	// a "ros::ServiceServer" type variable that advertises the service
+	// called "GetCurrentSetpoint". This service has the input-output
+	// behaviour defined in the "GetSetpointService.srv" file (located
+	// in the "srv" folder). This service, when called, is provided with
+	// an integer (that is essentially ignored), and is expected to respond
+	// with the current setpoint of the controller. When a request is made
+	// of this service the "getCurrentSetpointCallback" function is called.
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);
+
+
+
+    // Instantiate the local variable "service" to be a "ros::ServiceServer" type
+    // variable that advertises the service called "TemplateController". This service has
+    // the input-output behaviour defined in the "Controller.srv" file (located in the
+    // "srv" folder). This service, when called, is provided with the most recent
+    // measurement of the Crazyflie and is expected to respond with the control action
+    // that should be sent via the Crazyradio and requested from the Crazyflie, i.e.,
+    // this is where the "outer loop" controller function starts. When a request is made
+    // of this service the "calculateControlOutput" function is called.
+    ros::ServiceServer service = nodeHandle.advertiseService("TemplateController", calculateControlOutput);
+
+    // Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
+    // type variable that subscribes to the "GUIButton" topic and calls the class
+    // function "customCommandReceivedCallback" each time a messaged is received on this topic
+    // and the message received is passed as an input argument to the callback function.
+    ros::Subscriber customCommandReceivedSubscriber = nodeHandle.subscribe("CustomButtonPressed", 1, customCommandReceivedCallback);
+
+    // Same again but instead for changes requested by the coordinator.
+	// For this we need to first create a node handle to the coordinator:
+	//std::string namespace_to_coordinator;
+	//constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	//ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
+	// And now we can instantiate the subscriber:
+	ros::Subscriber customCommandReceivedSubscriber_from_coord = nodeHandle_to_coordinator.subscribe("TemplateControllerService/CustomButtonPressed", 1, customCommandReceivedCallback);
+
+
+
+    // Print out some information to the user.
+    ROS_INFO("[TEMPLATE CONTROLLER] Service ready :-)");
+
+    // Enter an endless while loop to keep the node alive.
+    ros::spin();
+
+    // Return zero if the "ross::spin" is cancelled.
+    return 0;
+}
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
index 8da3969f..072c0be3 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp
@@ -1774,14 +1774,6 @@ int main(int argc, char* argv[]) {
 
 
 
-    // Create a "ros::NodeHandle" type local variable "namespace_nodeHandle" that points
-    // to the name space of this node, i.e., "dfall_pkg" as specified by the line:
-    //     "using namespace dfall_pkg;"
-    // in the "DEFINES" section at the top of this file.
-    //ros::NodeHandle namespace_nodeHandle(ros::this_node::getNamespace());
-
-
-
     // Print out some information to the user.
     ROS_INFO("[TUNING CONTROLLER] Service ready :-)");
 
-- 
GitLab


From bb968445d227922beb14d139e432dc795c9989c4 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 13:07:55 +0100
Subject: [PATCH 70/87] Fixed small errors with Template Controller so that it
 compiles

---
 .../dfall_pkg/src/nodes/TemplateControllerService.cpp  | 10 +++++-----
 1 file changed, 5 insertions(+), 5 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
index 7b96ba94..71ecce97 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/TemplateControllerService.cpp
@@ -243,7 +243,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	for(int i = 0; i < 9; ++i)
 	{
 		// For the z-controller
-		thrustAdjustment -= yaml_gainMatrixThrust[i] * stateErrorBody[i];
+		thrustAdjustment -= yaml_gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
 		// For the x-controller
 		pitchRate_forResponse -= yaml_gainMatrixPitchRate[i] * stateErrorBody[i];
 		// For the y-controller
@@ -329,7 +329,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	}
 
 
-	if (yaml_shouldDisplayDebuginfo)
+	if (yaml_shouldDisplayDebugInfo)
 	{
 		//  ***********************************************************
 		//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
@@ -460,13 +460,13 @@ float computeMotorPolyBackward(float thrust)
 	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
 
 	// Saturate the signal to be 0 or in the range [1000,65000]
-	if (cmd_16bit < yaml_cmd_sixteenbit_min)
+	if (cmd_16bit < yaml_command_sixteenbit_min)
 	{
 		cmd_16bit = 0;
 	}
-	else if (cmd > yaml_cmd_sixteenbit_max)
+	else if (cmd_16bit > yaml_command_sixteenbit_max)
 	{
-		cmd_16bit = yaml_cmd_sixteenbit_max;
+		cmd_16bit = yaml_command_sixteenbit_max;
 	}
 	// Return the result
 	return cmd_16bit;
-- 
GitLab


From aae13fef3cbf2601893fb81299e39189ae26c01f Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 13:24:09 +0100
Subject: [PATCH 71/87] Fix to C make list for the naming of the flying agent
 and system config GUIS (the first letter needed to be captialised)

---
 dfall_ws/src/dfall_pkg/CMakeLists.txt | 26 +++++++++++++-------------
 1 file changed, 13 insertions(+), 13 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/CMakeLists.txt b/dfall_ws/src/dfall_pkg/CMakeLists.txt
index 5c26fb13..094f23d6 100755
--- a/dfall_ws/src/dfall_pkg/CMakeLists.txt
+++ b/dfall_ws/src/dfall_pkg/CMakeLists.txt
@@ -268,8 +268,8 @@ generate_messages(
 ## CATKIN_DEPENDS: catkin_packages dependent projects also need
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
-  INCLUDE_DIRS include ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}            # GUI -- include headers from GUI in package
-  INCLUDE_DIRS include ${FLYING_AGENT_GUI_LIB_PATH_INC}  # FlyingAgentGUI -- include headers from GUI in package
+  INCLUDE_DIRS include ${SYSTEM_CONFIG_GUI_LIB_PATH_INC}   # SystemConfigGUI -- include headers from GUI in package
+  INCLUDE_DIRS include ${FLYING_AGENT_GUI_LIB_PATH_INC}    # FlyingAgentGUI  -- include headers from GUI in package
   LIBRARIES
   CATKIN_DEPENDS roscpp rospy std_msgs rosbag roslib
   DEPENDS
@@ -377,14 +377,14 @@ set(FLYING_AGENT_GUI_CPP_SOURCES         # compilation of sources
 
 
 # GUI -- Add executables here
-add_executable(systemConfigGUI ${SYSTEM_CONFIG_GUI_CPP_SOURCES} ${UIS_HDRS_GUI} ${SRC_MOC_HDRS_GUI} ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC})
-qt5_use_modules(systemConfigGUI Widgets)
+add_executable(SystemConfigGUI ${SYSTEM_CONFIG_GUI_CPP_SOURCES} ${UIS_HDRS_GUI} ${SRC_MOC_HDRS_GUI} ${SYSTEM_CONFIG_GUI_RESOURCE_FILE_RRC})
+qt5_use_modules(SystemConfigGUI Widgets)
 
 
 
 # FLYING AGENT GUI -- Add executables here
-add_executable(flyingAgentGUI ${FLYING_AGENT_GUI_CPP_SOURCES} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
-qt5_use_modules(flyingAgentGUI Widgets)
+add_executable(FlyingAgentGUI ${FLYING_AGENT_GUI_CPP_SOURCES} ${UIS_HDRS_FLYING_AGENT_GUI} ${SRC_MOC_HDRS_FLYING_AGENT_GUI} ${FLYING_AGENT_GUI_RESOURCE_FILE_RCC})
+qt5_use_modules(FlyingAgentGUI Widgets)
 
 
 
@@ -409,12 +409,12 @@ add_dependencies(ParameterService          dfall_pkg_generate_messages_cpp ${cat
 
 
 # GUI-- dependencies
-add_dependencies(systemConfigGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(SystemConfigGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
 # FLYING AGENT GUI-- dependencies
-add_dependencies(flyingAgentGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+add_dependencies(FlyingAgentGUI dfall_pkg_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
 
 
 
@@ -461,15 +461,15 @@ target_link_libraries(ParameterService          ${catkin_LIBRARIES})
 
 
 # GUI -- link libraries
-target_link_libraries(systemConfigGUI Qt5::Widgets) # GUI -- let systemConfigGUI have acesss to Qt stuff
-target_link_libraries(systemConfigGUI Qt5::Svg)
-target_link_libraries(systemConfigGUI ${catkin_LIBRARIES})
+target_link_libraries(SystemConfigGUI Qt5::Widgets) # GUI -- let SystemConfigGUI have acesss to Qt stuff
+target_link_libraries(SystemConfigGUI Qt5::Svg)
+target_link_libraries(SystemConfigGUI ${catkin_LIBRARIES})
 
 
 
 # Flying Agent GUI -- link libraries
-target_link_libraries(flyingAgentGUI Qt5::Widgets) # GUI -- let flyingAgentGUI have acesss to Qt stuff
-target_link_libraries(flyingAgentGUI ${catkin_LIBRARIES})
+target_link_libraries(FlyingAgentGUI Qt5::Widgets) # GUI -- let FlyingAgentGUI have acesss to Qt stuff
+target_link_libraries(FlyingAgentGUI ${catkin_LIBRARIES})
 
 
 
-- 
GitLab


From ecd67e217c26b153444fef4a298a501d00137d08 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 13:43:41 +0100
Subject: [PATCH 72/87] Updated wiki and install folders for the change from
 pps_ws to dfall_ws, and from d_fall_pps to dfall_pkg

---
 install/{pps_install.sh => dfall_install.sh} | 14 ++++-----
 wiki/faq.md                                  | 18 ++++++------
 wiki/installation.md                         | 14 ++++-----
 wiki/namespace_conventions.md                |  2 +-
 wiki/setup.md                                |  2 +-
 wiki/workflow_for_students.md                | 30 ++++++++++----------
 6 files changed, 40 insertions(+), 40 deletions(-)
 rename install/{pps_install.sh => dfall_install.sh} (79%)

diff --git a/install/pps_install.sh b/install/dfall_install.sh
similarity index 79%
rename from install/pps_install.sh
rename to install/dfall_install.sh
index 233bd387..daba24ee 100755
--- a/install/pps_install.sh
+++ b/install/dfall_install.sh
@@ -24,8 +24,8 @@ rosdep update
 
 #untar catkin workspace
 #needs to run after ros installation because of symbolic link to CMakeLists.txt
-mkdir -p ~/pps_ws/src
-tar -xf package.tar.gz -C ~/pps_ws/src
+mkdir -p ~/dfall_ws/src
+tar -xf package.tar.gz -C ~/dfall_ws/src
 
 #environment setup
 echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
@@ -39,10 +39,10 @@ sudo cp ./99-crazyflie.rules /etc/udev/rules.d
 sudo cp ./99-crazyradio.rules /etc/udev/rules.d
 
 #build workspace
-cd ~/pps_ws
+cd ~/dfall_ws
 catkin_make -j4
 
-echo "source ~/pps_ws/devel/setup.bash" >> ~/.bashrc
-source ~/pps_ws/devel/setup.bash
-echo "source ~/pps_ws/src/d_fall_pps/launch/Config.sh" >> ~/.bashrc
-source ~/pps_ws/src/d_fall_pps/launch/Config.sh
+echo "source ~/dfall_ws/devel/setup.bash" >> ~/.bashrc
+source ~/dfall_ws/devel/setup.bash
+echo "source ~/dfall_ws/src/dfall_pkg/launch/Config.sh" >> ~/.bashrc
+source ~/dfall_ws/src/dfall_pkg/launch/Config.sh
diff --git a/wiki/faq.md b/wiki/faq.md
index 56da5fbf..04e4c9ba 100644
--- a/wiki/faq.md
+++ b/wiki/faq.md
@@ -35,9 +35,9 @@ git pull
 
 The ``Student GUI`` can be launched from a terminal window with the following command:
 ```
-roslaunch d_fall_pps Student.launch
+roslaunch dfall_pkg Student.launch
 ```
-This can be run from any directory because ``d_fall_pps`` is defined as an environment variable that points to the absolute foler location ``~/work/D-FaLL-System/pps_ws/src/d_fall_pps/launch/``
+This can be run from any directory because ``dfall_pkg`` is defined as an environment variable that points to the absolute foler location ``~/work/D-FaLL-System/dfall_ws/src/dfall_pkg/launch/``
 
 
 ### How do I make changes to a ``*.cpp`` file take effect?
@@ -45,9 +45,9 @@ In essence you need to re-compile the code and re-launch all ROS nodes.
 
 <b>Step 1)</b> Kill all ROS processes that are running nodes from the ``D-FaLL-System`` repository, i.e., you must kill the ``Student GUI`` node but you do not need to kill an ``rqt`` plotting node. To kill a process press ``Ctrl+c`` from the terminal window that is running the process.
 
-<b>Step 2)</b> In a terminal window, change to the ``pps_ws`` folder of the repository (where ``ws`` stands for workspace. On a machine setup as per the instructions this is:
+<b>Step 2)</b> In a terminal window, change to the ``dfall_ws`` folder of the repository (where ``ws`` stands for workspace. On a machine setup as per the instructions this is:
 ```
-cd ~work/D-FaLL-System/pps_ws/
+cd ~work/D-FaLL-System/dfall_ws/
 ``` 
 <b>Step 3)</b> Compile the repository, which includes your changes, using the command:
 ```
@@ -79,7 +79,7 @@ This can happen for a variety of reasons, and generally relates to the local com
 
 To understand how Step 5) could actually fix the problem, consider that ``~/.bashrc`` is run when a new terminal window is opened, and as part of installing the ``D-FaLL-System`` the following line is added to the  ``.bashrc``:
 ``
-source <catkin workspace>/src/d_fall_pps/launch/Config.sh
+source <catkin workspace>/src/dfall_pkg/launch/Config.sh
 ``
 And if you look at the ``Config.sh`` file in the repository you see that it defines environment variable relating to the ``ROS_MASTER_URI``, ``ROS_IP``, and ``ROS_NAMESPACE``. On occassion these are not properly defined on start up or are changed, hence closing and re-launching Terminal can resolve the problem.
 
@@ -91,9 +91,9 @@ The Vicon motion capture system provides position and attitude information via a
 To check whether the Vicon Datastream software is properly added to the local computer, goto the [Installation](installation.md) wiki page and follow the instructions under the title "Vicon Datastream SDK Installation".
 
 The main requirements are that:
-- The ``DataStreamClient.h`` header file needs to be located in ``~/pps_ws/src/d_fall_pps/lib/vicon/``,
-- The ``libViconDataStreamSDK_CPP.so`` shared object needs to be located in ``~/pps_ws/src/d_fall_pps/lib/vicon/``, and
-- A number of files of the form ``libboost_*`` should also be located in ``~/pps_ws/src/d_fall_pps/lib/vicon/``.
+- The ``DataStreamClient.h`` header file needs to be located in ``~/dfall_ws/src/dfall_pkg/lib/vicon/``,
+- The ``libViconDataStreamSDK_CPP.so`` shared object needs to be located in ``~/dfall_ws/src/dfall_pkg/lib/vicon/``, and
+- A number of files of the form ``libboost_*`` should also be located in ``~/dfall_ws/src/dfall_pkg/lib/vicon/``.
 
 
 
@@ -131,7 +131,7 @@ my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("/<ID>/my_current_
 ```
 where ``<ID>`` should be replaced by the ID of your computer, for example the number 7, ``my_current_xyz_yaw_topic`` is the name of the message topic that will be published, and ``Setpoint`` specifies the stucture of the message as defined in the file ``/msg/Setpoint.msg`` and included with:
 ```
-#include "d_fall_pps/Setpoint.h"
+#include "dfall_pkg/Setpoint.h"
 ```
 added at the top of  your ``StudentControllerService.cpp`` file.
 
diff --git a/wiki/installation.md b/wiki/installation.md
index 9d59218e..a97bfeeb 100644
--- a/wiki/installation.md
+++ b/wiki/installation.md
@@ -5,7 +5,7 @@
 ### Install Script
 Installation with the install script is the easiest. You will need:
 - the install script
-- the ``d_fall_pps`` package compressed in a file called ``package.tar.gz``
+- the ``dfall_pkg`` package compressed in a file called ``package.tar.gz``
 - the rule files for the USB connection to the crazyradio, called ``99-crazyflie.rules`` and ``99-crazyradio.rules``
 
 These files all need to be in the same directory. To run the installation, move to the containing directory (pps\ install) and call it with
@@ -21,7 +21,7 @@ The installation process consists of the following steps:
 The detailed instructions for the installation of ROS can be found [here](http://wiki.ros.org/kinetic/Installation/Ubuntu).
 
 - Workspace: <br />
-Create a new catkin workspace and copy the ``d_fall_pps`` package into the ``src`` folder of the workspace. Then build the package with ``catkin_make`` called from the workspace root.
+Create a new catkin workspace and copy the ``dfall_pkg`` package into the ``src`` folder of the workspace. Then build the package with ``catkin_make`` called from the workspace root.
 
 - Environment Setup: <br />
 Add a new line in the ``/etc/hosts`` file that links the teacher's IP with the domain name ``teacher`` and create a file called ``/etc/StudentID`` that contains the student id. Only write digits without any other symbols or whitespace characters.
@@ -47,7 +47,7 @@ Add following lines to the bottom of the file ``~/.bashrc`` (replace ``<catkin w
 ```
 source /opt/ros/kinetic/setup.bash
 source <catkin workspace>/devel/setup.bash
-source <catkin workspace>/src/d_fall_pps/launch/Config.sh
+source <catkin workspace>/src/dfall_pkg/launch/Config.sh
 ```
 
 The workspace setup script will only appear after the first compilation of the catkin workspace.
@@ -63,11 +63,11 @@ A Vicon motion capture system can be used to provide position and attitude measu
 - De-compress the downloaded file and open the folder that corresponds to the latest ``Linux64-boost-1.xx.x`` version, when tested this was ``1.58.0``
 - From the files found in this folder, copy the file ``DataStreamClient.h`` into the following folder:
 ```
-~/pps_ws/src/d_fall_pps/include/
+~/dfall_ws/src/dfall_pkg/include/
 ```
 - Copy the file ``libViconDataStreamSDK_CPP.so`` into the following folder (noting that the folder ``lib`` and ``vicon`` may need to be created):
 ```
-~/pps_ws/src/d_fall_pps/lib/vicon/
+~/dfall_ws/src/dfall_pkg/lib/vicon/
 ```
 - Copy all the files of the form ``libboost_*`` into the same ``/lib/vicon/`` folder
 - Note that the ``DataStreamClient.h`` header file and the ``/lib/vicon/`` folder are in the ``.gitignore`` and hence will not be tracked or removed by the git repository (though some more advanced git commands may still remove them anyway).
@@ -78,7 +78,7 @@ A Vicon motion capture system can be used to provide position and attitude measu
 ### Removing Config.sh and replacing
 As the teacher must not source the script ``Config.sh``, the ``.bashrc`` must be edited and the last line
 ```
-source ~/pps_ws/src/d_fall_pps/launch/Config.sh
+source ~/dfall_ws/src/dfall_pkg/launch/Config.sh
 ```
 must be replaced with
 ```
@@ -109,7 +109,7 @@ doing so are these:
    changes to take effect) <br><br>
 2. After having put some reflective markers in the crazyflie, register it in the Vicon system with the name that you want. (in the PPS case, we call them PPS_CFXX)<br><br>
 3. Go to the file channelLUT.cpp (path:
-   `pps_ws/src/d_fall_pps/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp`) and add an
+   `dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/channelLUT.cpp`) and add an
    entry with the name of the crazyflie and the radio address. Follow the
    formatting that the other entries have.<br><br>
    <img src="./pics/LUT.png" style="width: 450px;"/> <br><br>
diff --git a/wiki/namespace_conventions.md b/wiki/namespace_conventions.md
index 7ba26326..b47cd981 100644
--- a/wiki/namespace_conventions.md
+++ b/wiki/namespace_conventions.md
@@ -13,7 +13,7 @@ echo $ROS_NAMESPACE
 
 This environment vairable is set in the file:
 ```
-pps_ws/src/d_fall_pps/launch/Config.sh
+dfall_ws/src/dfall_pkg/launch/Config.sh
 ```
 The environemnt variable is set by the following line in that file:
 ```
diff --git a/wiki/setup.md b/wiki/setup.md
index bcebb8ad..887bd01f 100644
--- a/wiki/setup.md
+++ b/wiki/setup.md
@@ -95,7 +95,7 @@ Then go to the _IPv4 Settings_ and choose **Manual** as the _Method_ and then ad
 
 ### Vicon, teacher and students
 During installation process is the IP address of the teacher set to 10.42.0.10. (This value is written to the /etc/hosts file such that this IP address is accessible through the keyword _teacher_) <br>
-Have a look at `Config.sh` in `~/pps_ws/src/d_fall_pps/launch/`
+Have a look at `Config.sh` in `~/dfall_ws/src/dfall_pkg/launch/`
 <br><img src="./pics/setup_pics/configsh2.png" style="width: 500px;"/> <br>
 Here you see, that the ROS Master URI is set to be the teacher. This means that _roscore_ runs only on the teacher's computer. Your own IP address (_ROS IP_) is also set and taken from your Ethernet settings as defined in the section _Setting up the Vicon network_.
 <br>
diff --git a/wiki/workflow_for_students.md b/wiki/workflow_for_students.md
index 114c154d..b1cf0b1a 100644
--- a/wiki/workflow_for_students.md
+++ b/wiki/workflow_for_students.md
@@ -11,7 +11,7 @@ gyrosensor needs to initialize.
   * In the software side, everything has already been set up for the course, but
     it would be helpful to check if the repository is in the last version, and
     if the source code has been properly compiled. To do this, follow the next steps:
-       1. Go to the next folder: `cd ~/work/D-FaLL-System/pps_ws`
+       1. Go to the next folder: `cd ~/work/D-FaLL-System/dfall_ws`
        2. Checkout master branch of the repository and pull:<br />
          ``git checkout master``<br />
          ``git pull origin master``<br />
@@ -26,7 +26,7 @@ gyrosensor needs to initialize.
 
   * Once all the prerequisites have been fulfilled, we can start the student's
     GUI by going to a terminal and typing:
-    `roslaunch d_fall_pps Student.launch`
+    `roslaunch dfall_pkg Student.launch`
 
     *Note: for this to work, the teacher's computer has to be connected to the
     network and the teacher's GUI has to be started before. Please wait until
@@ -69,7 +69,7 @@ gyrosensor needs to initialize.
     safe controller to get familiar with the system.
 
     *Note: there are different parameters in the file called
-    `SafeController.yaml`, in the folder param (use `roscd d_fall_pps/param` in a
+    `SafeController.yaml`, in the folder param (use `roscd dfall_pkg/param` in a
     terminal to go there).* **These are the safe controller parameters and should NOT be
     changed.** *Take a look at the file and get familiar with the format used,
     since may have to write your own for the student controller.*
@@ -81,12 +81,12 @@ important files that should be taken into account.
 
 #### Files of interest:
 
-* In `d_fall_pps/src`
+* In `dfall_pkg/src`
 
   * _StudentControllerService.cpp_ <br>
   The file where students can implement their own controller. It provides already the ros service with the teacher. It can be used as a template.
 
-* In `d_fall_pps/param`
+* In `dfall_pkg/param`
 
   * _ClientConfig.yaml_ <br><br>
           <img src="./pics/client_config_yaml.png" style="width: 400px;"/> <br><br>
@@ -119,7 +119,7 @@ important files that should be taken into account.
       *Sets the low battery thresholds at which the crazyflie will automatically
       land. **Do not change these values.***
 
-* In `d_fall_pps/`
+* In `dfall_pkg/`
 
   * CMakeLists.txt
 
@@ -131,7 +131,7 @@ important files that should be taken into account.
 
 
 <!-- ##### -- Useful files: -->
-<!-- in `pps_ws/src/d_fall_pps/scripts` -->
+<!-- in `dfall_ws/src/dfall_pkg/scripts` -->
 <!-- -\-> call scripts in terminal by going to the above path and then typing -->
 <!-- ./SCRIPTNAME, e.g.: `./enable_crazyflie` -->
 
@@ -144,11 +144,11 @@ important files that should be taken into account.
 
 
 <!-- ##### -- Files to look at: -->
-<!-- in `pps_ws/src/d_fall_pps/param` -->
+<!-- in `dfall_ws/src/dfall_pkg/param` -->
 <!-- * _SafeController.yaml_ <br> -->
 <!-- This file contains the control parameters that the SafeControllerService uses. The SafeControllerService loads this file when it starts. You might want to use a similar approach and can try to copy some functionality from  SafeControllerService.cpp. -->
 
-<!-- in `pps_ws/scr/d_fall_pps/launch` <br> -->
+<!-- in `dfall_ws/scr/dfall_pkg/launch` <br> -->
 <!-- The launch files contained in this directory are used to launch several nodes and some parameter files to be launched simultaneously. It is best, that you take a look at them yourself, but here is a brief explanation what the different launch files are for.<br> -->
 <!-- To start the whole thing type the following in a terminal whilst being in the launch directory.<br> -->
 <!-- `roslaunch filename.launch` -->
@@ -177,10 +177,10 @@ important files that should be taken into account.
      without having to compile or restart the system. Here, as an example, we
      pass some parameters that can be seen below:<br><br>
         <img src="./pics/custom_controller_yaml.png" style="width: 400px;"/> <br><br>
-2. Go to `cd ~/work/D-FaLL-System/pps_ws` and write `catkin_make`.
+2. Go to `cd ~/work/D-FaLL-System/dfall_ws` and write `catkin_make`.
 
 3. Once everything has compiled without errors, run the next launch file:
-   `roslaunch d_fall_pps Student.launch`. This will run the student's GUI.
+   `roslaunch dfall_pkg Student.launch`. This will run the student's GUI.
 
 4. Make sure that your Crazyflie is turned ON and connect to it. Choose the tab
    called *Student Controller* and click on the button *Enable Student Controller*
@@ -218,7 +218,7 @@ to it*
    vicon\_y,...). Additionally, there are up to 10 general purpose variables
    that can be filled with any data we may be interested in plotting (value\_1,
    value\_2,...., value\_10). <br><br>
-2. Once chosen the variables, save the file and go to `cd ~/work/D-FaLL-System/pps_ws` and write `catkin_make`.<br><br>
+2. Once chosen the variables, save the file and go to `cd ~/work/D-FaLL-System/dfall_ws` and write `catkin_make`.<br><br>
 3. Open another terminal and type `rqt`. Then, in the top bar, go to
    Plugins->Visualization->Plot. A new plot will be added to the screen. If you
    want more than one plot, just add several ones doing the same thing. You will
@@ -231,7 +231,7 @@ to it*
    `/<student_id>/StudentControllerService/DebugTopic/vicon_z`. You can see an
    autocompletion of the
    list of all the topics available when you start typing in the field "Topic". <br><br>
-5. Start the Student node following the steps mentioned before (`roslaunch d_fall_pps Student.launch`) and enable the Student Controller.<br><br>
+5. Start the Student node following the steps mentioned before (`roslaunch dfall_pkg Student.launch`) and enable the Student Controller.<br><br>
 6. Once we are using the Student Controller, we will be seeing how the data
    selected gets plotted in the rqt plots.
 
@@ -242,12 +242,12 @@ to it*
 <!-- **Setup** -->
 <!-- 1.  Teacher must run his part, that publishes ViconData for students and hosts the roscore. -->
 <!-- 2.  Each student/group has a CrazyFlie and a laptop. -->
-<!-- 3.  Use `roscd d_fall_pps/launch` in a terminal as well as `roscd d_fall_pps/scripts` in another terminal -->
+<!-- 3.  Use `roscd dfall_pkg/launch` in a terminal as well as `roscd dfall_pkg/scripts` in another terminal -->
 
 <!-- <br> -->
 <!-- **Working** -->
 <!-- 1.  Adjust your custom controller -->
-<!-- 2.  Use `catkin_make` in the pps_ws directory to compile your controller implementation -->
+<!-- 2.  Use `catkin_make` in the dfall_ws directory to compile your controller implementation -->
 <!-- 3.  Start your crazyflie -->
 <!-- 4.  Launch the correct file in the launch directory as described above. ClientConfig.yaml has to be correct. -->
 <!-- 5. Use the scripts to change from the safe to your custom controller. -->
-- 
GitLab


From dacae599f59608f894c1d18aefd2c774a20f13ec Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 13:46:01 +0100
Subject: [PATCH 73/87] Renamed launch files to begin with a lowercase letter
 to make it easier for typing into the command line

---
 dfall_ws/src/dfall_pkg/launch/{Agent.launch => agent.launch}      | 0
 .../dfall_pkg/launch/{Coordinator.launch => coordinator.launch}   | 0
 dfall_ws/src/dfall_pkg/launch/{Teacher.launch => teacher.launch}  | 0
 3 files changed, 0 insertions(+), 0 deletions(-)
 rename dfall_ws/src/dfall_pkg/launch/{Agent.launch => agent.launch} (100%)
 rename dfall_ws/src/dfall_pkg/launch/{Coordinator.launch => coordinator.launch} (100%)
 rename dfall_ws/src/dfall_pkg/launch/{Teacher.launch => teacher.launch} (100%)

diff --git a/dfall_ws/src/dfall_pkg/launch/Agent.launch b/dfall_ws/src/dfall_pkg/launch/agent.launch
similarity index 100%
rename from dfall_ws/src/dfall_pkg/launch/Agent.launch
rename to dfall_ws/src/dfall_pkg/launch/agent.launch
diff --git a/dfall_ws/src/dfall_pkg/launch/Coordinator.launch b/dfall_ws/src/dfall_pkg/launch/coordinator.launch
similarity index 100%
rename from dfall_ws/src/dfall_pkg/launch/Coordinator.launch
rename to dfall_ws/src/dfall_pkg/launch/coordinator.launch
diff --git a/dfall_ws/src/dfall_pkg/launch/Teacher.launch b/dfall_ws/src/dfall_pkg/launch/teacher.launch
similarity index 100%
rename from dfall_ws/src/dfall_pkg/launch/Teacher.launch
rename to dfall_ws/src/dfall_pkg/launch/teacher.launch
-- 
GitLab


From ac1cb5ab09aeea3b282aea672340db4219003cef Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 14:41:01 +0100
Subject: [PATCH 74/87] Small changes to the picker controller for paramter
 loading, and to Flying agent GUI for units of the yaw error

---
 .../src/defaultcontrollertab.cpp              | 13 ++++---
 .../src/pickercontrollertab.cpp               | 11 +++---
 .../src/studentcontrollertab.cpp              | 13 ++++---
 .../include/nodes/PickerControllerService.h   | 12 +++---
 .../src/dfall_pkg/param/PickerController.yaml |  2 +-
 .../src/nodes/PickerControllerService.cpp     | 37 +++++++++++--------
 6 files changed, 48 insertions(+), 40 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index c4ad82b4..c527b641 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -138,17 +138,18 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
         ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
 
         if (roll < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll * RAD2DEG, 'f', 1));
         if (pitch < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
         if (yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1));
 
-        // GET THE CURRENT SETPOINT
+        // GET THE CURRENT SETPOINT ERROR
         float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
         float error_y   = y   - (ui->lineEdit_setpoint_current_y->text()  ).toFloat();
         float error_z   = z   - (ui->lineEdit_setpoint_current_z->text()  ).toFloat();
-        float error_yaw = yaw - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+        float error_yaw_deg = yaw * RAD2DEG - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
         // UPDATE THE ERROR COLUMN
         if (error_x < 0.0f) qstr = ""; else qstr = "+";
@@ -158,8 +159,8 @@ void DefaultControllerTab::setMeasuredPose(float x , float y , float z , float r
         if (error_z < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', 3));
 
-        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+        if (error_yaw_deg < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw_deg , 'f', 1));
 
         // Ensure the red frames are not visible
         if ( ui->red_frame_position_left->isVisible() )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
index 60c5ada3..f90b07f4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/pickercontrollertab.cpp
@@ -552,13 +552,14 @@ void PickerControllerTab::setMeasuredPose(float x , float y , float z , float ro
         ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', DECIMAL_PLACES_POSITION));
 
         if (yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
 
-        // GET THE CURRENT SETPOINT
+        // GET THE CURRENT SETPOINT ERROR
         float error_x   = x   - (ui->lineEdit_current_x->text()  ).toFloat();
         float error_y   = y   - (ui->lineEdit_current_y->text()  ).toFloat();
         float error_z   = z   - (ui->lineEdit_current_z->text()  ).toFloat();
-        float error_yaw = yaw - (ui->lineEdit_current_yaw->text()).toFloat();
+
+        float error_yaw_deg = yaw * RAD2DEG - (ui->lineEdit_current_yaw->text()).toFloat();
 
         // UPDATE THE ERROR COLUMN
         if (error_x < 0.0f) qstr = ""; else qstr = "+";
@@ -568,8 +569,8 @@ void PickerControllerTab::setMeasuredPose(float x , float y , float z , float ro
         if (error_z < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', DECIMAL_PLACES_POSITION));
 
-        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', DECIMAL_PLACES_ANGLE_DEGREES));
+        if (error_yaw_deg < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw_deg , 'f', DECIMAL_PLACES_ANGLE_DEGREES));
 
         // Ensure the red frames are not visible
         if ( ui->frame_x_unavailable->isVisible() )
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
index e89ddaff..440daaac 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/studentcontrollertab.cpp
@@ -220,17 +220,18 @@ void StudentControllerTab::setMeasuredPose(float x , float y , float z , float r
         ui->lineEdit_measured_z->setText(qstr + QString::number( z, 'f', 3));
 
         if (roll < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll  * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_roll->setText(qstr + QString::number( roll * RAD2DEG, 'f', 1));
         if (pitch < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_measured_pitch->setText(qstr + QString::number( pitch * RAD2DEG, 'f', 1));
         if (yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw   * RAD2DEG, 'f', 1));
+        ui->lineEdit_measured_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 1));
 
-        // GET THE CURRENT SETPOINT
+        // GET THE CURRENT SETPOINT ERROR
         float error_x   = x   - (ui->lineEdit_setpoint_current_x->text()  ).toFloat();
         float error_y   = y   - (ui->lineEdit_setpoint_current_y->text()  ).toFloat();
         float error_z   = z   - (ui->lineEdit_setpoint_current_z->text()  ).toFloat();
-        float error_yaw = yaw - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
+
+        float error_yaw_deg = yaw * RAD2DEG - (ui->lineEdit_setpoint_current_yaw->text()).toFloat();
 
         // UPDATE THE ERROR COLUMN
         if (error_x < 0.0f) qstr = ""; else qstr = "+";
@@ -240,8 +241,8 @@ void StudentControllerTab::setMeasuredPose(float x , float y , float z , float r
         if (error_z < 0.0f) qstr = ""; else qstr = "+";
         ui->lineEdit_error_z->setText(qstr + QString::number( error_z, 'f', 3));
 
-        if (error_yaw < 0.0f) qstr = ""; else qstr = "+";
-        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw * RAD2DEG, 'f', 1));
+        if (error_yaw_deg < 0.0f) qstr = ""; else qstr = "+";
+        ui->lineEdit_error_yaw->setText(qstr + QString::number( error_yaw_deg , 'f', 1));
 
         // Ensure the red frames are not visible
         if ( ui->red_frame_position_left->isVisible() )
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
index fab684a8..f0d015af 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
@@ -154,7 +154,7 @@ float m_weight_total_in_newtons;
 
 // The setpoint to be tracked, the ordering is (x,y,z,yaw),
 // with units [meters,meters,meters,radians]
-float  m_setpoint[4] = {0.0,0.0,0.4,0.0};
+float m_setpoint[4] = {0.0,0.0,0.4,0.0};
 
 // The setpoint that is actually used by the controller, this
 // differs from the setpoint when smoothing is turned on
@@ -164,10 +164,10 @@ float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
 bool m_shouldSmoothSetpointChanges = true;
 
 // Max setpoint change per second
-float yaml_max_setpoint_change_per_second_horizontal;
-float yaml_max_setpoint_change_per_second_vertical;
-float yaml_max_setpoint_change_per_second_yaw_degrees;
-float m_max_setpoint_change_per_second_yaw_radians;
+float yaml_max_setpoint_change_per_second_horizontal = 0.1;
+float yaml_max_setpoint_change_per_second_vertical = 0.1;
+float yaml_max_setpoint_change_per_second_yaw_degrees = 90.0;
+float m_max_setpoint_change_per_second_yaw_radians = 90.0 * DEG2RAD;
 
 
 
@@ -267,7 +267,7 @@ std::vector<float> yaml_PMKF_Kinf_for_angles         (2,0.0);
 // VARIABLES RELATING TO PERFORMING THE CONVERSION INTO BODY FRAME
 
 // Boolean whether to execute the convert into body frame function
-bool yaml_shouldPerformConvertIntoBodyFrame = false;
+bool yaml_shouldPerformConvertIntoBodyFrame = true;
 
 
 // VARIABLES RELATING TO THE PUBLISHING OF A DEBUG MESSAGE
diff --git a/dfall_ws/src/dfall_pkg/param/PickerController.yaml b/dfall_ws/src/dfall_pkg/param/PickerController.yaml
index f319b4fd..eb097bb6 100644
--- a/dfall_ws/src/dfall_pkg/param/PickerController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/PickerController.yaml
@@ -2,7 +2,7 @@
 # Max setpoint change per second
 max_setpoint_change_per_second_horizontal  :  0.20 # [meters]
 max_setpoint_change_per_second_vertical    :  0.10 # [meters]
-max_setpoint_change_per_second_yaw_degrees : 90.00 # [degrees]
+max_setpoint_change_per_second_yaw_degrees : 180.00 # [degrees]
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
index deda6de0..6d28bc65 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp
@@ -815,18 +815,20 @@ void convert_stateInertial_to_bodyFrameError(float stateInertial[12], float setp
 	// > Second, "unwrap" the yaw error to the interval ( -pi , pi )
 	while(yawError > PI) {yawError -= 2 * PI;}
 	while(yawError < -PI) {yawError += 2 * PI;}
-	// > Third, put the "yawError" into the "stateError" variable
-	stateInertial[8] = yawError;
-
-
-	if (yawError>(PI/6))
+	// > Third, clip the error to within some bounds
+		if (yawError>(PI/3))
 	{
-		yawError = (PI/6);
+		yawError = (PI/3);
 	}
-	else if (yawError<(-PI/6))
+	else if (yawError<(-PI/3))
 	{
-		yawError = (-PI/6);
+		yawError = (-PI/3);
 	}
+	// > Finally, put the "yawError" into the "stateError" variable
+	stateInertial[8] = yawError;
+
+
+
 
 	// CONVERSION INTO BODY FRAME
 	// Conver the state erorr from the Inertial frame into the Body frame
@@ -1056,7 +1058,6 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 // PUBLISH THE CURRENT X,Y,Z, AND YAW (if required)
 void publish_current_xyz_yaw(float x, float y, float z, float yaw)
 {
-	// // publish setpoint for FollowController of another student group
 	// SetpointWithHeader temp_current_xyz_yaw;
 	// // Fill in the x,y,z, and yaw info directly from the data provided to this
 	// // function
@@ -1135,7 +1136,7 @@ void isReadyPickerControllerYamlCallback(const IntWithHeader & msg)
 void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 {
 	// Here we load the parameters that are specified in the file:
-	// StudentController.yaml
+	// PickerController.yaml
 
 	// Add the "PickerController" namespace to the "nodeHandle"
 	ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "PickerController");
@@ -1203,7 +1204,7 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
 
 
 	// DEBUGGING: Print out one of the parameters that was loaded
-	ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: the fetched PickerController/mass_cf_in_grams = " << yaml_mass_cf_in_grams);
+	ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: the fetched PickerController/max_setpoint_change_per_second_yaw_degrees = " << yaml_max_setpoint_change_per_second_yaw_degrees);
 
 
 
@@ -1214,6 +1215,10 @@ void fetchPickerControllerYamlParameters(ros::NodeHandle& nodeHandle)
     // Set that the estimator frequency is the same as the control frequency
     m_estimator_frequency = yaml_control_frequency;
 
+    // DEBUGGING: Print out one of the processed values
+	ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: after processing m_max_setpoint_change_per_second_yaw_radians = " << m_max_setpoint_change_per_second_yaw_radians);
+
+
 }
 
 
@@ -1256,7 +1261,7 @@ int main(int argc, char* argv[]) {
 	//   <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 "studentID" paremeter, we first
+	// > 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.
 
@@ -1351,13 +1356,13 @@ int main(int argc, char* argv[]) {
 	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
 	{
 		// Nothing to do in this case.
-		// The "isReadyStudentControllerYamlCallback" function
+		// The "isReadyPickerControllerYamlCallback" function
 		// will be called once the YAML file is loaded
 	}
 	else
 	{
 		// Inform the user
-		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
+		ROS_ERROR("[PICKER CONTROLLER] The request load yaml file service call failed.");
 	}
 
 
@@ -1430,13 +1435,13 @@ int main(int argc, char* argv[]) {
 
     // Instantiate the instance variable "my_current_xyz_yaw_publisher" to be a "ros::Publisher"
     // that advertises under the name "<my_agentID>/my_current_xyz_yaw_topic" where <my_agentID>
-    // is filled in with the student ID number of this computer. The messages published will
+    // is filled in with the agent ID number of this computer. The messages published will
     // have the structure defined in the file "Setpoint.msg" (located in the "msg" folder).
     //my_current_xyz_yaw_publisher = nodeHandle.advertise<Setpoint>("my_current_xyz_yaw_topic", 1);
 
 
     // Print out some information to the user.
-    ROS_INFO("[Picker CONTROLLER] Service ready :-)");
+    ROS_INFO("[PICKER CONTROLLER] Service ready :-)");
 
     // Enter an endless while loop to keep the node alive.
     ros::spin();
-- 
GitLab


From a6f0c42a40a2de9c56c4b856e151e1bca456e6bb Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 19:30:48 +0100
Subject: [PATCH 75/87] Started process of converting the Flying agent client
 from the safe controller to the default controller, and streamlining things
 at the same time. Currently compiles and flys, but needs cleaning up and
 proper implementing of the take-off and land functions.

---
 .../include/Constants_for_Qt_compile.h        |   86 +-
 .../include/enablecontrollerloadyamlbar.h     |   12 +-
 .../flyingAgentGUI/src/controllertabs.cpp     |   15 +-
 .../flyingAgentGUI/src/coordinatorrow.cpp     |    6 +-
 .../src/enablecontrollerloadyamlbar.cpp       |    4 +-
 .../include/constants_for_qt_compile.h        |   83 +-
 dfall_ws/src/dfall_pkg/crazyradio/TestCF.py   |    8 -
 .../src/dfall_pkg/include/nodes/Constants.h   |   87 +-
 .../include/nodes/FlyingAgentClient.h         |  191 +-
 .../src/dfall_pkg/param/ClientConfig.yaml     |    7 +-
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp | 1839 +++++++++--------
 .../src/nodes/MpcControllerService.cpp        |   80 +-
 .../src/nodes/RemoteControllerService.cpp     |   80 +-
 .../src/nodes/SafeControllerService.cpp       |   78 +-
 14 files changed, 1232 insertions(+), 1344 deletions(-)

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 716a287f..a6d8f558 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
@@ -107,7 +107,7 @@
 #define CF_COMMAND_TYPE_ANGLE  8
 
 // Types of controllers being used:
-#define SAFE_CONTROLLER      1
+#define DEFAULT_CONTROLLER      1
 #define DEMO_CONTROLLER      2
 #define STUDENT_CONTROLLER   3
 #define MPC_CONTROLLER       4
@@ -118,7 +118,7 @@
 
 // The constants that "command" changes in the
 // operation state of this agent
-#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEFAULT_CONTROLLER      1
 #define CMD_USE_DEMO_CONTROLLER      2
 #define CMD_USE_STUDENT_CONTROLLER   3
 #define CMD_USE_MPC_CONTROLLER       4
@@ -208,84 +208,4 @@
 //    ----------------------------------------------------------------------------------
 
 // For standard buttons in the GUI
-#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-// OLD STUFF FOR LOADING YAML FILES
-// For which controller parameters to load from file
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
-#define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
-#define LOAD_YAML_STUDENT_CONTROLLER_AGENT          3
-#define LOAD_YAML_MPC_CONTROLLER_AGENT              4
-#define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
-#define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
-#define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
-#define LOAD_YAML_TEMPLATE_CONTROLLER_AGENT         8
-
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
-#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
-#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR    13
-#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR        14
-#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
-#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
-#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
-#define LOAD_YAML_TEMPLATE_CONTROLLER_COORDINATOR   18
-
-
-// For sending commands to the controller node informing
-// which parameters to fetch
-// > NOTE: these are identical to the #defines above, but
-//         used because they have the name distinguishes
-//         between:
-//         - "loading" a yaml file into ram
-//         - "fetching" the values that were loaded into ram
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT      1
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT   3
-#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT       4
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
-#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_OWN_AGENT  8
-
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR   13
-#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
-#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_COORDINATOR  18
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
\ No newline at end of file
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 6699aa3b..3ffd3ff9 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
@@ -72,17 +72,7 @@
 #endif
 
 
-// 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 "FlyingAgentClient"
-// node where the command is enacted
-// #define CMD_USE_SAFE_CONTROLLER      1
-// #define CMD_USE_DEMO_CONTROLLER      2
-// #define CMD_USE_STUDENT_CONTROLLER   3
-// #define CMD_USE_MPC_CONTROLLER       4
-// #define CMD_USE_REMOTE_CONTROLLER    5
-// #define CMD_USE_TUNING_CONTROLLER    6
+
 
 
 namespace Ui {
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 ec83ca37..899ab673 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
@@ -397,16 +397,11 @@ void ControllerTabs::setControllerEnabled(int new_controller)
     // the enable controller
     switch(new_controller)
     {
-        case SAFE_CONTROLLER:
-        {
-            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->default_tab );
-            break;
-        }
-//        case DEFAULT_CONTROLLER:
-//        {
-//            setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->default_tab );
-//            break;
-//        }
+       case DEFAULT_CONTROLLER:
+       {
+           setTextColourOfTabLabel( m_tab_text_colour_highlight , ui->default_tab );
+           break;
+       }
         case DEMO_CONTROLLER:
         {
             //ui->controller_enabled_label->setText("Demo");
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 21585a85..b6d60f69 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
@@ -88,7 +88,7 @@ CoordinatorRow::CoordinatorRow(QWidget *parent, int agentID) :
     setFlyingState(STATE_UNAVAILABLE);
     
     // SET THE DEFAULT NAME FOR THE SELECTED CONTROLLER
-    setControllerEnabled(SAFE_CONTROLLER);
+    setControllerEnabled(DEFAULT_CONTROLLER);
 
 
 #ifdef CATKIN_MAKE
@@ -708,9 +708,9 @@ void CoordinatorRow::setControllerEnabled(int new_controller)
 {
     switch(new_controller)
     {
-        case SAFE_CONTROLLER:
+        case DEFAULT_CONTROLLER:
         {
-            ui->controller_enabled_label->setText("Safe");
+            ui->controller_enabled_label->setText("Default");
             break;
         }
         case DEMO_CONTROLLER:
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 30468755..d5389a8b 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
@@ -125,9 +125,9 @@ void EnableControllerLoadYamlBar::on_enable_default_button_clicked()
 #ifdef CATKIN_MAKE
     dfall_pkg::IntWithHeader msg;
     fillIntMessageHeader(msg);
-    msg.data = CMD_USE_SAFE_CONTROLLER;
+    msg.data = CMD_USE_DEFAULT_CONTROLLER;
     this->commandPublisher.publish(msg);
-    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Safe Controller");
+    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable Default Controller");
 #endif
 }
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h
index b361da05..891b10ef 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/systemConfigGUI/include/constants_for_qt_compile.h
@@ -107,7 +107,7 @@
 #define CF_COMMAND_TYPE_ANGLE  8
 
 // Types of controllers being used:
-#define SAFE_CONTROLLER      1
+#define DEFAULT_CONTROLLER      1
 #define DEMO_CONTROLLER      2
 #define STUDENT_CONTROLLER   3
 #define MPC_CONTROLLER       4
@@ -117,7 +117,7 @@
 
 // The constants that "command" changes in the
 // operation state of this agent
-#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEFAULT_CONTROLLER      1
 #define CMD_USE_DEMO_CONTROLLER      2
 #define CMD_USE_STUDENT_CONTROLLER   3
 #define CMD_USE_MPC_CONTROLLER       4
@@ -206,81 +206,4 @@
 //    ----------------------------------------------------------------------------------
 
 // For standard buttons in the GUI
-#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-// OLD STUFF FOR LOADING YAML FILES
-// For which controller parameters to load from file
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
-#define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
-#define LOAD_YAML_STUDENT_CONTROLLER_AGENT          3
-#define LOAD_YAML_MPC_CONTROLLER_AGENT              4
-#define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
-#define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
-#define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
-
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
-#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
-#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR    13
-#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR        14
-#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
-#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
-#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
-
-
-// For sending commands to the controller node informing
-// which parameters to fetch
-// > NOTE: these are identical to the #defines above, but
-//         used because they have the name distinguishes
-//         between:
-//         - "loading" a yaml file into ram
-//         - "fetching" the values that were loaded into ram
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT      1
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT   3
-#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT       4
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
-
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR   13
-#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
\ No newline at end of file
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
index 3cfb0e2a..f955bd2c 100755
--- a/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
+++ b/dfall_ws/src/dfall_pkg/crazyradio/TestCF.py
@@ -54,12 +54,6 @@ DISCONNECTED = 2
 CMD_RECONNECT = 0
 CMD_DISCONNECT = 1
 
-# Commands for FlyingAgentClient
-CMD_USE_SAFE_CONTROLLER =   1
-CMD_USE_CUSTOM_CONTROLLER = 2
-CMD_CRAZYFLY_TAKE_OFF =     3
-CMD_CRAZYFLY_LAND =         4
-CMD_CRAZYFLY_MOTORS_OFF =   5
 
 # rp = RosPack()
 # record_file = rp.get_path('dfall_pkg') + '/LoggingOnboard.bag'
@@ -239,8 +233,6 @@ if __name__ == '__main__':
     # rospy.loginfo("Turning off crazyflie")
 
 
-    # change state to 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/Constants.h b/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
index 71507435..0843e1a2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/Constants.h
@@ -120,7 +120,7 @@
 //    ----------------------------------------------------------------------------------
 
 // Types of controllers being used:
-#define SAFE_CONTROLLER      1
+#define DEFAULT_CONTROLLER      1
 #define DEMO_CONTROLLER      2
 #define STUDENT_CONTROLLER   3
 #define MPC_CONTROLLER       4
@@ -131,7 +131,7 @@
 
 // The constants that "command" changes in the
 // operation state of this agent
-#define CMD_USE_SAFE_CONTROLLER      1
+#define CMD_USE_DEFAULT_CONTROLLER   1
 #define CMD_USE_DEMO_CONTROLLER      2
 #define CMD_USE_STUDENT_CONTROLLER   3
 #define CMD_USE_MPC_CONTROLLER       4
@@ -222,85 +222,4 @@
 //    ----------------------------------------------------------------------------------
 
 // For standard buttons in the GUI
-#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-// OLD STUFF FOR LOADING YAML FILES
-// For which controller parameters to load from file
-#define LOAD_YAML_SAFE_CONTROLLER_AGENT             1
-#define LOAD_YAML_DEMO_CONTROLLER_AGENT             2
-#define LOAD_YAML_STUDENT_CONTROLLER_AGENT          3
-#define LOAD_YAML_MPC_CONTROLLER_AGENT              4
-#define LOAD_YAML_REMOTE_CONTROLLER_AGENT           5
-#define LOAD_YAML_TUNING_CONTROLLER_AGENT           6
-#define LOAD_YAML_PICKER_CONTROLLER_AGENT           7
-#define LOAD_YAML_TEMPLATE_CONTROLLER_AGENT         7
-
-#define LOAD_YAML_SAFE_CONTROLLER_COORDINATOR       11
-#define LOAD_YAML_DEMO_CONTROLLER_COORDINATOR       12
-#define LOAD_YAML_STUDENT_CONTROLLER_COORDINATOR    13
-#define LOAD_YAML_MPC_CONTROLLER_COORDINATOR        14
-#define LOAD_YAML_REMOTE_CONTROLLER_COORDINATOR     15
-#define LOAD_YAML_TUNING_CONTROLLER_COORDINATOR     16
-#define LOAD_YAML_PICKER_CONTROLLER_COORDINATOR     17
-#define LOAD_YAML_TEMPLATE_CONTROLLER_COORDINATOR   18
-
-
-// For sending commands to the controller node informing
-// which parameters to fetch
-// > NOTE: these are identical to the #defines above, but
-//         used because they have the name distinguishes
-//         between:
-//         - "loading" a yaml file into ram
-//         - "fetching" the values that were loaded into ram
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT      1
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_OWN_AGENT      2
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_OWN_AGENT   3
-#define FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT       4
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT    5
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_OWN_AGENT    6
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_OWN_AGENT    7
-#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_OWN_AGENT  8
-
-#define FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR      11
-#define FETCH_YAML_DEMO_CONTROLLER_FROM_COORDINATOR      12
-#define FETCH_YAML_STUDENT_CONTROLLER_FROM_COORDINATOR   13
-#define FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR       14
-#define FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR    15
-#define FETCH_YAML_TUNING_CONTROLLER_FROM_COORDINATOR    16
-#define FETCH_YAML_PICKER_CONTROLLER_FROM_COORDINATOR    17
-#define FETCH_YAML_TEMPLATE_CONTROLLER_FROM_COORDINATOR  18
\ No newline at end of file
+#define REQUEST_DEFAULT_SETPOINT_BUTTON_ID    100
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 9e1d64e2..2d97b7c2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -121,8 +121,38 @@ std::string m_namespace_to_own_agent_parameter_service;
 std::string m_namespace_to_coordinator_parameter_service;
 
 
+// variables for the states:
+int m_flying_state;
+bool m_changed_flying_state_flag;
+
+// variable for crazyradio status
+int crazyradio_status;
+
+//describes the area of the crazyflie and other parameters
+CrazyflieContext m_context;
+
+// The index for which element in the "motion captate data"
+// array is expected to match the name in "m_context"
+// > Negative numbers indicate unknown
+int m_poseDataIndex = -1;
+
+// wheter to use safe of demo controller
+// variable for the instant controller, e.g., we use
+// safe controller for taking off and landing even
+// if demo controller is enabled. This variable WILL change automatically
+int m_instant_controller;
+ros::ServiceClient* m_instant_controller_service_client;
+bool m_controllers_avialble = false;
+ros::Timer timer_for_loadAllControllers;
+
+// controller used:
+int m_controller_nominally_selected;
+
+
 // The safe controller specified in the ClientConfig.yaml
 ros::ServiceClient safeController;
+// The default controller specified in the ClientConfig.yaml
+ros::ServiceClient defaultController;
 // The Demo controller specified in the ClientConfig.yaml
 ros::ServiceClient demoController;
 // The Student controller specified in the ClientConfig.yaml
@@ -139,92 +169,62 @@ ros::ServiceClient pickerController;
 ros::ServiceClient templateController;
 
 
-//values for safteyCheck
-bool yaml_strictSafety;
+// The values for the safety check on tilt angle
+bool yaml_isEnabled_strictSafety = true;
 float yaml_angleMargin;
+float yaml_maxTiltAngle_for_strictSafety_degrees = 70;
+float m_maxTiltAngle_for_strictSafety_redians = 70 * DEG2RAD;
 
 
 
 
-// battery threshold
-//float m_battery_threshold_while_flying;
-//float m_battery_threshold_while_motors_off;
-
-
-// battery values
+//Setpoint controller_setpoint;
 
-//int m_battery_state;
-//float m_battery_voltage;
-
-
-
-
-
-Setpoint controller_setpoint;
-
-std::vector<float> yaml_default_setpoint = {0.0f, 0.0f, 0.0f, 0.0f};
+//std::vector<float> yaml_default_setpoint = {0.0f, 0.0f, 0.0f, 0.0f};
 
 // variables for linear trayectory
-Setpoint current_safe_setpoint;
-double distance;
-double unit_vector[3];
-bool was_in_threshold = false;
-double yaml_distance_threshold;      //to be loaded from yaml
+//Setpoint current_safe_setpoint;
+//double distance;
+//double unit_vector[3];
+//bool was_in_threshold = false;
+//double yaml_distance_threshold;      //to be loaded from yaml
 
 
+// Service Client from which the "CrazyflieContext" is loaded
 ros::ServiceClient centralManager;
-ros::Publisher controlCommandPublisher;
+
+// Publisher for the control actions to be sent on
+// to the Crazyflie (the CrazyRadio node listen to this
+// publisher and actually send the commands)
+// {onboardControllerType,roll,pitch,yaw,motorCmd1,motorCmd2,motorCmd3,motorCmd4}
+ros::Publisher commandForSendingToCrazyfliePublisher;
 
 // communicate with safeControllerService, setpoint, etc...
-ros::Publisher safeControllerServiceSetpointPublisher;
+//ros::Publisher safeControllerServiceSetpointPublisher;
 
-// publisher for flying state
+// Publisher for the current flying state of this Flying Agent Client
 ros::Publisher flyingStatePublisher;
 
-// publisher for battery state
-ros::Publisher batteryStatePublisher;
-
-// publisher to send commands to itself.
-ros::Publisher commandPublisher;
+// Publisher for the commands of:
+// {take-off,land,motors-off, and which controller to use}
+//ros::Publisher commandPublisher;
 
-// communication with crazyRadio node. Connect and disconnect
+// Publisher Communication with crazyRadio node. Connect and disconnect
 ros::Publisher crazyRadioCommandPublisher;
 
 
-// Variable for the namespaces for the paramter services
-// > For the paramter service of this agent
-std::string namespace_to_own_agent_parameter_service;
-// > For the parameter service of the coordinator
-std::string namespace_to_coordinator_parameter_service;
-
-
-// variables for the states:
-int flying_state;
-bool changed_state_flag;
-
-// variable for crazyradio status
-int crazyradio_status;
-
-//describes the area of the crazyflie and other parameters
-CrazyflieContext context;
-
-//wheter to use safe of demo controller
-int instant_controller;         //variable for the instant controller, e.g., we use safe controller for taking off and landing even if demo controller is enabled. This variable WILL change automatically
-
-// controller used:
-int controller_used;
-
+// Publisher for which controller is currently being used
 ros::Publisher controllerUsedPublisher;
 
 
 
-float yaml_take_off_distance;
-float yaml_landing_distance;
-float yaml_duration_take_off;
-float yaml_duration_landing;
+// float yaml_take_off_distance;
+// float yaml_landing_distance;
+// float yaml_duration_take_off;
+// float yaml_duration_landing;
 
-bool finished_take_off = false;
-bool finished_land = false;
+// bool finished_take_off = false;
+// bool finished_land = false;
 
 ros::Timer timer_takeoff;
 ros::Timer timer_land;
@@ -250,17 +250,7 @@ ros::Timer timer_land;
 //    ----------------------------------------------------------------------------------
 
 
-// > For the LOAD PARAMETERS
-//void yamlReadyForFetchCallback(const std_msgs::Int32& msg);
-//void fetchYamlParametersForSafeController(ros::NodeHandle& nodeHandle);
-//void fetchClientConfigParameters(ros::NodeHandle& nodeHandle);
 
-// > For the LOADING of YAML PARAMETERS
-void isReadySafeControllerYamlCallback(const IntWithHeader & msg);
-void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle);
-
-void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
-void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
 
 
 
@@ -268,10 +258,16 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
 
 
 void viconCallback(const ViconData& viconData);
+int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index , CrazyflieData& pose);
+void coordinatesToLocal(CrazyflieData& cf);
+
 
 
+// > For the SAFETY CHECK on area and the angle
+bool safetyCheck(CrazyflieData data, ControlCommand controlCommand);
 
 
+void changeFlyingStateTo(int new_state);
 
 
 void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
@@ -279,34 +275,51 @@ void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
 
 
 
-void commandCallback(const IntWithHeader & commandMsg);
+void flyingStateRequestCallback(const IntWithHeader & commandMsg);
+
 
 
 
+// void loadSafeController();
+// void loadDemoController();
+// void loadStudentController();
+// void loadMpcController();
+// void loadRemoteController();
+// void loadTuningController();
+// void loadPickerController();
+// void loadTemplateController();
 
-void loadSafeController();
-void loadDemoController();
-void loadStudentController();
-void loadMpcController();
-void loadRemoteController();
-void loadTuningController();
-void loadPickerController();
-void loadTemplateController();
+void loadController( std::string paramter_name , ros::ServiceClient& serviceClient );
 
 void sendMessageUsingController(int controller);
 void setInstantController(int controller);
 int getInstantController();
-void setControllerUsed(int controller);
-int getControllerUsed();
+void setControllerNominallySelected(int controller);
+int getControllerNominallySelected();
+
+
+
+// THE CALLBACK THAT THE CRAZY RADIO STATUS CHANGED
+void crazyRadioStatusCallback(const std_msgs::Int32& msg);
 
+// THE CALLBACK THAT AN EMERGENCY STOP MESSAGE WAS RECEIVED
+void emergencyStopReceivedCallback(const IntWithHeader & msg);
 
-// > For the BATTERY
-//int getBatteryState();
-//void setBatteryStateTo(int new_battery_state);
-//float movingAverageBatteryFilter(float new_input);
-//void CFBatteryCallback(const std_msgs::Float32& msg);
+// THE SERVICE CALLBACK REQUESTING THE CURRENT FLYING STATE
+bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response);
+
+// FOR THE BATTERY STATE CALLBACK
 void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
 
+// FOR THE SAFETY CHECKS ON POSITION AND TILT ANGLE
+bool safetyCheck(CrazyflieData data);
+
+// THE CALLBACK THAT THE CONTEXT DATABASE CHANGED
+void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
 
-// > For the FLYING STATE
-bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response);
\ No newline at end of file
+// FOR LOADING THE CONTEXT OF THIS AGENT
+void loadCrazyflieContext();
+
+// FOR LOADING THE YAML PARAMETERS
+void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
+void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
index 779d2461..1d3c4806 100755
--- a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
@@ -1,4 +1,5 @@
 safeController:     "SafeControllerService/RateController"
+defaultController:  "DefaultControllerService/DefaultController"
 demoController:     "DemoControllerService/DemoController"
 studentController:  "StudentControllerService/StudentController"
 mpcController:      "MpcControllerService/MpcController"
@@ -7,9 +8,9 @@ tuningController:   "TuningControllerService/TuningController"
 pickerController:   "PickerControllerService/PickerController"
 templateController: "TemplateControllerService/TemplateController"
 
-# Flag for whether to use angle for switching to the Safe Controller
-strictSafety: false
-angleMargin: 0.8
+# Flag for whether to use angle for switching to the Default Controller
+isEnabled_strictSafety: true
+maxTiltAngle_for_strictSafety_degrees: 70
 
 battery_threshold_while_flying: 2.60       # in V
 battery_threshold_while_motors_off: 3.30   # in V
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index e4fab28c..2b51ea5b 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -1,4 +1,4 @@
-//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
 //
 //    This file is part of D-FaLL-System.
 //    
@@ -61,504 +61,443 @@
 
 
 
-//checks if crazyflie is within allowed area and if demo controller returns no data
-bool safetyCheck(CrazyflieData data, ControlCommand controlCommand) {
-	//position check
-	if((data.x < context.localArea.xmin) or (data.x > context.localArea.xmax)) {
-		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("[FLYING AGENT CLIENT] y safety failed");
-		return false;
-	}
-	if((data.z < context.localArea.zmin) or (data.z > context.localArea.zmax)) {
-		ROS_INFO_STREAM("[FLYING AGENT CLIENT] z safety failed");
-		return false;
-	}
 
-	//attitude check
-	//if strictSafety is set to true in ClientConfig.yaml the SafeController takes also over if the roll and pitch angles get to large
-	//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("[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("[FLYING AGENT CLIENT] pitch too big.");
-			return false;
-		}
-	}
 
-	return true;
-}
 
-void coordinatesToLocal(CrazyflieData& cf) {
-	AreaBounds area = context.localArea;
-	float originX = (area.xmin + area.xmax) / 2.0;
-	float originY = (area.ymin + area.ymax) / 2.0;
-    // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
-    float originZ = 0.0;
-	// float originZ = (area.zmin + area.zmax) / 2.0;
-
-	cf.x -= originX;
-	cf.y -= originY;
-	cf.z -= originZ;
-}
 
 
-void setCurrentSafeSetpoint(Setpoint setpoint)
-{
-    current_safe_setpoint = setpoint;
-}
 
-void calculateDistanceToCurrentSafeSetpoint(CrazyflieData& local)
-{
-    double dx = current_safe_setpoint.x - local.x;
-    double dy = current_safe_setpoint.y - local.y;
-    double dz = current_safe_setpoint.z - local.z;
 
-    distance = sqrt(pow(dx,2) + pow(dy,2) + pow(dz,2));
+// void takeOffCF(CrazyflieData& current_local_coordinates) //local because the setpoint is in local coordinates
+// {
+//     // set the setpoint and call safe controller
+//     Setpoint setpoint_msg;
+//     setpoint_msg.x = current_local_coordinates.x;           // previous one
+//     setpoint_msg.y = current_local_coordinates.y;           //previous one
+//     setpoint_msg.z = current_local_coordinates.z + yaml_take_off_distance;           //previous one plus some offset
+//     // setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
+//     setpoint_msg.yaw = 0.0;
+//     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
+//     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);
 
-    unit_vector[0] = dx/distance;
-    unit_vector[1] = dy/distance;
-    unit_vector[2] = dz/distance;
-}
+//     // now, use safe controller to go to that setpoint
+//     loadSafeController();
+//     setInstantController(SAFE_CONTROLLER);
+//     // when do we finish? after some time with delay?
 
+//     // update variable that keeps track of current setpoint
+//     setCurrentSafeSetpoint(setpoint_msg);
+// }
 
-void takeOffCF(CrazyflieData& current_local_coordinates) //local because the setpoint is in local coordinates
-{
-    // set the setpoint and call safe controller
-    Setpoint setpoint_msg;
-    setpoint_msg.x = current_local_coordinates.x;           // previous one
-    setpoint_msg.y = current_local_coordinates.y;           //previous one
-    setpoint_msg.z = current_local_coordinates.z + yaml_take_off_distance;           //previous one plus some offset
-    // setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
-    setpoint_msg.yaw = 0.0;
-    safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-    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();
-    setInstantController(SAFE_CONTROLLER);
-    // when do we finish? after some time with delay?
-
-    // update variable that keeps track of current setpoint
-    setCurrentSafeSetpoint(setpoint_msg);
-}
-
-void landCF(CrazyflieData& current_local_coordinates)
-{
-    // set the setpoint and call safe controller
-    Setpoint setpoint_msg;
-    setpoint_msg.x = current_local_coordinates.x;           // previous one
-    setpoint_msg.y = current_local_coordinates.y;           //previous one
-    setpoint_msg.z = yaml_landing_distance;           //previous one plus some offset
-    setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
-    safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-
-    // now, use safe controller to go to that setpoint
-    loadSafeController();
-    setInstantController(SAFE_CONTROLLER);
-    setCurrentSafeSetpoint(setpoint_msg);
-}
-
-void changeFlyingStateTo(int new_state)
-{
-    if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
-    {
-        ROS_INFO("[FLYING AGENT CLIENT] Change state to: %d", new_state);
-        flying_state = new_state;
-    }
-    else
-    {
-        ROS_INFO("[FLYING AGENT CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
-        flying_state = STATE_MOTORS_OFF;
-    }
+// void landCF(CrazyflieData& current_local_coordinates)
+// {
+//     // set the setpoint and call safe controller
+//     Setpoint setpoint_msg;
+//     setpoint_msg.x = current_local_coordinates.x;           // previous one
+//     setpoint_msg.y = current_local_coordinates.y;           //previous one
+//     setpoint_msg.z = yaml_landing_distance;           //previous one plus some offset
+//     setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
+//     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
 
-    changed_state_flag = true;
-    std_msgs::Int32 flying_state_msg;
-    flying_state_msg.data = flying_state;
-    flyingStatePublisher.publish(flying_state_msg);
-}
+//     // now, use safe controller to go to that setpoint
+//     loadSafeController();
+//     setInstantController(SAFE_CONTROLLER);
+//     setCurrentSafeSetpoint(setpoint_msg);
+// }
 
 
-void takeOffTimerCallback(const ros::TimerEvent&)
-{
-    finished_take_off = true;
-}
 
-void landTimerCallback(const ros::TimerEvent&)
-{
-    finished_land = true;
-}
 
-void goToControllerSetpoint()
-{
-    safeControllerServiceSetpointPublisher.publish(controller_setpoint);
-    setCurrentSafeSetpoint(controller_setpoint);
-}
+// void goToControllerSetpoint()
+// {
+//     safeControllerServiceSetpointPublisher.publish(controller_setpoint);
+//     setCurrentSafeSetpoint(controller_setpoint);
+// }
 
 
 //is called when new data from Vicon arrives
 void viconCallback(const ViconData& viconData)
 {
-	for(std::vector<CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it) {
-		CrazyflieData global = *it;
+    // NOTE: THIS FUNCTION IS CALL AT THE FREQUENCY OF THE MOTION
+    //       CAPTURE SYSTEM. HENCE ANY OPTERATIONS PERFORMED IN
+    //       THIS FUNCTION MUST BE NON-BLOCKING.
+
+    // Initilise a variable for the pose data of this agent
+    CrazyflieData poseDataForThisAgent;
+
+    // Extract the pose data from the full motion capture array
+    // NOTE: that if the return index is a negative then this
+    //       indicates that the pose data was not found.
+    m_poseDataIndex = getPoseDataForObjectNameWithExpectedIndex( viconData, m_context.crazyflieName , m_poseDataIndex , poseDataForThisAgent );
+
+
+
+    // switch(m_flying_state) 
+    // {
+    //     case STATE_MOTORS_OFF: // here we will put the code of current disabled button
+    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
+    //         {
+    //             m_changed_flying_state_flag = false;
+    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_MOTORS_OFF");
+    //         }
+    //         break;
+    //     case STATE_TAKE_OFF: //we need to move up from where we are now.
+    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
+    //         {
+    //             m_changed_flying_state_flag = false;
+    //             takeOffCF(local);
+    //             finished_take_off = false;
+    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_TAKE_OFF");
+    //             timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_take_off), takeOffTimerCallback, true);
+    //         }
+    //         if(finished_take_off)
+    //         {
+    //             finished_take_off = false;
+    //             setInstantController(getControllerNominallySelected());
+    //             changeFlyingStateTo(STATE_FLYING);
+    //         }
+    //         break;
+    //     case STATE_FLYING:
+    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
+    //         {
+    //             m_changed_flying_state_flag = false;
+    //             // need to change setpoint to the controller one
+    //             goToControllerSetpoint();
+    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_FLYING");
+    //         }
+    //         break;
+    //     case STATE_LAND:
+    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
+    //         {
+    //             m_changed_flying_state_flag = false;
+    //             landCF(local);
+    //             finished_land = false;
+    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_LAND");
+    //             timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_landing), landTimerCallback, true);
+    //         }
+    //         if(finished_land)
+    //         {
+    //             finished_land = false;
+    //             setInstantController(getControllerNominallySelected());
+    //             changeFlyingStateTo(STATE_MOTORS_OFF);
+    //         }
+    //         break;
+    //     default:
+    //         break;
+    // }
+
+    // Only continue if:
+    // (1) the pose for this agent was found, and
+    // (2) the flying state is something other than MOTORS-OFF
+    if (
+        (m_poseDataIndex >= 0)
+        and
+        (m_flying_state != STATE_MOTORS_OFF)
+        and
+        (m_controllers_avialble)
+    )
+    {
+        // Initliase the "Contrller" service call variable
+        Controller controllerCall;
 
-        if(global.crazyflieName == context.crazyflieName)
-        {
-            Controller controllerCall;
-            CrazyflieData local = global;
-            coordinatesToLocal(local);
-            controllerCall.request.ownCrazyflie = local;
+        // Fill in the pose data for this agent
+        controllerCall.request.ownCrazyflie = poseDataForThisAgent;
 
-            ros::NodeHandle nodeHandle("~");
+        // Initialise a node handle, needed for starting timers
+        ros::NodeHandle nodeHandle("~");
 
-            switch(flying_state) //things here repeat every X ms, non-blocking stuff
+        // If the object is NOT occluded,
+        // then proceed to make the "Controller Service Call" that
+        // compute the controller output.
+        if(!poseDataForThisAgent.occluded)
+        {
+            // PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
+            if ( getInstantController() != DEFAULT_CONTROLLER )
             {
-                case STATE_MOTORS_OFF: // here we will put the code of current disabled button
-                    if(changed_state_flag) // stuff that will be run only once when changing state
-                    {
-                        changed_state_flag = false;
-                        ROS_INFO("[FLYING AGENT CLIENT] STATE_MOTORS_OFF");
-                    }
-                    break;
-                case STATE_TAKE_OFF: //we need to move up from where we are now.
-                    if(changed_state_flag) // stuff that will be run only once when changing state
-                    {
-                        changed_state_flag = false;
-                        takeOffCF(local);
-                        finished_take_off = false;
-                        ROS_INFO("[FLYING AGENT CLIENT] STATE_TAKE_OFF");
-                        timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_take_off), takeOffTimerCallback, true);
-                    }
-                    if(finished_take_off)
-                    {
-                        finished_take_off = false;
-                        setInstantController(getControllerUsed());
-                        changeFlyingStateTo(STATE_FLYING);
-                    }
-                    break;
-                case STATE_FLYING:
-                    if(changed_state_flag) // stuff that will be run only once when changing state
-                    {
-                        changed_state_flag = false;
-                        // need to change setpoint to the controller one
-                        goToControllerSetpoint();
-                        ROS_INFO("[FLYING AGENT CLIENT] STATE_FLYING");
-                    }
-                    break;
-                case STATE_LAND:
-                    if(changed_state_flag) // stuff that will be run only once when changing state
-                    {
-                        changed_state_flag = false;
-                        landCF(local);
-                        finished_land = false;
-                        ROS_INFO("[FLYING AGENT CLIENT] STATE_LAND");
-                        timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_landing), landTimerCallback, true);
-                    }
-                    if(finished_land)
-                    {
-                        finished_land = false;
-                        setInstantController(getControllerUsed());
-                        changeFlyingStateTo(STATE_MOTORS_OFF);
-                    }
-                    break;
-                default:
-                    break;
+                if ( !safetyCheck(poseDataForThisAgent) )
+                {
+                    setInstantController(DEFAULT_CONTROLLER);
+                    ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to DEFAULT CONTROLLER");
+                }
             }
 
-            // control part that should always be running, calls to controller, computation of control output
-            if(flying_state != STATE_MOTORS_OFF)
+            // Initialise a local boolean success variable
+            bool isSuccessful_controllerCall = false;
+
+            // switch( getInstantController() )
+            // {
+            //     case DEFAULT_CONTROLLER
+            //         isSuccessful_controllerCall = defaultController.call(controllerCall);
+            //         break;
+            //     case DEMO_CONTROLLER:
+            //         isSuccessful_controllerCall = demoController.call(controllerCall);
+            //         break;
+            //     case STUDENT_CONTROLLER:
+            //         isSuccessful_controllerCall = studentController.call(controllerCall);
+            //         break;
+            //     case MPC_CONTROLLER:
+            //         isSuccessful_controllerCall = mpcController.call(controllerCall);
+            //         break;
+            //     case REMOTE_CONTROLLER:
+            //         isSuccessful_controllerCall = remoteController.call(controllerCall);
+            //         break;
+            //     case TUNING_CONTROLLER:
+            //         isSuccessful_controllerCall = tuningController.call(controllerCall);
+            //         break;
+            //     case PICKER_CONTROLLER:
+            //         isSuccessful_controllerCall = pickerController.call(controllerCall);
+            //         break;
+            //     case TEMPLATE_CONTROLLER:
+            //         isSuccessful_controllerCall = templateController.call(controllerCall);
+            //         break;
+            //     default:
+            //         ROS_ERROR("[FLYING AGENT CLIENT] the current controller was not recognised");
+            //         break;
+            // }
+
+
+            isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+
+            // Ensure success and enforce safety
+            if(!isSuccessful_controllerCall)
             {
-                if(!global.occluded)    //if it is not occluded, then proceed to compute the controller output.
+                //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());
+
+                // Let the user know that the controller call failed
+                ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+
+                // Switch to the default controller,
+                // if it was not already the active controller
+                if ( getInstantController() != DEFAULT_CONTROLLER )
                 {
-                    // Only call an "non-safe" controller if:
-                    // 1) we are not currently using safe controller, AND
-                    // 2) the flying state is FLYING
-                    if( (getInstantController() != SAFE_CONTROLLER) && (flying_state == STATE_FLYING) )
+                    // Set the DEFAULT controller to be active
+                    setInstantController(DEFAULT_CONTROLLER);
+                    // Try the controller call
+                    isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+                    // Inform the user is not successful
+                    if ( !isSuccessful_controllerCall )
                     {
-                        // Initialise a local boolean success variable
-                        bool success = false;
-
-                        switch(getInstantController())
-                        {
-                            case DEMO_CONTROLLER:
-                                success = demoController.call(controllerCall);
-                                break;
-                            case STUDENT_CONTROLLER:
-                                success = studentController.call(controllerCall);
-                                break;
-                            case MPC_CONTROLLER:
-                                success = mpcController.call(controllerCall);
-                                break;
-                            case REMOTE_CONTROLLER:
-                                success = remoteController.call(controllerCall);
-                                break;
-                            case TUNING_CONTROLLER:
-                                success = tuningController.call(controllerCall);
-                                break;
-                            case PICKER_CONTROLLER:
-                                success = pickerController.call(controllerCall);
-                                break;
-                            case TEMPLATE_CONTROLLER:
-                                success = templateController.call(controllerCall);
-                                break;
-                            default:
-                                ROS_ERROR("[FLYING AGENT CLIENT] the current controller was not recognised");
-                                break;
-                        }
-
-                        // Ensure success and enforce safety
-                        if(!success)
-                        {
-                            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("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
-                        }
-
-                        
+                        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Also failed to call the DEFAULT controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
                     }
-                    // SAFE_CONTROLLER and state is different from flying
-                    else
-                    {
-                        calculateDistanceToCurrentSafeSetpoint(local); // update distance, it also updates the unit vector
-                        // ROS_INFO_STREAM("distance: " << distance);
-                        // here, detect if euclidean distance between setpoint and current position is higher than a threshold
-                        if(distance > yaml_distance_threshold)
-                        {
-                            // DEBUGGING: display a message that the crazyflie is inside the thresholds
-                            //ROS_INFO("inside threshold");
-                            // Declare a local variable for the "setpoint message" to be published
-                            Setpoint setpoint_msg;
-                            // here, where we are now, or where we were in the beginning?
-                            setpoint_msg.x = local.x + yaml_distance_threshold * unit_vector[0];
-                            setpoint_msg.y = local.y + yaml_distance_threshold * unit_vector[1];
-                            setpoint_msg.z = local.z + yaml_distance_threshold * unit_vector[2];
-
-                            // yaw is better divided by the number of steps?
-                            setpoint_msg.yaw = current_safe_setpoint.yaw;
-                            safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-                            was_in_threshold = true;
-                        }
-                        else
-                        {
-                            if(was_in_threshold)
-                            {
-                                was_in_threshold = false;
-                                safeControllerServiceSetpointPublisher.publish(current_safe_setpoint);
-                                // goToControllerSetpoint(); //maybe this is a bit repetitive?
-                            }
-                        }
-
-                        bool success = safeController.call(controllerCall);
-                        if(!success) {
-                            ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
-                        }
-                    }
-
-
-                    controlCommandPublisher.publish(controllerCall.response.controlOutput);
-
-                    // Putting data into the ROS "bag" for post-analysis
-                    //bag.write("ViconData", ros::Time::now(), local);
-                    //bag.write("ControlOutput", ros::Time::now(), controllerCall.response.controlOutput);
                 }
             }
+
+            // Send the command to the CrazyRadio
+            // > IF SUCCESSFUL
+            if (isSuccessful_controllerCall)
+            {
+                commandForSendingToCrazyfliePublisher.publish(controllerCall.response.controlOutput);
+            }
+            // > ELSE SEND ZERO OUTPUT COMMAND
             else
             {
+                // Send the command to turn the motors off
                 ControlCommand zeroOutput = ControlCommand(); //everything set to zero
                 zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
-                controlCommandPublisher.publish(zeroOutput);
-
-                // Putting data into the ROS "bag" for post-analysis
-                //bag.write("ViconData", ros::Time::now(), local);
-                //bag.write("ControlOutput", ros::Time::now(), zeroOutput);
+                commandForSendingToCrazyfliePublisher.publish(zeroOutput);
+                // And change the state to motor-off
+                changeFlyingStateTo(STATE_MOTORS_OFF);
             }
-        }
-	}
-}
-
 
 
 
-void loadCrazyflieContext() {
-	CMQuery contextCall;
-	contextCall.request.studentID = m_agentID;
-	ROS_INFO_STREAM("[FLYING AGENT CLIENT] AgentID:" << m_agentID);
+            // else if(!safetyCheck(global, controllerCall.response.controlOutput))
+            // {
+            //     setInstantController(SAFE_CONTROLLER);
+            //     ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
+            // }
+
+
+
+            // // Ensure success and enforce safety
+            // if(!success)
+            // {
+            //     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("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
+            // }
+
+                
+            // }
+            // // SAFE_CONTROLLER and state is different from flying
+            // else
+            // {
+            //     calculateDistanceToCurrentSafeSetpoint(local); // update distance, it also updates the unit vector
+            //     // ROS_INFO_STREAM("distance: " << distance);
+            //     // here, detect if euclidean distance between setpoint and current position is higher than a threshold
+            //     if(distance > yaml_distance_threshold)
+            //     {
+            //         // DEBUGGING: display a message that the crazyflie is inside the thresholds
+            //         //ROS_INFO("inside threshold");
+            //         // Declare a local variable for the "setpoint message" to be published
+            //         Setpoint setpoint_msg;
+            //         // here, where we are now, or where we were in the beginning?
+            //         setpoint_msg.x = local.x + yaml_distance_threshold * unit_vector[0];
+            //         setpoint_msg.y = local.y + yaml_distance_threshold * unit_vector[1];
+            //         setpoint_msg.z = local.z + yaml_distance_threshold * unit_vector[2];
+
+            //         // yaw is better divided by the number of steps?
+            //         setpoint_msg.yaw = current_safe_setpoint.yaw;
+            //         safeControllerServiceSetpointPublisher.publish(setpoint_msg);
+            //         was_in_threshold = true;
+            //     }
+            //     else
+            //     {
+            //         if(was_in_threshold)
+            //         {
+            //             was_in_threshold = false;
+            //             safeControllerServiceSetpointPublisher.publish(current_safe_setpoint);
+            //             // goToControllerSetpoint(); //maybe this is a bit repetitive?
+            //         }
+            //     }
+
+            //     bool success = safeController.call(controllerCall);
+            //     if(!success) {
+            //         ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
+            //     }
+            // }
+
+            // Send the command to the CrazyRadio
+            //commandForSendingToCrazyfliePublisher.publish(controllerCall.response.controlOutput);
+
+        } // END OF: "if(!global.occluded)"
 
-    CrazyflieContext new_context;
+    }
+    else
+    {
+        // Send the command to turn the motors off
+        ControlCommand zeroOutput = ControlCommand(); //everything set to zero
+        zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
+        commandForSendingToCrazyfliePublisher.publish(zeroOutput);
 
-	centralManager.waitForExistence(ros::Duration(-1));
+	} // END OF: "if ( (m_poseDataIndex >= 0) and (m_flying_state != STATE_MOTORS_OFF) )"
 
-	if(centralManager.call(contextCall)) {
-		new_context = contextCall.response.crazyflieContext;
-		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
-        {
 
-            // Motors off is done in python script now everytime we disconnect
 
-            // send motors OFF and disconnect before setting context = new_context
-            // std_msgs::Int32 msg;
-            // msg.data = CMD_CRAZYFLY_MOTORS_OFF;
-            // commandPublisher.publish(msg);
 
-            ROS_INFO("[FLYING AGENT CLIENT] CF is now different for this student. Disconnect and turn it off");
 
-            IntWithHeader msg;
-            msg.shouldCheckForAgentID = false;
-            msg.data = CMD_DISCONNECT;
-            crazyRadioCommandPublisher.publish(msg);
+int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index , CrazyflieData& pose_to_fill_in)
+{
+    // Initialise an integer for the index where the object
+    // "name" is found
+    // > Initialise an negative to indicate not found
+    int object_index = -1;
+
+    // Get the length of the "pose data array"
+    int length_poseData = viconData.crazyflies.size();
+
+    // If the "expected index" is non-negative and less than
+    // the length of the data array, then attempt to check
+    // for a name match
+    if (
+        (0 <= expected_index)
+        and
+        (expected_index < length_poseData)
+    )
+    {
+        // Check if the names match
+        if (viconData.crazyflies[expected_index].crazyflieName == m_context.crazyflieName)
+        {
+            object_index = expected_index;
         }
+    }
 
-        context = new_context;
+    // If not found, then iterate the data array looking
+    // for a name match
+    if (object_index < 0)
+    {
+        for( int i=0 ; i<length_poseData ; i++ )
+        {    
+            // Check if the names match
+            if(viconData.crazyflies[i].crazyflieName == m_context.crazyflieName)
+            {
+                object_index = i;
+            }
+        }
+    }
 
-        ros::NodeHandle nh("CrazyRadio");
-        nh.setParam("crazyFlieAddress", context.crazyflieAddress);
-	}
+    // If not found, then retrun, else fill in the pose data
+    if (object_index < 0)
+    {
+        return object_index;
+    }
     else
     {
-		ROS_ERROR("[FLYING AGENT CLIENT] Failed to load context. Waiting for next Save in DB by teacher");
-	}
+        pose_to_fill_in = viconData.crazyflies[object_index];
+        coordinatesToLocal(pose_to_fill_in);
+        return object_index;
+    }
 }
 
 
+void coordinatesToLocal(CrazyflieData& cf)
+{
+    AreaBounds area = m_context.localArea;
+    float originX = (area.xmin + area.xmax) / 2.0;
+    float originY = (area.ymin + area.ymax) / 2.0;
+    // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
+    float originZ = 0.0;
+    // float originZ = (area.zmin + area.zmax) / 2.0;
 
-void commandCallback(const IntWithHeader & msg) {
+    cf.x -= originX;
+    cf.y -= originY;
+    cf.z -= originZ;
+}
 
-    // Check whether the message is relevant
-    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
 
-    // Continue if the message is relevant
-    if (isRevelant)
-    {
-        // Extract the data
-    	int cmd = msg.data;
 
-    	switch(cmd) {
-        	case CMD_USE_SAFE_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_SAFE_CONTROLLER Command received");
-                setControllerUsed(SAFE_CONTROLLER);
-        		break;
 
-        	case CMD_USE_DEMO_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_DEMO_CONTROLLER Command received");
-                setControllerUsed(DEMO_CONTROLLER);
-        		break;
 
-            case CMD_USE_STUDENT_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_STUDENT_CONTROLLER Command received");
-                setControllerUsed(STUDENT_CONTROLLER);
-                break;
 
-            case CMD_USE_MPC_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_MPC_CONTROLLER Command received");
-                setControllerUsed(MPC_CONTROLLER);
-                break;
 
-            case CMD_USE_REMOTE_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_REMOTE_CONTROLLER Command received");
-                setControllerUsed(REMOTE_CONTROLLER);
-                break;
 
-            case CMD_USE_TUNING_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_TUNING_CONTROLLER Command received");
-                setControllerUsed(TUNING_CONTROLLER);
-                break;
 
-            case CMD_USE_PICKER_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_PICKER_CONTROLLER Command received");
-                setControllerUsed(PICKER_CONTROLLER);
-                break;
-
-            case CMD_USE_TEMPLATE_CONTROLLER:
-                ROS_INFO("[FLYING AGENT CLIENT] USE_TEMPLATE_CONTROLLER Command received");
-                setControllerUsed(TEMPLATE_CONTROLLER);
-                break;
-
-        	case CMD_CRAZYFLY_TAKE_OFF:
-                ROS_INFO("[FLYING AGENT CLIENT] TAKE_OFF Command received");
-                if(flying_state == STATE_MOTORS_OFF)
-                {
-                    changeFlyingStateTo(STATE_TAKE_OFF);
-                }
-        		break;
-
-        	case CMD_CRAZYFLY_LAND:
-                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("[FLYING AGENT CLIENT] MOTORS_OFF Command received");
-                changeFlyingStateTo(STATE_MOTORS_OFF);
-                break;
-
-        	default:
-        		ROS_ERROR_STREAM("[FLYING AGENT CLIENT] unexpected command number: " << cmd);
-        		break;
-    	}
+void changeFlyingStateTo(int new_state)
+{
+    if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
+    {
+        ROS_INFO("[FLYING AGENT CLIENT] Change state to: %d", new_state);
+        m_flying_state = new_state;
+    }
+    else
+    {
+        ROS_INFO("[FLYING AGENT CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
+        m_flying_state = STATE_MOTORS_OFF;
     }
-}
 
-void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg)
-{
-    ROS_INFO("[FLYING AGENT CLIENT] Received message that the Context Database Changed");
-    loadCrazyflieContext();
-}
+    // Set the class variable flag that the
+    // flying state was changed
+    m_changed_flying_state_flag = true;
 
-void emergencyStopCallback(const IntWithHeader & msg)
-{
-    ROS_INFO("[FLYING AGENT CLIENT] Received message to EMERGENCY STOP");
-    commandCallback(msg);
+    // Publish a message with the new flying state
+    std_msgs::Int32 flying_state_msg;
+    flying_state_msg.data = m_flying_state;
+    flyingStatePublisher.publish(flying_state_msg);
 }
 
-//void commandAllAgentsCallback(const std_msgs::Int32& msg)
-//{
-//    commandCallback(msg);
-//}
 
-void crazyRadioStatusCallback(const std_msgs::Int32& msg)
-{
-    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)
-    //{
-    //    setBatteryStateTo(BATTERY_STATE_NORMAL);
-    //}
-}
-
-void controllerSetPointCallback(const Setpoint& newSetpoint)
+void takeOffTimerCallback(const ros::TimerEvent&)
 {
-    // load in variable the setpoint
-    controller_setpoint = newSetpoint;
-
-    // if we are in flying, set it up NOW
-    if(flying_state == STATE_FLYING)
-    {
-        goToControllerSetpoint();
-    }
+    //finished_take_off = true;
 }
 
-void safeSetPointCallback(const Setpoint& newSetpoint)
+void landTimerCallback(const ros::TimerEvent&)
 {
+    //finished_land = true;
 }
 
 
@@ -583,7 +522,6 @@ void safeSetPointCallback(const Setpoint& newSetpoint)
 
 
 
-
 
 
 //    ----------------------------------------------------------------------------------
@@ -598,204 +536,411 @@ void safeSetPointCallback(const Setpoint& newSetpoint)
 
 
 
-void loadSafeController() {
-    //ros::NodeHandle nodeHandle("~");
+// void loadSafeController() {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string safeControllerName;
+//     if(!nodeHandle.getParam("safeController", safeControllerName)) {
+//         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("[FLYING AGENT CLIENT] loaded safe controller: " << safeController.getService());
+// }
+
+// void loadDemoController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string demoControllerName;
+//     if(!nodeHandle.getParam("demoController", demoControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get demo controller name");
+//         return;
+//     }
+
+//     demoController = ros::service::createClient<Controller>(demoControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded demo controller " << demoController.getService());
+// }
+
+// void loadStudentController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string studentControllerName;
+//     if(!nodeHandle.getParam("studentController", studentControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get student controller name");
+//         return;
+//     }
+
+//     studentController = ros::service::createClient<Controller>(studentControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded student controller " << studentController.getService());
+// }
+
+// void loadMpcController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string mpcControllerName;
+//     if(!nodeHandle.getParam("mpcController", mpcControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get mpc controller name");
+//         return;
+//     }
+
+//     mpcController = ros::service::createClient<Controller>(mpcControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded mpc controller " << mpcController.getService());
+// }
+
+// void loadRemoteController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string remoteControllerName;
+//     if(!nodeHandle.getParam("remoteController", remoteControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get remote controller name");
+//         return;
+//     }
+
+//     remoteController = ros::service::createClient<Controller>(remoteControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded remote controller " << remoteController.getService());
+// }
+
+// void loadTuningController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string tuningControllerName;
+//     if(!nodeHandle.getParam("tuningController", tuningControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get tuning controller name");
+//         return;
+//     }
+
+//     tuningController = ros::service::createClient<Controller>(tuningControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded tuning controller " << tuningController.getService());
+// }
+
+// void loadPickerController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string pickerControllerName;
+//     if(!nodeHandle.getParam("pickerController", pickerControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get picker controller name");
+//         return;
+//     }
+
+//     pickerController = ros::service::createClient<Controller>(pickerControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded picker controller " << pickerController.getService());
+// }
+
+// void loadTemplateController()
+// {
+//     //ros::NodeHandle nodeHandle("~");
+//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+//     std::string templateControllerName;
+//     if(!nodeHandle.getParam("templateController", templateControllerName))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get template controller name");
+//         return;
+//     }
+
+//     templateController = ros::service::createClient<Controller>(templateControllerName, true);
+//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded template controller " << templateController.getService());
+// }
+
+
+
+
+
+// CREATE A SERVICE CLIENT
+// NOTE: the second argument is a boolean that specifies whether the 
+//       service is persistent or not. In the ROS documentation a
+//       persistent connection is described as:
+//   "Persistent connections should be used carefully. They greatly
+//    improve performance for repeated requests, but they also make
+//    your client more fragile to service failures. Clients using
+//    persistent connections should implement their own reconnection
+//    logic in the event that the persistent connection fails."
+void loadController( std::string paramter_name , ros::ServiceClient& serviceClient )
+{
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
-    std::string safeControllerName;
-    if(!nodeHandle.getParam("safeController", safeControllerName)) {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get safe controller name");
+    std::string controllerName;
+    if(!nodeHandle.getParam(paramter_name, controllerName))
+    {
+        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to get \"" << paramter_name << "\" paramter");
         return;
     }
 
-    ros::service::waitForService(safeControllerName);
-    safeController = ros::service::createClient<Controller>(safeControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] loaded safe controller: " << safeController.getService());
+    serviceClient = ros::service::createClient<Controller>(controllerName, true);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded service: " << serviceClient.getService() <<  ", valid: " << serviceClient.isValid() << ", exists: " << serviceClient.exists() );
 }
 
-void loadDemoController()
-{
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
-    std::string demoControllerName;
-    if(!nodeHandle.getParam("demoController", demoControllerName))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get demo controller name");
-        return;
-    }
 
-    demoController = ros::service::createClient<Controller>(demoControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded demo controller " << demoController.getService());
+
+
+void sendMessageUsingController(int controller)
+{
+    // Send a message on the topic for informing the Flying
+    // Agent GUI about this update
+    std_msgs::Int32 controller_used_msg;
+    controller_used_msg.data = controller;
+    controllerUsedPublisher.publish(controller_used_msg);
 }
 
-void loadStudentController()
+void setInstantController(int controller) //for right now, temporal use
 {
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    // Update the class variable
+    m_instant_controller = controller;
+
+    
 
-    std::string studentControllerName;
-    if(!nodeHandle.getParam("studentController", studentControllerName))
+    switch(controller)
     {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get student controller name");
-        return;
+        case DEFAULT_CONTROLLER:
+            m_instant_controller_service_client = &defaultController;
+            break;
+        case STUDENT_CONTROLLER:
+            m_instant_controller_service_client = &studentController;
+            break;
+        case TUNING_CONTROLLER:
+            m_instant_controller_service_client = &tuningController;
+            break;
+        case PICKER_CONTROLLER:
+            m_instant_controller_service_client = &pickerController;
+            break;
+        case TEMPLATE_CONTROLLER:
+            m_instant_controller_service_client = &templateController;
+            break;
+        default:
+            break;
     }
 
-    studentController = ros::service::createClient<Controller>(studentControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded student controller " << studentController.getService());
+    sendMessageUsingController(controller);
+    // switch(controller)
+    // {
+    //     case SAFE_CONTROLLER:
+    //         loadSafeController();
+    //         break;
+    //     case DEMO_CONTROLLER:
+    //         loadDemoController();
+    //         break;
+    //     case STUDENT_CONTROLLER:
+    //         loadStudentController();
+    //         break;
+    //     case MPC_CONTROLLER:
+    //         loadMpcController();
+    //         break;
+    //     case REMOTE_CONTROLLER:
+    //         loadRemoteController();
+    //         break;
+    //     case TUNING_CONTROLLER:
+    //         loadTuningController();
+    //         break;
+    //     case PICKER_CONTROLLER:
+    //         loadPickerController();
+    //         break;
+    //     case TEMPLATE_CONTROLLER:
+    //         loadTemplateController();
+    //         break;
+    //     default:
+    //         break;
+    // }
 }
 
-void loadMpcController()
+int getInstantController()
 {
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    return m_instant_controller;
+}
+
+void setControllerNominallySelected(int controller)
+{
+    // Update the class variable
+    m_controller_nominally_selected = controller;
 
-    std::string mpcControllerName;
-    if(!nodeHandle.getParam("mpcController", mpcControllerName))
+    // If in state "MOTORS-OFF" or "FLYING",
+    // then the change is instant.
+    if(m_flying_state == STATE_MOTORS_OFF || m_flying_state == STATE_FLYING)
     {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get mpc controller name");
-        return;
-    }
 
-    mpcController = ros::service::createClient<Controller>(mpcControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded mpc controller " << mpcController.getService());
+        setInstantController(controller); 
+    }
 }
 
-void loadRemoteController()
+int getControllerNominallySelected()
 {
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    return m_controller_nominally_selected;
+}
+
+
+
 
-    std::string remoteControllerName;
-    if(!nodeHandle.getParam("remoteController", remoteControllerName))
+
+
+
+
+
+
+void flyingStateRequestCallback(const IntWithHeader & msg) {
+
+    // Check whether the message is relevant
+    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
+
+    // Continue if the message is relevant
+    if (isRevelant)
     {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get remote controller name");
-        return;
+        // Extract the data
+        int cmd = msg.data;
+
+        switch(cmd) {
+            case CMD_USE_DEFAULT_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_DEFAULT_CONTROLLER Command received");
+                setControllerNominallySelected(DEFAULT_CONTROLLER);
+                break;
+
+            case CMD_USE_DEMO_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_DEMO_CONTROLLER Command received");
+                setControllerNominallySelected(DEMO_CONTROLLER);
+                break;
+
+            case CMD_USE_STUDENT_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_STUDENT_CONTROLLER Command received");
+                setControllerNominallySelected(STUDENT_CONTROLLER);
+                break;
+
+            case CMD_USE_MPC_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_MPC_CONTROLLER Command received");
+                setControllerNominallySelected(MPC_CONTROLLER);
+                break;
+
+            case CMD_USE_REMOTE_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_REMOTE_CONTROLLER Command received");
+                setControllerNominallySelected(REMOTE_CONTROLLER);
+                break;
+
+            case CMD_USE_TUNING_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_TUNING_CONTROLLER Command received");
+                setControllerNominallySelected(TUNING_CONTROLLER);
+                break;
+
+            case CMD_USE_PICKER_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_PICKER_CONTROLLER Command received");
+                setControllerNominallySelected(PICKER_CONTROLLER);
+                break;
+
+            case CMD_USE_TEMPLATE_CONTROLLER:
+                ROS_INFO("[FLYING AGENT CLIENT] USE_TEMPLATE_CONTROLLER Command received");
+                setControllerNominallySelected(TEMPLATE_CONTROLLER);
+                break;
+
+            case CMD_CRAZYFLY_TAKE_OFF:
+                ROS_INFO("[FLYING AGENT CLIENT] TAKE_OFF Command received");
+                if(m_flying_state == STATE_MOTORS_OFF)
+                {
+                    changeFlyingStateTo(STATE_TAKE_OFF);
+                }
+                break;
+
+            case CMD_CRAZYFLY_LAND:
+                ROS_INFO("[FLYING AGENT CLIENT] LAND Command received");
+                if(m_flying_state != STATE_MOTORS_OFF)
+                {
+                    changeFlyingStateTo(STATE_LAND);
+                }
+                break;
+            case CMD_CRAZYFLY_MOTORS_OFF:
+                ROS_INFO("[FLYING AGENT CLIENT] MOTORS_OFF Command received");
+                changeFlyingStateTo(STATE_MOTORS_OFF);
+                break;
+
+            default:
+                ROS_ERROR_STREAM("[FLYING AGENT CLIENT] unexpected command number: " << cmd);
+                break;
+        }
     }
+}
+
+
 
-    remoteController = ros::service::createClient<Controller>(remoteControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded remote controller " << remoteController.getService());
+
+
+
+
+
+void crazyRadioStatusCallback(const std_msgs::Int32& msg)
+{
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Received message with Crazy Radio Status = " << msg.data );
+    crazyradio_status = msg.data;
 }
 
-void loadTuningController()
-{
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
-    std::string tuningControllerName;
-    if(!nodeHandle.getParam("tuningController", tuningControllerName))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get tuning controller name");
-        return;
-    }
 
-    tuningController = ros::service::createClient<Controller>(tuningControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded tuning controller " << tuningController.getService());
-}
 
-void loadPickerController()
-{
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
-    std::string pickerControllerName;
-    if(!nodeHandle.getParam("pickerController", pickerControllerName))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get picker controller name");
-        return;
-    }
 
-    pickerController = ros::service::createClient<Controller>(pickerControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded picker controller " << pickerController.getService());
+void emergencyStopReceivedCallback(const IntWithHeader & msg)
+{
+    ROS_INFO("[FLYING AGENT CLIENT] Received message to EMERGENCY STOP");
+    flyingStateRequestCallback(msg);
 }
 
-void loadTemplateController()
-{
-    //ros::NodeHandle nodeHandle("~");
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
 
-    std::string templateControllerName;
-    if(!nodeHandle.getParam("templateController", templateControllerName))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get template controller name");
-        return;
-    }
 
-    templateController = ros::service::createClient<Controller>(templateControllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded template controller " << templateController.getService());
-}
 
-void sendMessageUsingController(int controller)
-{
-    // Send a message on the topic for informing the Flying
-    // Agent GUI about this update
-    std_msgs::Int32 controller_used_msg;
-    controller_used_msg.data = controller;
-    controllerUsedPublisher.publish(controller_used_msg);
-}
 
-void setInstantController(int controller) //for right now, temporal use
-{
-    instant_controller = controller;
-    sendMessageUsingController(controller);
-    switch(controller)
-    {
-        case SAFE_CONTROLLER:
-            loadSafeController();
-            break;
-        case DEMO_CONTROLLER:
-            loadDemoController();
-            break;
-        case STUDENT_CONTROLLER:
-            loadStudentController();
-            break;
-        case MPC_CONTROLLER:
-            loadMpcController();
-            break;
-        case REMOTE_CONTROLLER:
-            loadRemoteController();
-            break;
-        case TUNING_CONTROLLER:
-            loadTuningController();
-            break;
-        case PICKER_CONTROLLER:
-            loadPickerController();
-            break;
-        case TEMPLATE_CONTROLLER:
-            loadTemplateController();
-            break;
-        default:
-            break;
-    }
-}
 
-int getInstantController()
+//    ----------------------------------------------------------------------------------
+//     GGGG  EEEEE  TTTTT      SSSS  TTTTT    A    TTTTT  U   U   SSSS
+//    G      E        T       S        T     A A     T    U   U  S
+//    G      EEE      T        SSS     T    A   A    T    U   U   SSS
+//    G   G  E        T           S    T    AAAAA    T    U   U      S
+//     GGGG  EEEEE    T       SSSS     T    A   A    T     UUU   SSSS
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K   SSSS
+//    C       A A   L      L      B   B   A A   C      K  K   S
+//    C      A   A  L      L      BBBB   A   A  C      KKK     SSS
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K       S
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K  SSSS
+//    ----------------------------------------------------------------------------------
+
+bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response)
 {
-    return instant_controller;
+    // Put the flying state into the response variable
+    response.data = m_flying_state;
+    // Return
+    return true;
 }
 
-void setControllerUsed(int controller) //for permanent configs
-{
-    controller_used = controller;
 
-    if(flying_state == STATE_MOTORS_OFF || flying_state == STATE_FLYING)
-    {
-        setInstantController(controller); //if motors OFF or STATE FLYING, transparent, change is instant
-    }
-}
 
-int getControllerUsed()
-{
-    return controller_used;
-}
+
+
+
 
 
 
@@ -810,8 +955,6 @@ int getControllerUsed()
 //    BBBB   A   A    T      T    EEEEE  R   R    Y
 //    ----------------------------------------------------------------------------------
 
-
-
 void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
 {
     // Extract the data
@@ -820,7 +963,7 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
     // Take action if changed to low battery state
     if (new_battery_state == BATTERY_STATE_LOW)
     {
-        if (flying_state != STATE_MOTORS_OFF)
+        if (m_flying_state != STATE_MOTORS_OFF)
         {
             ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered, now landing.");
             changeFlyingStateTo(STATE_LAND);
@@ -843,126 +986,149 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
 
 
 
-/*
-int getBatteryState()
-{
-    return m_battery_state;
-}
 
 
-void setBatteryStateTo(int new_battery_state)
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS    A    FFFFF  EEEEE  TTTTT  Y   Y
+//    S       A A   F      E        T     Y Y
+//     SSS   A   A  FFF    EEE      T      Y
+//        S  AAAAA  F      E        T      Y
+//    SSSS   A   A  F      EEEEE    T      Y
+//
+//     CCCC  H   H  EEEEE   CCCC  K   K   SSSS
+//    C      H   H  E      C      K  K   S
+//    C      HHHHH  EEE    C      KKK     SSS
+//    C      H   H  E      C      K  K       S
+//     CCCC  H   H  EEEEE   CCCC  K   K  SSSS
+//    ----------------------------------------------------------------------------------
+
+// Checks if crazyflie is within allowed area
+bool safetyCheck(CrazyflieData data)
 {
-    switch(new_battery_state)
+    // Check on the X position
+    if((data.x < m_context.localArea.xmin) or (data.x > m_context.localArea.xmax))
     {
-        case BATTERY_STATE_NORMAL:
-            m_battery_state = BATTERY_STATE_NORMAL;
-            ROS_INFO("[FLYING AGENT CLIENT] changed battery state to normal");
-            break;
-        case BATTERY_STATE_LOW:
-            m_battery_state = BATTERY_STATE_LOW;
-            ROS_INFO("[FLYING AGENT CLIENT] changed battery state to low");
-            if(flying_state != STATE_MOTORS_OFF)
-                changeFlyingStateTo(STATE_LAND);
-            break;
-        default:
-            ROS_INFO("[FLYING AGENT CLIENT] Unknown battery state command, set to normal");
-            m_battery_state = BATTERY_STATE_NORMAL;
-            break;
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] x safety failed");
+        return false;
+    }
+    // Check on the Y position
+    if((data.y < m_context.localArea.ymin) or (data.y > m_context.localArea.ymax))
+    {
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] y safety failed");
+        return false;
+    }
+    // Check on the Z position
+    if((data.z < m_context.localArea.zmin) or (data.z > m_context.localArea.zmax))
+    {
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] z safety failed");
+        return false;
+    }
+
+    // Check the title angle (if required)
+    // > The tilt anlge between the body frame and inertial frame z-axis is
+    //   give by:
+    //   tilt angle  =  1 / ( cos(roll)*cos(pitch) )
+    // > But this would be too sensitve to a divide by zero error, so instead
+    //   we just check if each angle separately exceeds the limit
+    if(yaml_isEnabled_strictSafety)
+    {
+        // Check on the ROLL angle
+        if(
+            (data.roll > m_maxTiltAngle_for_strictSafety_redians)
+            or
+            (data.roll < -m_maxTiltAngle_for_strictSafety_redians)
+        )
+        {
+            ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
+            return false;
+        }
+        // Check on the PITCH angle
+        if(
+            (data.pitch > m_maxTiltAngle_for_strictSafety_redians)
+            or
+            (data.pitch < -m_maxTiltAngle_for_strictSafety_redians)
+        )
+        {
+            ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
+            return false;
+        }
     }
 
-    std_msgs::Int32 battery_state_msg;
-    battery_state_msg.data = getBatteryState();
-    batteryStatePublisher.publish(battery_state_msg);
+    // If the code makes it to here then all the safety checks passed,
+    // Hence return "true"
+    return true;
 }
 
-float movingAverageBatteryFilter(float new_input)
-{
-    const int N = 7;
-    static float previous_output = 4.2f;
-    static float inputs[N] = {4.2f,4.2f,4.2f,4.2f,4.2f,4.2f,4.2f};
 
 
-    // imagine an array of an even number of samples, we will output the one
-    // in the middle averaged with information from all of them.
-    // For that, we only need to store some past of the signal
-    float output = previous_output + new_input/N - inputs[N-1]/N;
 
-    // update array of inputs
-    for(int i = N - 1; i > 0; i--)
-    {
-        inputs[i] = inputs[i-1];
-    }
-    inputs[0] = new_input;
+
+//    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//     CCCC   OOO   N   N  TTTTT  EEEEE  X   X  TTTTT
+//    C      O   O  NN  N    T    E       X X     T
+//    C      O   O  N N N    T    EEE      X      T
+//    C      O   O  N  NN    T    E       X X     T
+//     CCCC   OOO   N   N    T    EEEEE  X   X    T
+//    ----------------------------------------------------------------------------------
 
 
-    // update previous output
-    previous_output = output;
-    return output;
+void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg)
+{
+    ROS_INFO("[FLYING AGENT CLIENT] Received message that the Context Database Changed");
+    loadCrazyflieContext();
 }
 
 
-void CFBatteryCallback(const std_msgs::Float32& msg)
+
+void loadCrazyflieContext()
 {
-    m_battery_voltage = msg.data;
-    // filter and check if inside limits, and if, change status
-    // need to do the filtering first
-    float filtered_battery_voltage = movingAverageBatteryFilter(m_battery_voltage); //need to perform filtering here
-
-    // ROS_INFO_STREAM("filtered data: " << filtered_battery_voltage);
-    if(
-        (flying_state != STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_flying))
-        ||
-        (flying_state == STATE_MOTORS_OFF && (filtered_battery_voltage < m_battery_threshold_while_motors_off))
-    )
-    {
-        if(getBatteryState() != BATTERY_STATE_LOW)
-        {
-            setBatteryStateTo(BATTERY_STATE_LOW);
-            ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered");
-        }
-        
-    }
-    else
-    {
-        // TO AVOID BEING ABLE TO IMMEDIATELY TAKE-OFF AFTER A
-        // "BATTERY LOW" EVENT IS TRIGGERED, WE DO NOT SET THE
-        // BATTERY STATE BACK TO NORMAL
-        // if(getBatteryState() != BATTERY_STATE_NORMAL)
-        // {
-        //     setBatteryStateTo(BATTERY_STATE_NORMAL);
-        // }
-    }
-}
-*/
+    CMQuery contextCall;
+    contextCall.request.studentID = m_agentID;
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] AgentID:" << m_agentID);
 
+    CrazyflieContext new_context;
 
+    centralManager.waitForExistence(ros::Duration(-1));
 
+    if(centralManager.call(contextCall)) {
+        new_context = contextCall.response.crazyflieContext;
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] CrazyflieContext:\n" << new_context);
 
+        if((m_context.crazyflieName != "") && (new_context.crazyflieName != m_context.crazyflieName)) //linked crazyflie name changed and it was not empty before
+        {
 
+            // Motors off is done in python script now everytime we disconnect
 
+            // send motors OFF and disconnect before setting m_context = new_context
+            // std_msgs::Int32 msg;
+            // msg.data = CMD_CRAZYFLY_MOTORS_OFF;
+            // commandPublisher.publish(msg);
 
+            ROS_INFO("[FLYING AGENT CLIENT] CF is now different for this student. Disconnect and turn it off");
 
+            IntWithHeader msg;
+            msg.shouldCheckForAgentID = false;
+            msg.data = CMD_DISCONNECT;
+            crazyRadioCommandPublisher.publish(msg);
+        }
 
-//    ----------------------------------------------------------------------------------
-//     GGGG  EEEEE  TTTTT      SSSS  TTTTT    A    TTTTT  U   U   SSSS
-//    G      E        T       S        T     A A     T    U   U  S
-//    G      EEE      T        SSS     T    A   A    T    U   U   SSS
-//    G   G  E        T           S    T    AAAAA    T    U   U      S
-//     GGGG  EEEEE    T       SSSS     T    A   A    T     UUU   SSSS
-//
-//     CCCC    A    L      L      BBBB     A     CCCC  K   K   SSSS
-//    C       A A   L      L      B   B   A A   C      K  K   S
-//    C      A   A  L      L      BBBB   A   A  C      KKK     SSS
-//    C      AAAAA  L      L      B   B  AAAAA  C      K  K       S
-//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K  SSSS
-//    ----------------------------------------------------------------------------------
+        m_context = new_context;
 
-bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response)
-{
-    // Put the flying state into the response variable
-    response.data = flying_state;
-    // Return
-    return true;
+        ros::NodeHandle nh("CrazyRadio");
+        nh.setParam("crazyFlieAddress", m_context.crazyflieAddress);
+    }
+    else
+    {
+        ROS_ERROR("[FLYING AGENT CLIENT] Failed to load context. Waiting for next Save in DB by teacher");
+    }
 }
 
 
@@ -971,7 +1137,6 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn
 
 
 
-
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
 //    L      O   O   A A   D   D
@@ -988,105 +1153,105 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn
 
 
 
-void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
-{
-    // Check whether the message is relevant
-    bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
-
-    // Continue if the message is relevant
-    if (isRevelant)
-    {
-        // Extract the data
-        int parameter_service_to_load_from = msg.data;
-        // Initialise a local variable for the namespace
-        std::string namespace_to_use;
-        // Load from the respective parameter service
-        switch(parameter_service_to_load_from)
-        {
-            // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-            case LOAD_YAML_FROM_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("[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("[FLYING AGENT CLIENT] Paramter service to load from was NOT recognised.");
-                namespace_to_use = m_namespace_to_own_agent_parameter_service;
-                break;
-            }
-        }
-        // Create a node handle to the selected parameter service
-        ros::NodeHandle nodeHandle_to_use(namespace_to_use);
-        // Call the function that fetches the parameters
-        fetchSafeControllerYamlParameters(nodeHandle_to_use);
-    }
-}
-
-
-
-void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
-{
-    // Here we load the parameters that are specified in the file:
-    // SafeController.yaml
-
-    // Add the "SafeController" namespace to the "nodeHandle"
-    ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "SafeController");
-
-    // take off and landing parameters (in meters and seconds)
-    yaml_take_off_distance = getParameterFloat(nodeHandle_for_paramaters,"takeOffDistance");
-    yaml_landing_distance = getParameterFloat(nodeHandle_for_paramaters,"landingDistance");
-    yaml_duration_take_off = getParameterFloat(nodeHandle_for_paramaters,"durationTakeOff");
-    yaml_duration_landing = getParameterFloat(nodeHandle_for_paramaters,"durationLanding");
-    yaml_distance_threshold = getParameterFloat(nodeHandle_for_paramaters,"distanceThreshold");
-
-    // setpoint in meters (x, y, z, yaw)
-    getParameterFloatVector(nodeHandle_for_paramaters,"defaultSetpoint",yaml_default_setpoint,4);
-
-    // DEBUGGING: Print out one of the parameters that was loaded
-    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
-
-    // Add the "SafeController" namespace to the "nodeHandle"
-    ros::NodeHandle nodeHandle_for_safeController(nodeHandle, "SafeController");
-
-    if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get takeOffDistance");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get landing_distance");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("durationTakeOff", duration_take_off))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_take_off");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_landing");
-    }
-
-    if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get distance_threshold");
-    }
-    */
-}
+// void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
+// {
+//     // Check whether the message is relevant
+//     bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
+
+//     // Continue if the message is relevant
+//     if (isRevelant)
+//     {
+//         // Extract the data
+//         int parameter_service_to_load_from = msg.data;
+//         // Initialise a local variable for the namespace
+//         std::string namespace_to_use;
+//         // Load from the respective parameter service
+//         switch(parameter_service_to_load_from)
+//         {
+//             // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+//             case LOAD_YAML_FROM_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("[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("[FLYING AGENT CLIENT] Paramter service to load from was NOT recognised.");
+//                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
+//                 break;
+//             }
+//         }
+//         // Create a node handle to the selected parameter service
+//         ros::NodeHandle nodeHandle_to_use(namespace_to_use);
+//         // Call the function that fetches the parameters
+//         fetchSafeControllerYamlParameters(nodeHandle_to_use);
+//     }
+// }
+
+
+
+// void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
+// {
+//     // Here we load the parameters that are specified in the file:
+//     // SafeController.yaml
+
+//     // Add the "SafeController" namespace to the "nodeHandle"
+//     ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "SafeController");
+
+//     // take off and landing parameters (in meters and seconds)
+//     yaml_take_off_distance = getParameterFloat(nodeHandle_for_paramaters,"takeOffDistance");
+//     yaml_landing_distance = getParameterFloat(nodeHandle_for_paramaters,"landingDistance");
+//     yaml_duration_take_off = getParameterFloat(nodeHandle_for_paramaters,"durationTakeOff");
+//     yaml_duration_landing = getParameterFloat(nodeHandle_for_paramaters,"durationLanding");
+//     yaml_distance_threshold = getParameterFloat(nodeHandle_for_paramaters,"distanceThreshold");
+
+//     // setpoint in meters (x, y, z, yaw)
+//     getParameterFloatVector(nodeHandle_for_paramaters,"defaultSetpoint",yaml_default_setpoint,4);
+
+//     // DEBUGGING: Print out one of the parameters that was loaded
+//     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
+
+//     // Add the "SafeController" namespace to the "nodeHandle"
+//     ros::NodeHandle nodeHandle_for_safeController(nodeHandle, "SafeController");
+
+//     if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get takeOffDistance");
+//     }
+
+//     if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get landing_distance");
+//     }
+
+//     if(!nodeHandle_for_safeController.getParam("durationTakeOff", duration_take_off))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_take_off");
+//     }
+
+//     if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_landing");
+//     }
+
+//     if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
+//     {
+//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get distance_threshold");
+//     }
+//     */
+// }
 
 
 
@@ -1147,40 +1312,44 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
     ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "ClientConfig");
 
     // Flag for whether to use angle for switching to the Safe Controller
-    yaml_strictSafety = getParameterBool(nodeHandle_for_paramaters,"strictSafety");
-    yaml_angleMargin = getParameterFloat(nodeHandle_for_paramaters,"angleMargin");
+    yaml_isEnabled_strictSafety = getParameterBool(nodeHandle_for_paramaters,"isEnabled_strictSafety");
+    yaml_maxTiltAngle_for_strictSafety_degrees = getParameterFloat(nodeHandle_for_paramaters,"maxTiltAngle_for_strictSafety_degrees");
     
-
-
     // DEBUGGING: Print out one of the parameters that was loaded
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched ClientConfig/strictSafety = " << yaml_strictSafety);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched ClientConfig/isEnabled_strictSafety = " << yaml_isEnabled_strictSafety);
 
 
-    /*
-    if(!nodeHandle.getParam("strictSafety", strictSafety)) {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get strictSafety param");
-        return;
-    }
-    if(!nodeHandle.getParam("angleMargin", angleMargin)) {
-        ROS_ERROR("[FLYING AGENT CLIENT] Failed to get angleMargin param");
-        return;
-    }
 
+    // PROCESS THE PARAMTERS
+    // Convert from degrees to radians
+    m_maxTiltAngle_for_strictSafety_redians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
 
-    if(!nodeHandle.getParam("battery_threshold_while_flying", m_battery_threshold_while_flying)) {
-        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("[FLYING AGENT CLIENT] Failed to get battery_threshold_while_motors_off param");
-        return;
-    }
-    */
+    // DEBUGGING: Print out one of the processed values
+    ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_redians = " << m_maxTiltAngle_for_strictSafety_redians);
 }
 
 
 
 
+void timerCallback_for_loadAllControllers(const ros::TimerEvent&)
+{
+    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
+    loadController( "defaultController"  , defaultController );
+    loadController( "studentController"  , studentController );
+    loadController( "tuningController"   , tuningController );
+    loadController( "pickerController"   , pickerController );
+    loadController( "templateController" , templateController );
+
+    if (defaultController)
+    {
+        m_controllers_avialble = true;
+    }
+    else
+    {
+        m_controllers_avialble = false;
+    }
+}
+
 
 //    ----------------------------------------------------------------------------------
 //    M   M    A    III  N   N
@@ -1250,8 +1419,8 @@ int main(int argc, char* argv[])
     ros::Subscriber clientConfig_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "ClientConfig", 1, isReadyClientConfigYamlCallback);
     ros::Subscriber clientConfig_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("ClientConfig", 1, isReadyClientConfigYamlCallback);
 
-    ros::Subscriber safeController_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "SafeController", 1, isReadySafeControllerYamlCallback);
-    ros::Subscriber safeController_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("SafeController", 1, isReadySafeControllerYamlCallback);
+    //ros::Subscriber safeController_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "SafeController", 1, isReadySafeControllerYamlCallback);
+    //ros::Subscriber safeController_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("SafeController", 1, isReadySafeControllerYamlCallback);
 
 
 
@@ -1266,53 +1435,19 @@ int main(int argc, char* argv[])
 
     // Call the class function that loads the parameters for this class.
     fetchClientConfigYamlParameters(nodeHandle_to_own_agent_parameter_service);
-    fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
-
-
-    // THIS IS THE "NEW" WAY TO DO IT
-    // BUT NEED TO CHECK ALL VARIABLES HAVE INITIAL VALUE
- //    // FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
-
-	// // The yaml files for the controllers are not added to
-	// // "Parameter Service" as part of launching.
-	// // The process for loading the yaml parameters is to send a
-	// // service call containing the filename of the *.yaml file,
-	// // and then a message will be received on the above subscribers
-	// // when the paramters are ready.
-	// // > NOTE IMPORTANTLY that by using a serice client
-	// //   we stall the availability of this node until the
-	// //   paramter service is ready
-
-	// // Create the service client as a local variable
-	// ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
-	// // Create the service call as a local variable
-	// LoadYamlFromFilename loadYamlFromFilenameCall;
-	// // Specify the Yaml filename as a string
-	// loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
-	// // Set for whom this applies to
-	// loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
-	// // Wait until the serivce exists
-	// requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
-	// // Make the service call
-	// if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
-	// {
-	// 	// Nothing to do in this case.
-	// 	// The "isReadyDefaultControllerYamlCallback" function
-	// 	// will be called once the YAML file is loaded
-	// }
-	// else
-	// {
-	// // Inform the user
-	// 	ROS_ERROR("[DEFAULT CONTROLLER] The request load yaml file service call failed.");
-	// }
-
-
-
-    // Copy the default setpoint into the class variable
-    controller_setpoint.x   = yaml_default_setpoint[0];
-    controller_setpoint.y   = yaml_default_setpoint[1];
-    controller_setpoint.z   = yaml_default_setpoint[2];
-    controller_setpoint.yaw = yaml_default_setpoint[3];
+    //fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
+
+
+    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
+    // loadController( "defaultController"  , defaultController );
+    // loadController( "studentController"  , studentController );
+    // loadController( "tuningController"   , tuningController );
+    // loadController( "pickerController"   , pickerController );
+    // loadController( "templateController" , templateController );
+    m_controllers_avialble = false;
+    timer_for_loadAllControllers = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_loadAllControllers, true);
+    
+
 
 
 
@@ -1343,7 +1478,7 @@ int main(int argc, char* argv[])
     ros::Subscriber databaseChangedSubscriber = nodeHandle_dfall_root.subscribe("CentralManagerService/DBChanged", 1, crazyflieContextDatabaseChangedCallback);
 
     // EMERGENCY STOP OF THE WHOLE "D-FaLL-System"
-    ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopCallback);
+    ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopReceivedCallback);
 
     // LOCALISATION DATA FROM MOTION CAPTURE SYSTEM
 	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
@@ -1354,7 +1489,7 @@ int main(int argc, char* argv[])
     // PUBLISHER FOR COMMANDING THE CRAZYFLIE
     // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
 	//ros::Publishers to advertise the control output
-	controlCommandPublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
+	commandForSendingToCrazyfliePublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
 	//this topic lets the FlyingAgentClient listen to the terminal commands
     //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
@@ -1364,9 +1499,9 @@ int main(int argc, char* argv[])
     // SUBSCRIBER FOR THE CHANGE STATE COMMANDS
     // i.e., {TAKE-OFF,LAND,MOTORS-OFF,CONTROLLER SELECTION}
     // > for the agent GUI
-    ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, commandCallback);
+    ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, flyingStateRequestCallback);
     // > for the coord GUI
-    ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("FlyingAgentClient/Command", 1, commandCallback);
+    ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("FlyingAgentClient/Command", 1, flyingStateRequestCallback);
 
 
 
@@ -1397,14 +1532,14 @@ int main(int argc, char* argv[])
 
     // publish first flying state data
     std_msgs::Int32 flying_state_msg;
-    flying_state_msg.data = flying_state;
+    flying_state_msg.data = m_flying_state;
     flyingStatePublisher.publish(flying_state_msg);
 
     // SafeControllerServicePublisher:
     ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
-    safeControllerServiceSetpointPublisher = namespaceNodeHandle.advertise<dfall_pkg::Setpoint>("SafeControllerService/Setpoint", 1);
-    ros::Subscriber controllerSetpointSubscriber = namespaceNodeHandle.subscribe("student_GUI/ControllerSetpoint", 1, controllerSetPointCallback);
-    ros::Subscriber safeSetpointSubscriber = namespaceNodeHandle.subscribe("SafeControllerService/Setpoint", 1, safeSetPointCallback);
+    //safeControllerServiceSetpointPublisher = namespaceNodeHandle.advertise<dfall_pkg::Setpoint>("SafeControllerService/Setpoint", 1);
+    //ros::Subscriber controllerSetpointSubscriber = namespaceNodeHandle.subscribe("student_GUI/ControllerSetpoint", 1, controllerSetPointCallback);
+    //ros::Subscriber safeSetpointSubscriber = namespaceNodeHandle.subscribe("SafeControllerService/Setpoint", 1, safeSetPointCallback);
 
     
 
@@ -1435,9 +1570,9 @@ int main(int argc, char* argv[])
 
 
 	//start with safe controller
-    flying_state = STATE_MOTORS_OFF;
-    setControllerUsed(SAFE_CONTROLLER);
-    setInstantController(SAFE_CONTROLLER); //initialize this also, so we notify GUI
+    m_flying_state = STATE_MOTORS_OFF;
+    setControllerNominallySelected(DEFAULT_CONTROLLER);
+    setInstantController(DEFAULT_CONTROLLER); //initialize this also, so we notify GUI
 
 
     // Advertise the service for the current flying state
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
index 216676d5..9a0545e3 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/MpcControllerService.cpp
@@ -653,46 +653,46 @@ void setpointCallback(const Setpoint& newSetpoint)
 // 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
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
-
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
-	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
-
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
-		}
-	}
+	// // Extract from the "msg" for which controller the and from where to fetch the YAML
+	// // parameters
+	// int controller_to_fetch_yaml = msg.data;
+
+	// // Switch between fetching for the different controllers and from different locations
+	// switch(controller_to_fetch_yaml)
+	// {
+
+	// 	// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+	// 	case FETCH_YAML_MPC_CONTROLLER_FROM_OWN_AGENT:
+	// 	{
+	// 		// Let the user know that this message was received
+	// 		ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
+	// 		// Create a node handle to the parameter service running on this agent's machine
+	// 		ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+	// 		// Call the function that fetches the parameters
+	// 		fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+	// 		break;
+	// 	}
+
+	// 	// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+	// 	case FETCH_YAML_MPC_CONTROLLER_FROM_COORDINATOR:
+	// 	{
+	// 		// Let the user know that this message was received
+	// 		ROS_INFO("[MPC CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
+	// 		// Create a node handle to the parameter service running on the coordinator machine
+	// 		ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
+	// 		// Call the function that fetches the parameters
+	// 		fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+	// 		break;
+	// 	}
+
+	// 	default:
+	// 	{
+	// 		// Let the user know that the command was not relevant
+	// 		//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
+	// 		//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
+	// 		break;
+	// 	}
+	// }
 }
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
index 2b980cbf..de85865d 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/RemoteControllerService.cpp
@@ -1214,46 +1214,46 @@ void setpointCallback(const Setpoint& newSetpoint)
 // 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
-	// parameters
-	int controller_to_fetch_yaml = msg.data;
-
-	// Switch between fetching for the different controllers and from different locations
-	switch(controller_to_fetch_yaml)
-	{
-
-		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-		case FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[REMOTE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
-			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-			break;
-		}
-
-		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-		case FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR:
-		{
-			// Let the user know that this message was received
-			ROS_INFO("[REMOTE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-			// Create a node handle to the parameter service running on the coordinator machine
-			ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
-
-		default:
-		{
-			// Let the user know that the command was not relevant
-			//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
-			//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
-			break;
-		}
-	}
+	// // Extract from the "msg" for which controller the and from where to fetch the YAML
+	// // parameters
+	// int controller_to_fetch_yaml = msg.data;
+
+	// // Switch between fetching for the different controllers and from different locations
+	// switch(controller_to_fetch_yaml)
+	// {
+
+	// 	// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+	// 	case FETCH_YAML_REMOTE_CONTROLLER_FROM_OWN_AGENT:
+	// 	{
+	// 		// Let the user know that this message was received
+	// 		ROS_INFO("[REMOTE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent.");
+	// 		// Create a node handle to the parameter service running on this agent's machine
+	// 		ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+	// 		// Call the function that fetches the parameters
+	// 		fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+	// 		break;
+	// 	}
+
+	// 	// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+	// 	case FETCH_YAML_REMOTE_CONTROLLER_FROM_COORDINATOR:
+	// 	{
+	// 		// Let the user know that this message was received
+	// 		ROS_INFO("[REMOTE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
+	// 		// Create a node handle to the parameter service running on the coordinator machine
+	// 		ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
+	// 		// Call the function that fetches the parameters
+	// 		fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+	// 		break;
+	// 	}
+
+	// 	default:
+	// 	{
+	// 		// Let the user know that the command was not relevant
+	// 		//ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded");
+	// 		//ROS_INFO("> However the parameters do not relate to this controller, hence nothing will be fetched.");
+	// 		break;
+	// 	}
+	// }
 }
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
index d1934a0f..e9f1c08c 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/SafeControllerService.cpp
@@ -235,45 +235,45 @@ void estimateState(Controller::Request &request, float (&est)[9])
 // 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
-    // parameters
-    int controller_to_fetch_yaml = msg.data;
-
-    // Switch between fetching for the different controllers and from different locations
-    switch(controller_to_fetch_yaml)
-    {
-
-        // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-        case FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT:
-        {
-            // Let the user know that this message was received
-            ROS_INFO("[SAFE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this machine.");
-            // Create a node handle to the parameter service running on this agent's machine
-            ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
-            // Call the function that fetches the parameters
-            fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
-            break;
-        }
-
-        // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
-        case FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR:
-        {
-            // Let the user know that this message was received
-            ROS_INFO("[SAFE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
-            // Create a node handle to the parameter service running on the coordinator machine
-            ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
-            // Call the function that fetches the parameters
-            fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-            break;
-        }
-
-        default:
-        {
-            // Let the user know that the command was not relevant
-            //ROS_INFO("The SafeControllerService received the message that YAML parameters were (re-)loaded.\r> However the parameters do not relate to this controller, hence nothing will be fetched.");
-            break;
-        }
-    }
+    // // Extract from the "msg" for which controller the and from where to fetch the YAML
+    // // parameters
+    // int controller_to_fetch_yaml = msg.data;
+
+    // // Switch between fetching for the different controllers and from different locations
+    // switch(controller_to_fetch_yaml)
+    // {
+
+    //     // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+    //     case FETCH_YAML_SAFE_CONTROLLER_FROM_OWN_AGENT:
+    //     {
+    //         // Let the user know that this message was received
+    //         ROS_INFO("[SAFE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this machine.");
+    //         // Create a node handle to the parameter service running on this agent's machine
+    //         ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
+    //         // Call the function that fetches the parameters
+    //         fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
+    //         break;
+    //     }
+
+    //     // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+    //     case FETCH_YAML_SAFE_CONTROLLER_FROM_COORDINATOR:
+    //     {
+    //         // Let the user know that this message was received
+    //         ROS_INFO("[SAFE CONTROLLER] Received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator.");
+    //         // Create a node handle to the parameter service running on the coordinator machine
+    //         ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service);
+    //         // Call the function that fetches the parameters
+    //         fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+    //         break;
+    //     }
+
+    //     default:
+    //     {
+    //         // Let the user know that the command was not relevant
+    //         //ROS_INFO("The SafeControllerService received the message that YAML parameters were (re-)loaded.\r> However the parameters do not relate to this controller, hence nothing will be fetched.");
+    //         break;
+    //     }
+    // }
 }
 
 void fetchYamlParameters(ros::NodeHandle& nodeHandle)
-- 
GitLab


From 134add5833eb6517bcb9293a0a441410851e5f0b Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 23:57:29 +0100
Subject: [PATCH 76/87] Add bits and pieces to the Slying Agent client for
 checking availability and occulsion of mocap data. Needs compiling and
 teesting

---
 dfall_ws/src/dfall_pkg/launch/Config.sh       |   4 +-
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp | 605 ++++--------------
 2 files changed, 140 insertions(+), 469 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/launch/Config.sh b/dfall_ws/src/dfall_pkg/launch/Config.sh
index 3a8fb387..98cd6dfe 100755
--- a/dfall_ws/src/dfall_pkg/launch/Config.sh
+++ b/dfall_ws/src/dfall_pkg/launch/Config.sh
@@ -1,7 +1,7 @@
 # TO RUN THE SYSTEM FULLY ON THE LOCAL COMPUTER:
-# export ROS_MASTER_URI=http://localhost:11311
+export ROS_MASTER_URI=http://localhost:11311
 # TO RUN THE SYSTEM ON A DEFAULT CONFIGURATION OF THE NETWROK:
-export ROS_MASTER_URI=http://teacher:11311
+#export ROS_MASTER_URI=http://teacher:11311
 # OTHER NECESSARY ENVIRONMENT VARIABLES:
 export ROS_IP=$(hostname -I | awk '{print $1;}')
 export DFALL_DEFAULT_AGENT_ID=$(cat /etc/dfall_default_agent_id)
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 2b51ea5b..00a01201 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -126,6 +126,10 @@ void viconCallback(const ViconData& viconData)
     //       CAPTURE SYSTEM. HENCE ANY OPTERATIONS PERFORMED IN
     //       THIS FUNCTION MUST BE NON-BLOCKING.
 
+    // Initialise a counter of consecutive frames of motion
+    // capture data where the agent is occuled
+    static int number_of_consecutive_occulsions = 0;
+
     // Initilise a variable for the pose data of this agent
     CrazyflieData poseDataForThisAgent;
 
@@ -135,60 +139,16 @@ void viconCallback(const ViconData& viconData)
     m_poseDataIndex = getPoseDataForObjectNameWithExpectedIndex( viconData, m_context.crazyflieName , m_poseDataIndex , poseDataForThisAgent );
 
 
+    // Detecting time-out of the motion capture data
+    // > Update the flag
+    m_isAvailable_mocap_data = true;
+    // > Stop any previous instance that might still be running
+    m_timer_mocap_timeout_check.stop();
+    // > Set the period again (second argument is reset)
+    m_timer_mocap_timeout_check.setPeriod( ros::Duration(yaml_mocap_timeout_duration), true);
+    // > Start the timer again
+    m_timer_mocap_timeout_check.start();
 
-    // switch(m_flying_state) 
-    // {
-    //     case STATE_MOTORS_OFF: // here we will put the code of current disabled button
-    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
-    //         {
-    //             m_changed_flying_state_flag = false;
-    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_MOTORS_OFF");
-    //         }
-    //         break;
-    //     case STATE_TAKE_OFF: //we need to move up from where we are now.
-    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
-    //         {
-    //             m_changed_flying_state_flag = false;
-    //             takeOffCF(local);
-    //             finished_take_off = false;
-    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_TAKE_OFF");
-    //             timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_take_off), takeOffTimerCallback, true);
-    //         }
-    //         if(finished_take_off)
-    //         {
-    //             finished_take_off = false;
-    //             setInstantController(getControllerNominallySelected());
-    //             changeFlyingStateTo(STATE_FLYING);
-    //         }
-    //         break;
-    //     case STATE_FLYING:
-    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
-    //         {
-    //             m_changed_flying_state_flag = false;
-    //             // need to change setpoint to the controller one
-    //             goToControllerSetpoint();
-    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_FLYING");
-    //         }
-    //         break;
-    //     case STATE_LAND:
-    //         if(m_changed_flying_state_flag) // stuff that will be run only once when changing state
-    //         {
-    //             m_changed_flying_state_flag = false;
-    //             landCF(local);
-    //             finished_land = false;
-    //             ROS_INFO("[FLYING AGENT CLIENT] STATE_LAND");
-    //             timer_takeoff = nodeHandle.createTimer(ros::Duration(yaml_duration_landing), landTimerCallback, true);
-    //         }
-    //         if(finished_land)
-    //         {
-    //             finished_land = false;
-    //             setInstantController(getControllerNominallySelected());
-    //             changeFlyingStateTo(STATE_MOTORS_OFF);
-    //         }
-    //         break;
-    //     default:
-    //         break;
-    // }
 
     // Only continue if:
     // (1) the pose for this agent was found, and
@@ -215,6 +175,9 @@ void viconCallback(const ViconData& viconData)
         // compute the controller output.
         if(!poseDataForThisAgent.occluded)
         {
+        	// Reset the "consecutive occulsions" flag
+        	number_of_consecutive_occulsions = 0;
+
             // PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
             if ( getInstantController() != DEFAULT_CONTROLLER )
             {
@@ -228,36 +191,6 @@ void viconCallback(const ViconData& viconData)
             // Initialise a local boolean success variable
             bool isSuccessful_controllerCall = false;
 
-            // switch( getInstantController() )
-            // {
-            //     case DEFAULT_CONTROLLER
-            //         isSuccessful_controllerCall = defaultController.call(controllerCall);
-            //         break;
-            //     case DEMO_CONTROLLER:
-            //         isSuccessful_controllerCall = demoController.call(controllerCall);
-            //         break;
-            //     case STUDENT_CONTROLLER:
-            //         isSuccessful_controllerCall = studentController.call(controllerCall);
-            //         break;
-            //     case MPC_CONTROLLER:
-            //         isSuccessful_controllerCall = mpcController.call(controllerCall);
-            //         break;
-            //     case REMOTE_CONTROLLER:
-            //         isSuccessful_controllerCall = remoteController.call(controllerCall);
-            //         break;
-            //     case TUNING_CONTROLLER:
-            //         isSuccessful_controllerCall = tuningController.call(controllerCall);
-            //         break;
-            //     case PICKER_CONTROLLER:
-            //         isSuccessful_controllerCall = pickerController.call(controllerCall);
-            //         break;
-            //     case TEMPLATE_CONTROLLER:
-            //         isSuccessful_controllerCall = templateController.call(controllerCall);
-            //         break;
-            //     default:
-            //         ROS_ERROR("[FLYING AGENT CLIENT] the current controller was not recognised");
-            //         break;
-            // }
 
 
             isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
@@ -265,10 +198,6 @@ void viconCallback(const ViconData& viconData)
             // Ensure success and enforce safety
             if(!isSuccessful_controllerCall)
             {
-                //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());
-
                 // Let the user know that the controller call failed
                 ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
 
@@ -292,95 +221,42 @@ void viconCallback(const ViconData& viconData)
             // > IF SUCCESSFUL
             if (isSuccessful_controllerCall)
             {
-                commandForSendingToCrazyfliePublisher.publish(controllerCall.response.controlOutput);
+                m_commaNdfOrsendiNgTocrazyflIepublisher.publish(controllerCall.response.controlOutput);
             }
             // > ELSE SEND ZERO OUTPUT COMMAND
             else
             {
                 // Send the command to turn the motors off
-                ControlCommand zeroOutput = ControlCommand(); //everything set to zero
-                zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
-                commandForSendingToCrazyfliePublisher.publish(zeroOutput);
+                sendZeroOutputCommandForMotors();
                 // And change the state to motor-off
                 changeFlyingStateTo(STATE_MOTORS_OFF);
             }
-
-
-
-            // else if(!safetyCheck(global, controllerCall.response.controlOutput))
-            // {
-            //     setInstantController(SAFE_CONTROLLER);
-            //     ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
-            // }
-
-
-
-            // // Ensure success and enforce safety
-            // if(!success)
-            // {
-            //     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("[FLYING AGENT CLIENT] safety check failed, switching to safe controller");
-            // }
-
-                
-            // }
-            // // SAFE_CONTROLLER and state is different from flying
-            // else
-            // {
-            //     calculateDistanceToCurrentSafeSetpoint(local); // update distance, it also updates the unit vector
-            //     // ROS_INFO_STREAM("distance: " << distance);
-            //     // here, detect if euclidean distance between setpoint and current position is higher than a threshold
-            //     if(distance > yaml_distance_threshold)
-            //     {
-            //         // DEBUGGING: display a message that the crazyflie is inside the thresholds
-            //         //ROS_INFO("inside threshold");
-            //         // Declare a local variable for the "setpoint message" to be published
-            //         Setpoint setpoint_msg;
-            //         // here, where we are now, or where we were in the beginning?
-            //         setpoint_msg.x = local.x + yaml_distance_threshold * unit_vector[0];
-            //         setpoint_msg.y = local.y + yaml_distance_threshold * unit_vector[1];
-            //         setpoint_msg.z = local.z + yaml_distance_threshold * unit_vector[2];
-
-            //         // yaw is better divided by the number of steps?
-            //         setpoint_msg.yaw = current_safe_setpoint.yaw;
-            //         safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-            //         was_in_threshold = true;
-            //     }
-            //     else
-            //     {
-            //         if(was_in_threshold)
-            //         {
-            //             was_in_threshold = false;
-            //             safeControllerServiceSetpointPublisher.publish(current_safe_setpoint);
-            //             // goToControllerSetpoint(); //maybe this is a bit repetitive?
-            //         }
-            //     }
-
-            //     bool success = safeController.call(controllerCall);
-            //     if(!success) {
-            //         ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
-            //     }
-            // }
-
-            // Send the command to the CrazyRadio
-            //commandForSendingToCrazyfliePublisher.publish(controllerCall.response.controlOutput);
-
+		}
+		else
+		{
+			// Increment the number of consective occulations
+			number_of_consecutive_occulsions++;
+			// Update the flag if this exceeds the threshold
+			if (
+				(!m_isOcculded_mocap_data)
+				and
+				(number_of_consecutive_occulsions > yaml_consecutive_occulsions_threshold)
+			)
+			{
+				// Update the flag
+				m_isOcculded_mocap_data = true;
+				// Send the command to turn the motors off
+		        sendZeroOutputCommandForMotors();
+		        // Update the flying state
+		        changeFlyingStateTo( STATE_MOTORS_OFF );
+			}
         } // END OF: "if(!global.occluded)"
 
     }
     else
     {
         // Send the command to turn the motors off
-        ControlCommand zeroOutput = ControlCommand(); //everything set to zero
-        zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
-        commandForSendingToCrazyfliePublisher.publish(zeroOutput);
+        sendZeroOutputCommandForMotors();
 
 	} // END OF: "if ( (m_poseDataIndex >= 0) and (m_flying_state != STATE_MOTORS_OFF) )"
 
@@ -459,6 +335,31 @@ void coordinatesToLocal(CrazyflieData& cf)
 }
 
 
+void timerCallback_mocap_timeout_check(const ros::TimerEvent&)
+{
+	// Update the flag
+	m_isAvailable_mocap_data = true;
+	// Inform the user
+	ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Motion Capture Data has been unavailable for " << yaml_mocap_timeout_duration << " seconds." );
+	// Ensure that the motors are turned off
+	if ( !(m_flying_state==STATE_MOTORS_OFF) )
+	{
+		// Send the command to turn the motors off
+        sendZeroOutputCommandForMotors();
+        // Update the flying state
+        changeFlyingStateTo( STATE_MOTORS_OFF );
+	}
+}
+
+
+void sendZeroOutputCommandForMotors()
+{
+	ControlCommand zeroOutput = ControlCommand(); //everything set to zero
+    zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
+    m_commaNdfOrsendiNgTocrazyflIepublisher.publish(zeroOutput);
+}
+
+
 
 
 
@@ -471,7 +372,7 @@ void changeFlyingStateTo(int new_state)
     if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
     {
         ROS_INFO("[FLYING AGENT CLIENT] Change state to: %d", new_state);
-        m_flying_state = new_state;
+        m_flying_state== = new_state;
     }
     else
     {
@@ -481,7 +382,7 @@ void changeFlyingStateTo(int new_state)
 
     // Set the class variable flag that the
     // flying state was changed
-    m_changed_flying_state_flag = true;
+    //m_changed_flying_state_flag = true;
 
     // Publish a message with the new flying state
     std_msgs::Int32 flying_state_msg;
@@ -525,6 +426,13 @@ void landTimerCallback(const ros::TimerEvent&)
 
 
 //    ----------------------------------------------------------------------------------
+//    L       OOO     A    DDDD
+//    L      O   O   A A   D   D
+//    L      O   O  A   A  D   D
+//    L      O   O  AAAAA  D   D
+//    LLLLL   OOO   A   A  DDDD
+//
+//
 //     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
 //    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
 //    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
@@ -533,150 +441,9 @@ void landTimerCallback(const ros::TimerEvent&)
 //    ----------------------------------------------------------------------------------
 
 
-
-
-
-// void loadSafeController() {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string safeControllerName;
-//     if(!nodeHandle.getParam("safeController", safeControllerName)) {
-//         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("[FLYING AGENT CLIENT] loaded safe controller: " << safeController.getService());
-// }
-
-// void loadDemoController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string demoControllerName;
-//     if(!nodeHandle.getParam("demoController", demoControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get demo controller name");
-//         return;
-//     }
-
-//     demoController = ros::service::createClient<Controller>(demoControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded demo controller " << demoController.getService());
-// }
-
-// void loadStudentController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string studentControllerName;
-//     if(!nodeHandle.getParam("studentController", studentControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get student controller name");
-//         return;
-//     }
-
-//     studentController = ros::service::createClient<Controller>(studentControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded student controller " << studentController.getService());
-// }
-
-// void loadMpcController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string mpcControllerName;
-//     if(!nodeHandle.getParam("mpcController", mpcControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get mpc controller name");
-//         return;
-//     }
-
-//     mpcController = ros::service::createClient<Controller>(mpcControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded mpc controller " << mpcController.getService());
-// }
-
-// void loadRemoteController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string remoteControllerName;
-//     if(!nodeHandle.getParam("remoteController", remoteControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get remote controller name");
-//         return;
-//     }
-
-//     remoteController = ros::service::createClient<Controller>(remoteControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded remote controller " << remoteController.getService());
-// }
-
-// void loadTuningController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string tuningControllerName;
-//     if(!nodeHandle.getParam("tuningController", tuningControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get tuning controller name");
-//         return;
-//     }
-
-//     tuningController = ros::service::createClient<Controller>(tuningControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded tuning controller " << tuningController.getService());
-// }
-
-// void loadPickerController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string pickerControllerName;
-//     if(!nodeHandle.getParam("pickerController", pickerControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get picker controller name");
-//         return;
-//     }
-
-//     pickerController = ros::service::createClient<Controller>(pickerControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded picker controller " << pickerController.getService());
-// }
-
-// void loadTemplateController()
-// {
-//     //ros::NodeHandle nodeHandle("~");
-//     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-//     ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
-
-//     std::string templateControllerName;
-//     if(!nodeHandle.getParam("templateController", templateControllerName))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get template controller name");
-//         return;
-//     }
-
-//     templateController = ros::service::createClient<Controller>(templateControllerName, true);
-//     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded template controller " << templateController.getService());
-// }
-
-
-
-
-
-// CREATE A SERVICE CLIENT
-// NOTE: the second argument is a boolean that specifies whether the 
+// CREATE A "CONTROLLER" TYPE SERVICE CLIENT
+// NOTE: that in the "ros::service::createClient" function the
+//       second argument is a boolean that specifies whether the 
 //       service is persistent or not. In the ROS documentation a
 //       persistent connection is described as:
 //   "Persistent connections should be used carefully. They greatly
@@ -702,6 +469,49 @@ void loadController( std::string paramter_name , ros::ServiceClient& serviceClie
 
 
 
+void timerCallback_for_creaTeaLlcontrollerServiceClients(const ros::TimerEvent&)
+{
+    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
+    loadController( "defaultController"  , defaultController );
+    loadController( "studentController"  , studentController );
+    loadController( "tuningController"   , tuningController );
+    loadController( "pickerController"   , pickerController );
+    loadController( "templateController" , templateController );
+
+    // Check that at least the default controller is available
+    // > Setting the flag accordingly
+    if (defaultController)
+    {
+        m_controllers_avialble = true;
+    }
+    else
+    {
+        m_controllers_avialble = false;
+        // Inform the user of the problem
+        ROS_ERROR("[FLYING AGENT CLIENT] The default controller service client (and pressumably all other controllers) could NOT be created.");
+    }
+}
+
+
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//     SSSS  EEEEE  L      EEEEE   CCCC  TTTTT
+//    S      E      L      E      C        T
+//     SSS   EEE    L      EEE    C        T
+//        S  E      L      E      C        T
+//    SSSS   EEEEE  LLLLL  EEEEE   CCCC    T
+//
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
+//    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
+//    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
+//    C      O   O  N  NN    T    R   R  O   O  L      L      E      R   R
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL  LLLLL  EEEEE  R   R
+//    ----------------------------------------------------------------------------------
+
 
 
 void sendMessageUsingController(int controller)
@@ -742,35 +552,6 @@ void setInstantController(int controller) //for right now, temporal use
     }
 
     sendMessageUsingController(controller);
-    // switch(controller)
-    // {
-    //     case SAFE_CONTROLLER:
-    //         loadSafeController();
-    //         break;
-    //     case DEMO_CONTROLLER:
-    //         loadDemoController();
-    //         break;
-    //     case STUDENT_CONTROLLER:
-    //         loadStudentController();
-    //         break;
-    //     case MPC_CONTROLLER:
-    //         loadMpcController();
-    //         break;
-    //     case REMOTE_CONTROLLER:
-    //         loadRemoteController();
-    //         break;
-    //     case TUNING_CONTROLLER:
-    //         loadTuningController();
-    //         break;
-    //     case PICKER_CONTROLLER:
-    //         loadPickerController();
-    //         break;
-    //     case TEMPLATE_CONTROLLER:
-    //         loadTemplateController();
-    //         break;
-    //     default:
-    //         break;
-    // }
 }
 
 int getInstantController()
@@ -1152,110 +933,6 @@ void loadCrazyflieContext()
 //    ----------------------------------------------------------------------------------
 
 
-
-// void isReadySafeControllerYamlCallback(const IntWithHeader & msg)
-// {
-//     // Check whether the message is relevant
-//     bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
-
-//     // Continue if the message is relevant
-//     if (isRevelant)
-//     {
-//         // Extract the data
-//         int parameter_service_to_load_from = msg.data;
-//         // Initialise a local variable for the namespace
-//         std::string namespace_to_use;
-//         // Load from the respective parameter service
-//         switch(parameter_service_to_load_from)
-//         {
-//             // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
-//             case LOAD_YAML_FROM_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("[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("[FLYING AGENT CLIENT] Paramter service to load from was NOT recognised.");
-//                 namespace_to_use = m_namespace_to_own_agent_parameter_service;
-//                 break;
-//             }
-//         }
-//         // Create a node handle to the selected parameter service
-//         ros::NodeHandle nodeHandle_to_use(namespace_to_use);
-//         // Call the function that fetches the parameters
-//         fetchSafeControllerYamlParameters(nodeHandle_to_use);
-//     }
-// }
-
-
-
-// void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle)
-// {
-//     // Here we load the parameters that are specified in the file:
-//     // SafeController.yaml
-
-//     // Add the "SafeController" namespace to the "nodeHandle"
-//     ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "SafeController");
-
-//     // take off and landing parameters (in meters and seconds)
-//     yaml_take_off_distance = getParameterFloat(nodeHandle_for_paramaters,"takeOffDistance");
-//     yaml_landing_distance = getParameterFloat(nodeHandle_for_paramaters,"landingDistance");
-//     yaml_duration_take_off = getParameterFloat(nodeHandle_for_paramaters,"durationTakeOff");
-//     yaml_duration_landing = getParameterFloat(nodeHandle_for_paramaters,"durationLanding");
-//     yaml_distance_threshold = getParameterFloat(nodeHandle_for_paramaters,"distanceThreshold");
-
-//     // setpoint in meters (x, y, z, yaw)
-//     getParameterFloatVector(nodeHandle_for_paramaters,"defaultSetpoint",yaml_default_setpoint,4);
-
-//     // DEBUGGING: Print out one of the parameters that was loaded
-//     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
-
-//     // Add the "SafeController" namespace to the "nodeHandle"
-//     ros::NodeHandle nodeHandle_for_safeController(nodeHandle, "SafeController");
-
-//     if(!nodeHandle_for_safeController.getParam("takeOffDistance", take_off_distance))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get takeOffDistance");
-//     }
-
-//     if(!nodeHandle_for_safeController.getParam("landingDistance", landing_distance))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get landing_distance");
-//     }
-
-//     if(!nodeHandle_for_safeController.getParam("durationTakeOff", duration_take_off))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_take_off");
-//     }
-
-//     if(!nodeHandle_for_safeController.getParam("durationLanding", duration_landing))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get duration_landing");
-//     }
-
-//     if(!nodeHandle_for_safeController.getParam("distanceThreshold", distance_threshold))
-//     {
-//         ROS_ERROR("[FLYING AGENT CLIENT] Failed to get distance_threshold");
-//     }
-//     */
-// }
-
-
-
-
 void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
 {
     // Check whether the message is relevant
@@ -1325,30 +1002,12 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
     m_maxTiltAngle_for_strictSafety_redians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
 
     // DEBUGGING: Print out one of the processed values
-    ROS_INFO_STREAM("[PICKER CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_redians = " << m_maxTiltAngle_for_strictSafety_redians);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_redians = " << m_maxTiltAngle_for_strictSafety_redians);
 }
 
 
 
 
-void timerCallback_for_loadAllControllers(const ros::TimerEvent&)
-{
-    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
-    loadController( "defaultController"  , defaultController );
-    loadController( "studentController"  , studentController );
-    loadController( "tuningController"   , tuningController );
-    loadController( "pickerController"   , pickerController );
-    loadController( "templateController" , templateController );
-
-    if (defaultController)
-    {
-        m_controllers_avialble = true;
-    }
-    else
-    {
-        m_controllers_avialble = false;
-    }
-}
 
 
 //    ----------------------------------------------------------------------------------
@@ -1438,14 +1097,26 @@ int main(int argc, char* argv[])
     //fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
 
+
+
+
     // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
-    // loadController( "defaultController"  , defaultController );
-    // loadController( "studentController"  , studentController );
-    // loadController( "tuningController"   , tuningController );
-    // loadController( "pickerController"   , pickerController );
-    // loadController( "templateController" , templateController );
+    // > This cannot be done directly here because the other nodes may
+    //   be currently unavailable. Hence, we start a timer for a few
+    //   seconds and in the call back all the controller service
+    //   clients are created.
     m_controllers_avialble = false;
-    timer_for_loadAllControllers = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_loadAllControllers, true);
+    m_timer_for_createAllControllerServiceClients = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_creaTeaLlcontrollerServiceClients, true);
+
+
+
+
+
+    // INITIALISE THE MOTION CAPTURE TIME-OUT TIMER
+    // > And stop it immediately
+    m_isAvailable_mocap_data = false;
+    m_timer_mocap_timeout_check = nodeHandle.createTimer(ros::Duration(yaml_mocap_timeout_duration), timerCallback_mocap_timeout_check, true);
+    m_timer_mocap_timeout_check.stop();
     
 
 
@@ -1489,7 +1160,7 @@ int main(int argc, char* argv[])
     // PUBLISHER FOR COMMANDING THE CRAZYFLIE
     // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
 	//ros::Publishers to advertise the control output
-	commandForSendingToCrazyfliePublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
+	m_commaNdfOrsendiNgTocrazyflIepublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
 	//this topic lets the FlyingAgentClient listen to the terminal commands
     //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
-- 
GitLab


From 61ffeb028e4ed1aded385fb5523bdfbc32ad9dcb Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Mon, 11 Feb 2019 23:59:06 +0100
Subject: [PATCH 77/87] Undo change accidentally committed to the Config.sh
 file

---
 dfall_ws/src/dfall_pkg/launch/Config.sh | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/launch/Config.sh b/dfall_ws/src/dfall_pkg/launch/Config.sh
index 98cd6dfe..028d739f 100755
--- a/dfall_ws/src/dfall_pkg/launch/Config.sh
+++ b/dfall_ws/src/dfall_pkg/launch/Config.sh
@@ -1,7 +1,7 @@
 # TO RUN THE SYSTEM FULLY ON THE LOCAL COMPUTER:
-export ROS_MASTER_URI=http://localhost:11311
+#export ROS_MASTER_URI=http://localhost:11311
 # TO RUN THE SYSTEM ON A DEFAULT CONFIGURATION OF THE NETWROK:
-#export ROS_MASTER_URI=http://teacher:11311
+export ROS_MASTER_URI=http://teacher:11311
 # OTHER NECESSARY ENVIRONMENT VARIABLES:
 export ROS_IP=$(hostname -I | awk '{print $1;}')
 export DFALL_DEFAULT_AGENT_ID=$(cat /etc/dfall_default_agent_id)
-- 
GitLab


From 7c93c2f22cfa73ec4c28e79c0c98ee1da9c4b838 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 12 Feb 2019 17:21:32 +0100
Subject: [PATCH 78/87] Mostly finished with converting the Flying Agent Client
 to the Default controller. Needs comoiltion testing. Next step is to make the
 Default controller able to perform take-off and land manoeuvres

---
 .../forms/defaultcontrollertab.ui             | 1988 +++++++++--------
 .../forms/studentcontrollertab.ui             |  384 ++--
 .../include/defaultcontrollertab.h            |    1 +
 .../src/defaultcontrollertab.cpp              |   51 +-
 .../nodes/DefaultControllerConstants.h        |   54 +
 .../include/nodes/DefaultControllerService.h  |   19 +-
 .../include/nodes/FlyingAgentClient.h         |  225 +-
 .../src/dfall_pkg/param/ClientConfig.yaml     |   32 +-
 .../src/nodes/DefaultControllerService.cpp    |  413 ++--
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp |  941 ++++----
 .../src/nodes/StudentControllerService.cpp    |    2 +-
 11 files changed, 2348 insertions(+), 1762 deletions(-)
 create mode 100644 dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
index 64921ccc..c8225eaf 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/defaultcontrollertab.ui
@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1633</width>
-    <height>765</height>
+    <width>1614</width>
+    <height>991</height>
    </rect>
   </property>
   <property name="font">
@@ -19,163 +19,79 @@
    <string>Form</string>
   </property>
   <layout class="QGridLayout" name="gridLayout">
-   <item row="3" column="13">
-    <spacer name="horizontalSpacer">
+   <item row="1" column="0">
+    <widget class="Line" name="line">
      <property name="orientation">
       <enum>Qt::Horizontal</enum>
      </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>40</width>
-       <height>20</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="6" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="3">
-    <widget class="QLabel" name="label_row_z">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>z [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="6">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string/>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="4">
-    <widget class="QLineEdit" name="lineEdit_error_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
     </widget>
    </item>
-   <item row="0" column="4">
-    <widget class="QLabel" name="label_error_title">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
+   <item row="3" column="0">
+    <layout class="QHBoxLayout" name="horizontalLayout_6">
+     <property name="leftMargin">
+      <number>0</number>
      </property>
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
+     <property name="topMargin">
+      <number>0</number>
      </property>
-     <property name="text">
-      <string>Error</string>
+     <property name="rightMargin">
+      <number>0</number>
      </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
+     <property name="bottomMargin">
+      <number>0</number>
      </property>
-    </widget>
+     <item>
+      <widget class="QLabel" name="label_current_state_title">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Preferred">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Current State:</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <widget class="QLabel" name="label_current_state">
+       <property name="text">
+        <string>TextLabel</string>
+       </property>
+      </widget>
+     </item>
+     <item>
+      <spacer name="horizontalSpacer_3">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+    </layout>
    </item>
-   <item row="3" column="6">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
+   <item row="4" column="0">
+    <spacer name="verticalSpacer">
+     <property name="orientation">
+      <enum>Qt::Vertical</enum>
      </property>
-     <property name="maximumSize">
+     <property name="sizeHint" stdset="0">
       <size>
-       <width>180</width>
-       <height>60</height>
+       <width>20</width>
+       <height>40</height>
       </size>
      </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string/>
-     </property>
-    </widget>
+    </spacer>
    </item>
-   <item row="3" column="7">
-    <spacer name="horizontalSpacer_2">
+   <item row="2" column="0">
+    <spacer name="verticalSpacer_2">
      <property name="orientation">
-      <enum>Qt::Horizontal</enum>
+      <enum>Qt::Vertical</enum>
      </property>
      <property name="sizeType">
       <enum>QSizePolicy::Fixed</enum>
@@ -188,247 +104,355 @@
      </property>
     </spacer>
    </item>
-   <item row="5" column="10">
-    <layout class="QHBoxLayout" name="horizontalLayout_2">
-     <item>
-      <widget class="QPushButton" name="z_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
+   <item row="0" column="0">
+    <layout class="QGridLayout" name="gridLayout_2">
+     <property name="leftMargin">
+      <number>0</number>
+     </property>
+     <property name="topMargin">
+      <number>0</number>
+     </property>
+     <property name="rightMargin">
+      <number>0</number>
+     </property>
+     <property name="bottomMargin">
+      <number>0</number>
+     </property>
+     <item row="2" column="1">
+      <widget class="QLabel" name="label_row_x">
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>16777215</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>-</string>
+        <string>x [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
+     <item row="0" column="6">
+      <widget class="QLabel" name="label_increment_title">
        <property name="maximumSize">
         <size>
-         <width>140</width>
-         <height>60</height>
+         <width>16777215</width>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
         <font>
-         <family>Courier</family>
+         <weight>75</weight>
+         <bold>true</bold>
         </font>
        </property>
+       <property name="text">
+        <string>Increment</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="z_increment_plus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
+     <item row="0" column="2">
+      <widget class="QLabel" name="label_error_title">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Error</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
+      </widget>
+     </item>
+     <item row="5" column="1">
+      <widget class="QLabel" name="label_row_yaw">
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>16777215</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>+</string>
+        <string>yaw [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="4" column="3">
-    <widget class="QLabel" name="label_row_y">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>y [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="3">
-    <widget class="QLabel" name="label_row_x">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>x [m]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="10">
-    <layout class="QHBoxLayout" name="horizontalLayout_3">
-     <item>
-      <widget class="QPushButton" name="y_increment_minus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
+     <item row="1" column="2">
+      <widget class="QLabel" name="label_error_title_line2">
        <property name="maximumSize">
         <size>
-         <width>60</width>
-         <height>60</height>
+         <width>16777215</width>
+         <height>50</height>
         </size>
        </property>
        <property name="text">
-        <string>-</string>
+        <string>meas-ref</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
+     <item row="1" column="3">
+      <widget class="QLabel" name="label_current_title_line2">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
+      </widget>
+     </item>
+     <item row="0" column="3">
+      <widget class="QLabel" name="label_current_title">
        <property name="maximumSize">
         <size>
-         <width>140</width>
-         <height>60</height>
+         <width>16777215</width>
+         <height>50</height>
         </size>
        </property>
        <property name="font">
         <font>
-         <family>Courier</family>
+         <weight>75</weight>
+         <bold>true</bold>
         </font>
        </property>
+       <property name="text">
+        <string>Current</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="y_increment_plus_button">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
+     <item row="1" column="6">
+      <widget class="QLabel" name="label_increment_title_line2">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
+      </widget>
+     </item>
+     <item row="3" column="1">
+      <widget class="QLabel" name="label_row_y">
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>16777215</width>
          <height>60</height>
         </size>
        </property>
        <property name="text">
-        <string>+</string>
+        <string>y [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="4" column="6">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string/>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="4">
-    <widget class="QLineEdit" name="lineEdit_error_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="6" column="10">
-    <layout class="QHBoxLayout" name="horizontalLayout">
-     <item>
-      <widget class="QPushButton" name="yaw_increment_minus_button">
+     <item row="3" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_3">
+       <item>
+        <widget class="QPushButton" name="y_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="y_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="4" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_2">
+       <item>
+        <widget class="QPushButton" name="z_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="z_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="2" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>-</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+     <item row="5" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_yaw">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
@@ -437,282 +461,183 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="yaw_increment_plus_button">
+     <item row="5" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout">
+       <item>
+        <widget class="QPushButton" name="yaw_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="yaw_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="5" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_yaw">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>+</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="0" column="10">
-    <widget class="QLabel" name="label_increment_title">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Increment</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="6">
-    <widget class="QLabel" name="label_new_title_line2">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="5">
-    <widget class="QLabel" name="label_current_title_line2">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="5">
-    <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="4">
-    <widget class="QLineEdit" name="lineEdit_error_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="6" column="4">
-    <widget class="QLineEdit" name="lineEdit_error_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-     <property name="readOnly">
-      <bool>true</bool>
-     </property>
-    </widget>
-   </item>
-   <item row="6" column="3">
-    <widget class="QLabel" name="label_row_yaw">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>yaw [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="4">
-    <widget class="QLabel" name="label_error_title_line2">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>meas-ref</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="10">
-    <layout class="QHBoxLayout" name="horizontalLayout_4">
-     <item>
-      <widget class="QPushButton" name="x_increment_minus_button">
+     <item row="2" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_x">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>-</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+     <item row="7" column="1">
+      <widget class="QLabel" name="label_row_roll">
+       <property name="text">
+        <string>roll [deg]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="3">
+      <widget class="QPushButton" name="default_setpoint_button">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>140</width>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Default</string>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
@@ -721,415 +646,668 @@
          <family>Courier</family>
         </font>
        </property>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="label_measured_title">
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>Measured</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
       </widget>
      </item>
-     <item>
-      <widget class="QPushButton" name="x_increment_plus_button">
+     <item row="6" column="1">
+      <widget class="QLabel" name="label_row_pitch">
+       <property name="text">
+        <string>pitch [deg]</string>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="2">
+      <widget class="QLineEdit" name="lineEdit_error_y">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>60</width>
+         <width>180</width>
          <height>60</height>
         </size>
        </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>+</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-    </layout>
-   </item>
-   <item row="0" column="5">
-    <widget class="QLabel" name="label_current_title">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Current</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="2" column="10">
-    <widget class="QLabel" name="label_increment_title_line2">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Setpoint</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="6" column="6">
-    <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string/>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="6">
-    <widget class="QLabel" name="label_new_title">
-     <property name="maximumSize">
-      <size>
-       <width>16777215</width>
-       <height>50</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>New</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="5">
-    <widget class="QPushButton" name="default_setpoint_button">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Default</string>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="6">
-    <widget class="QPushButton" name="set_setpoint_button">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="text">
-      <string>Set New</string>
-     </property>
-    </widget>
-   </item>
-   <item row="3" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_x">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="0" column="1">
-    <widget class="QLabel" name="label_measured_title">
-     <property name="font">
-      <font>
-       <weight>75</weight>
-       <bold>true</bold>
-      </font>
-     </property>
-     <property name="text">
-      <string>Measured</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="3">
-    <widget class="QLabel" name="label_row_pitch">
-     <property name="text">
-      <string>pitch [deg]</string>
-     </property>
-    </widget>
-   </item>
-   <item row="4" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_y">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="5" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_z">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="8" column="3">
-    <widget class="QLabel" name="label_row_roll">
-     <property name="text">
-      <string>roll [deg]</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item row="6" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_yaw">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="7" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_pitch">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="8" column="1">
-    <widget class="QLineEdit" name="lineEdit_measured_roll">
-     <property name="sizePolicy">
-      <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-       <horstretch>0</horstretch>
-       <verstretch>0</verstretch>
-      </sizepolicy>
-     </property>
-     <property name="maximumSize">
-      <size>
-       <width>180</width>
-       <height>60</height>
-      </size>
-     </property>
-     <property name="font">
-      <font>
-       <family>Courier</family>
-      </font>
-     </property>
-     <property name="text">
-      <string>xx.xx</string>
-     </property>
-    </widget>
-   </item>
-   <item row="10" column="1">
-    <spacer name="verticalSpacer">
-     <property name="orientation">
-      <enum>Qt::Vertical</enum>
-     </property>
-     <property name="sizeHint" stdset="0">
-      <size>
-       <width>20</width>
-       <height>40</height>
-      </size>
-     </property>
-    </spacer>
-   </item>
-   <item row="2" column="1">
-    <layout class="QHBoxLayout" name="horizontalLayout_5">
-     <property name="spacing">
-      <number>0</number>
-     </property>
-     <property name="leftMargin">
-      <number>0</number>
-     </property>
-     <property name="topMargin">
-      <number>0</number>
-     </property>
-     <property name="rightMargin">
-      <number>0</number>
-     </property>
-     <property name="bottomMargin">
-      <number>0</number>
-     </property>
-     <item>
-      <widget class="QFrame" name="red_frame_position_left">
+     <item row="4" column="1">
+      <widget class="QLabel" name="label_row_z">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>z [m]</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_y">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>10</width>
-         <height>16777215</height>
+         <width>180</width>
+         <height>60</height>
         </size>
        </property>
-       <property name="styleSheet">
-        <string notr="true">background-color:red;</string>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
        </property>
-       <property name="frameShape">
-        <enum>QFrame::StyledPanel</enum>
+       <property name="text">
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
        </property>
-       <property name="frameShadow">
-        <enum>QFrame::Raised</enum>
+       <property name="readOnly">
+        <bool>true</bool>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QLabel" name="label_measured_title_line2">
+     <item row="4" column="3">
+      <widget class="QLineEdit" name="lineEdit_setpoint_current_z">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
        <property name="text">
-        <string>Position</string>
+        <string>xx.xx</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+       <property name="readOnly">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="6">
+      <layout class="QHBoxLayout" name="horizontalLayout_4">
+       <item>
+        <widget class="QPushButton" name="x_increment_minus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>-</string>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLineEdit" name="lineEdit_setpoint_increment_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>140</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QPushButton" name="x_increment_plus_button">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>60</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="text">
+          <string>+</string>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="1" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_5">
+       <property name="spacing">
+        <number>0</number>
+       </property>
+       <property name="leftMargin">
+        <number>0</number>
+       </property>
+       <property name="topMargin">
+        <number>0</number>
+       </property>
+       <property name="rightMargin">
+        <number>0</number>
+       </property>
+       <property name="bottomMargin">
+        <number>0</number>
+       </property>
+       <item>
+        <widget class="QFrame" name="red_frame_position_left">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QLabel" name="label_measured_title_line2">
+         <property name="text">
+          <string>Position</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignCenter</set>
+         </property>
+        </widget>
+       </item>
+       <item>
+        <widget class="QFrame" name="red_frame_position_right">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>10</width>
+           <height>16777215</height>
+          </size>
+         </property>
+         <property name="styleSheet">
+          <string notr="true">background-color:red;</string>
+         </property>
+         <property name="frameShape">
+          <enum>QFrame::StyledPanel</enum>
+         </property>
+         <property name="frameShadow">
+          <enum>QFrame::Raised</enum>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="2" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_8">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="3" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_9">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="4" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_10">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="5" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_11">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="6" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_12">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_pitch">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="7" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_13">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_roll">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="2" column="7">
+      <spacer name="horizontalSpacer">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>40</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="2" column="5">
+      <spacer name="horizontalSpacer_2">
+       <property name="orientation">
+        <enum>Qt::Horizontal</enum>
+       </property>
+       <property name="sizeType">
+        <enum>QSizePolicy::Fixed</enum>
+       </property>
+       <property name="sizeHint" stdset="0">
+        <size>
+         <width>20</width>
+         <height>20</height>
+        </size>
+       </property>
+      </spacer>
+     </item>
+     <item row="0" column="4">
+      <widget class="QLabel" name="label_new_title">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <weight>75</weight>
+         <bold>true</bold>
+        </font>
+       </property>
+       <property name="text">
+        <string>New</string>
        </property>
        <property name="alignment">
         <set>Qt::AlignCenter</set>
        </property>
       </widget>
      </item>
-     <item>
-      <widget class="QFrame" name="red_frame_position_right">
+     <item row="1" column="4">
+      <widget class="QLabel" name="label_new_title_line2">
+       <property name="maximumSize">
+        <size>
+         <width>16777215</width>
+         <height>50</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Setpoint</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="2" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_x">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="3" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_y">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="4" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_z">
        <property name="sizePolicy">
-        <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
          <horstretch>0</horstretch>
          <verstretch>0</verstretch>
         </sizepolicy>
        </property>
        <property name="maximumSize">
         <size>
-         <width>10</width>
-         <height>16777215</height>
+         <width>180</width>
+         <height>60</height>
         </size>
        </property>
-       <property name="styleSheet">
-        <string notr="true">background-color:red;</string>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
        </property>
-       <property name="frameShape">
-        <enum>QFrame::StyledPanel</enum>
+      </widget>
+     </item>
+     <item row="5" column="4">
+      <widget class="QLineEdit" name="lineEdit_setpoint_new_yaw">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
        </property>
-       <property name="frameShadow">
-        <enum>QFrame::Raised</enum>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="font">
+        <font>
+         <family>Courier</family>
+        </font>
+       </property>
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="6" column="4">
+      <widget class="QPushButton" name="set_setpoint_button">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="maximumSize">
+        <size>
+         <width>180</width>
+         <height>60</height>
+        </size>
+       </property>
+       <property name="text">
+        <string>Set New</string>
        </property>
       </widget>
      </item>
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
index c1df7fef..e3e70de4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/studentcontrollertab.ui
@@ -492,66 +492,6 @@
        </property>
       </spacer>
      </item>
-     <item row="3" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_x">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
-     <item row="4" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_y">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
      <item row="4" column="1">
       <widget class="QLabel" name="label_row_y">
        <property name="maximumSize">
@@ -568,126 +508,6 @@
        </property>
       </widget>
      </item>
-     <item row="7" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_pitch">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
-     <item row="6" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_yaw">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
-     <item row="8" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_roll">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
-     <item row="5" column="0">
-      <widget class="QLineEdit" name="lineEdit_measured_z">
-       <property name="sizePolicy">
-        <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
-         <horstretch>0</horstretch>
-         <verstretch>0</verstretch>
-        </sizepolicy>
-       </property>
-       <property name="maximumSize">
-        <size>
-         <width>180</width>
-         <height>60</height>
-        </size>
-       </property>
-       <property name="font">
-        <font>
-         <family>Courier</family>
-        </font>
-       </property>
-       <property name="text">
-        <string>xx.xx</string>
-       </property>
-       <property name="alignment">
-        <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-       </property>
-       <property name="readOnly">
-        <bool>true</bool>
-       </property>
-      </widget>
-     </item>
      <item row="7" column="1">
       <widget class="QLabel" name="label_row_pitch">
        <property name="maximumSize">
@@ -1379,6 +1199,210 @@
        </property>
       </spacer>
      </item>
+     <item row="3" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_6">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_x">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="4" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_7">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_y">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="5" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_8">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_z">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="7" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_9">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_pitch">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="6" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_10">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_yaw">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
+     <item row="8" column="0">
+      <layout class="QHBoxLayout" name="horizontalLayout_11">
+       <item>
+        <widget class="QLineEdit" name="lineEdit_measured_roll">
+         <property name="sizePolicy">
+          <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
+           <horstretch>0</horstretch>
+           <verstretch>0</verstretch>
+          </sizepolicy>
+         </property>
+         <property name="maximumSize">
+          <size>
+           <width>180</width>
+           <height>60</height>
+          </size>
+         </property>
+         <property name="font">
+          <font>
+           <family>Courier</family>
+          </font>
+         </property>
+         <property name="text">
+          <string>xx.xx</string>
+         </property>
+         <property name="alignment">
+          <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
+         </property>
+         <property name="readOnly">
+          <bool>true</bool>
+         </property>
+        </widget>
+       </item>
+      </layout>
+     </item>
     </layout>
    </item>
    <item row="14" column="0">
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index c454832d..148335ac 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -60,6 +60,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
+#include "nodes/DefaultControllerConstants.h"
 
 // SPECIFY THE PACKAGE NAMESPACE
 //using namespace dfall_pkg;
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index c527b641..4dab1f6b 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -47,6 +47,9 @@ DefaultControllerTab::DefaultControllerTab(QWidget *parent) :
     ui->red_frame_position_left->setVisible(false);
     ui->red_frame_position_right->setVisible(false);
 
+    // Make the current state label blank
+    ui->label_current_state->setText("");
+
 
 
 #ifdef CATKIN_MAKE
@@ -249,6 +252,52 @@ void DefaultControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWith
 
     if (yaw < 0.0f) qstr = ""; else qstr = "+";
     ui->lineEdit_setpoint_current_yaw->setText(qstr + QString::number( yaw * RAD2DEG, 'f', 3));
+
+    // UPDATE THE CURRENT STATE LABEL
+    int current_state = newSetpoint.buttonID;
+    switch (current_state)
+    {
+    case DEFAULT_CONTROLLER_STATE_STANDBY:
+    {
+        ui->label_current_state->setText("standby");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS:
+    {
+        ui->label_current_state->setText("Take-off, spinning motors");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_MOVE_UP:
+    {
+        ui->label_current_state->setText("Take-off, moving up");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_GOTO_SETPOINT:
+    {
+        ui->label_current_state->setText("Take-off, goto setpoint");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN:
+    {
+        ui->label_current_state->setText("Landing, move down");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS:
+    {
+        ui->label_current_state->setText("Landing, spinning motors");
+        break;
+    }
+    case DEFAULT_CONTROLLER_STATE_UNKNOWN:
+    {
+        ui->label_current_state->setText("Unknown");
+        break;
+    }
+    default:
+    {
+        ui->label_current_state->setText("Not recognised");
+        break;
+    }
+    }
 }
 #endif
 
@@ -801,4 +850,4 @@ bool DefaultControllerTab::getTypeAndIDParameters()
     // Return
     return return_was_successful;
 }
-#endif
\ No newline at end of file
+#endif
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
new file mode 100644
index 00000000..cf6d6cee
--- /dev/null
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
@@ -0,0 +1,54 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//
+//    This file is part of D-FaLL-System.
+//    
+//    D-FaLL-System is free software: you can redistribute it and/or modify
+//    it under the terms of the GNU General Public License as published by
+//    the Free Software Foundation, either version 3 of the License, or
+//    (at your option) any later version.
+//    
+//    D-FaLL-System is distributed in the hope that it will be useful,
+//    but WITHOUT ANY WARRANTY; without even the implied warranty of
+//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+//    GNU General Public License for more details.
+//    
+//    You should have received a copy of the GNU General Public License
+//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
+//    
+//
+//    ----------------------------------------------------------------------------------
+//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
+//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
+//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
+//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
+//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
+//
+//
+//    DESCRIPTION:
+//    Constants that are used across the Default Controler
+//    Service, its GUI, and the Flying Agent Client
+//
+//    ----------------------------------------------------------------------------------
+
+
+
+
+// TO REQUEST MANOEUVRES
+
+#define DEFAULT_CONTROLLER_REQUEST_TAKE_OFF    1
+#define DEFAULT_CONTROLLER_REQUEST_LANDING     2
+
+
+// TO IDENITFY THE STATE OF THE DEFAULT CONTROLLER
+
+#define DEFAULT_CONTROLLER_STATE_UNKNOWN      -1
+#define DEFAULT_CONTROLLER_STATE_STANDBY      99
+
+// > The sequence of states for a TAKE-OFF manoeuvre
+#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS      11
+#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_MOVE_UP          12
+#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_GOTO_SETPOINT    13
+
+// > The sequence of states for a LANDING manoeuvre
+#define DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN        21
+#define DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS      22
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 00dc4219..8da4fa3c 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -72,6 +72,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
+#include "nodes/DefaultControllerConstants.h"
 
 // Include other classes
 #include "classes/GetParamtersAndNamespaces.h"
@@ -114,6 +115,13 @@ using namespace dfall_pkg;
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+// The current state of the Default Controller
+int m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
+
+// The elapased time, incremented by counting the motion
+// capture callbacks
+float m_time_in_seconds = 0.0;
+
 
 // The ID of the agent that this node is monitoring
 int m_agentID;
@@ -140,6 +148,7 @@ std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
 
 // > the frequency at which the controller is running
 float yaml_control_frequency = 200.0;
+float m_control_deltaT = (1.0/200.0);
 
 // > the min and max for saturating 16 bit thrust commands
 float yaml_command_sixteenbit_min = 1000;
@@ -172,8 +181,8 @@ std::vector<float> m_gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.
 // ROS Publisher for debugging variables
 ros::Publisher m_debugPublisher;
 
-// ROS Publisher for inform the network about
-// changes to the setpoin
+// ROS Publisher to inform the network about
+// changes to the setpoint
 ros::Publisher m_setpointChangedPublisher;
 
 
@@ -201,6 +210,9 @@ ros::Publisher m_setpointChangedPublisher;
 // need to written below in an order that ensure each function is
 // implemented before it is called from another function)
 
+// CALLBACK FOR THE REQUEST MANOEUVRE SERVICE
+bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Response &response);
+
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
@@ -220,6 +232,9 @@ void setNewSetpoint(float x, float y, float z, float yaw);
 // GET CURRENT SETPOINT SERVICE CALLBACK
 bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpointService::Response &response);
 
+// PUBLISH THE CURRENT SETPOINT AND STATE
+void publishCurrentSetpointAndState();
+
 // CUSTOM COMMAND RECEIVED CALLBACK
 void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 2d97b7c2..863c8c7c 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -66,6 +66,7 @@
 
 // Include the shared definitions
 #include "nodes/Constants.h"
+#include "nodes/DefaultControllerConstants.h"
 
 // Include other classes
 #include "classes/GetParamtersAndNamespaces.h"
@@ -121,74 +122,96 @@ std::string m_namespace_to_own_agent_parameter_service;
 std::string m_namespace_to_coordinator_parameter_service;
 
 
-// variables for the states:
-int m_flying_state;
-bool m_changed_flying_state_flag;
 
-// variable for crazyradio status
-int crazyradio_status;
+// VARIABLES FOR THE MOTION CAPTURE DATA
+// > The index for which element in the "motion capture
+//   data" array is expected to match the name in
+//   "m_context", (negative numbers indicate unknown)
+int m_poseDataIndex = -1;
+// > Boolen indicating if the Mocap data is availble
+bool m_isAvailable_mocap_data = false;
+// > Boolen indicating if the object is "long term" occuled
+bool m_isOcculded_mocap_data = false;
+// > Number of consecutive occulsions that trigger the
+//   "m_isOcculded_mocap_data" variable to be "true"
+int yaml_consecutive_occulsions_threshold = 10;
+// > Timer that when triggered determines that the
+//   "m_isAvailable_mocap_data" variable becomes true
+ros::Timer m_timer_mocap_timeout_check;
+
+
+
+// VARIABLES FOR STORING THE PARAMTER OF THE POSITION
+// AND TILT ANGLE SAFTY CHECKS
+// > Boolean indicating whether the tilt angle check
+//   should be performed
+bool yaml_isEnabled_strictSafety = true;
+// > The maximum allowed tilt angle, in degrees and radians
+float yaml_maxTiltAngle_for_strictSafety_degrees = 70;
+float m_maxTiltAngle_for_strictSafety_redians = 70 * DEG2RAD;
 
-//describes the area of the crazyflie and other parameters
-CrazyflieContext m_context;
 
-// The index for which element in the "motion captate data"
-// array is expected to match the name in "m_context"
-// > Negative numbers indicate unknown
-int m_poseDataIndex = -1;
 
-// wheter to use safe of demo controller
-// variable for the instant controller, e.g., we use
-// safe controller for taking off and landing even
-// if demo controller is enabled. This variable WILL change automatically
+// VARIABLES FOR MANAGING THE FLYING STATE
+// > Integer that is the current flying state
+int m_flying_state;
+// > Booleans for whether the {take-off,landing} should
+//   be performed with the default controller
+bool yaml_shouldPerfom_takeOff_with_defaultController = true;
+bool yaml_shouldPerfom_takeOff_with_defaultController = true;
+// > Service Clients for requesting the Default controller
+//   to perform a {take-off,landing} maneouvre
+ros::ServiceClient m_defaultController_requestManoeuvre;
+// > Timer that fire when the {take-off,landing} is complete
+ros::Timer m_timer_takeoff_complete;
+ros::Timer m_timer_land_complete;
+
+
+
+// VARIABLES RELATING TO CONTROLLER SELECTION
+// > Integer indicating the controller that is to be
+//   used in when motion capture data is received
 int m_instant_controller;
+// > Pointer to the controller service client that
+//   agrees with the "m_instant_controller" variable
 ros::ServiceClient* m_instant_controller_service_client;
+// > Boolean indicating that the controller service clients
+//   have been successfully created
 bool m_controllers_avialble = false;
+// > Timer for creating the controller service client after
+//   some delay
 ros::Timer timer_for_loadAllControllers;
-
-// controller used:
+// > Integer indicating the controller that has been
+//   requested. This controller is used during the "flying"
+//   state, and the "Default" controller is used during the
+//   "take-off" and "landing" states.
 int m_controller_nominally_selected;
 
 
-// The safe controller specified in the ClientConfig.yaml
-ros::ServiceClient safeController;
+
+// VARIABLES FOR THE CONTROLER SERVIVCE CLIENTS
 // The default controller specified in the ClientConfig.yaml
-ros::ServiceClient defaultController;
-// The Demo controller specified in the ClientConfig.yaml
-ros::ServiceClient demoController;
+ros::ServiceClient m_defaultController;
 // The Student controller specified in the ClientConfig.yaml
-ros::ServiceClient studentController;
-// The MPC controller specified in the ClientConfig.yaml
-ros::ServiceClient mpcController;
-// The Remote controller specified in the ClientConfig.yaml
-ros::ServiceClient remoteController;
+ros::ServiceClient m_studentController;
 // The Tuning controller specified in the ClientConfig.yaml
-ros::ServiceClient tuningController;
+ros::ServiceClient m_tuningController;
 // The Picker controller specified in the ClientConfig.yaml
-ros::ServiceClient pickerController;
+ros::ServiceClient m_pickerController;
 // The Template controller specified in the ClientConfig.yaml
-ros::ServiceClient templateController;
+ros::ServiceClient m_templateController;
 
 
-// The values for the safety check on tilt angle
-bool yaml_isEnabled_strictSafety = true;
-float yaml_angleMargin;
-float yaml_maxTiltAngle_for_strictSafety_degrees = 70;
-float m_maxTiltAngle_for_strictSafety_redians = 70 * DEG2RAD;
 
 
 
 
-//Setpoint controller_setpoint;
 
-//std::vector<float> yaml_default_setpoint = {0.0f, 0.0f, 0.0f, 0.0f};
-
-// variables for linear trayectory
-//Setpoint current_safe_setpoint;
-//double distance;
-//double unit_vector[3];
-//bool was_in_threshold = false;
-//double yaml_distance_threshold;      //to be loaded from yaml
+// variable for crazyradio status
+int m_crazyradio_status;
 
+//describes the area of the crazyflie and other parameters
+CrazyflieContext m_context;
 
 // Service Client from which the "CrazyflieContext" is loaded
 ros::ServiceClient centralManager;
@@ -199,9 +222,6 @@ ros::ServiceClient centralManager;
 // {onboardControllerType,roll,pitch,yaw,motorCmd1,motorCmd2,motorCmd3,motorCmd4}
 ros::Publisher commandForSendingToCrazyfliePublisher;
 
-// communicate with safeControllerService, setpoint, etc...
-//ros::Publisher safeControllerServiceSetpointPublisher;
-
 // Publisher for the current flying state of this Flying Agent Client
 ros::Publisher flyingStatePublisher;
 
@@ -212,27 +232,11 @@ ros::Publisher flyingStatePublisher;
 // Publisher Communication with crazyRadio node. Connect and disconnect
 ros::Publisher crazyRadioCommandPublisher;
 
-
 // Publisher for which controller is currently being used
 ros::Publisher controllerUsedPublisher;
 
 
 
-// float yaml_take_off_distance;
-// float yaml_landing_distance;
-// float yaml_duration_take_off;
-// float yaml_duration_landing;
-
-// bool finished_take_off = false;
-// bool finished_land = false;
-
-ros::Timer timer_takeoff;
-ros::Timer timer_land;
-
-// A ROS "bag" to store data for post-analysis
-//rosbag::Bag bag;
-
-
 
 
 //    ----------------------------------------------------------------------------------
@@ -251,75 +255,104 @@ ros::Timer timer_land;
 
 
 
-
-
-
-
-
-
+// FUNCTIONS FOR HANDLING THE MOTION CAPTURE DATA
+// > Callback run every time new motion capture
+//   data is available
 void viconCallback(const ViconData& viconData);
+// > For extracting the pose data of an specific
+//   object by name
 int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::string name , int expected_index , CrazyflieData& pose);
+// > For converting the global frame motion capture
+//   data to the local frame of this agent
 void coordinatesToLocal(CrazyflieData& cf);
+// > Callback run when motion capture data has not
+//   been receive for a specified time
+void timerCallback_mocap_timeout_check(const ros::TimerEvent&);
+// > For sending a command, via the CrazyRadio, that
+//   the motors should be set to zero
+void sendZeroOutputCommandForMotors();
 
 
 
-// > For the SAFETY CHECK on area and the angle
-bool safetyCheck(CrazyflieData data, ControlCommand controlCommand);
-
-
-void changeFlyingStateTo(int new_state);
-
-
-void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
-
-
-
+// FOR THE SAFETY CHECKS ON POSITION AND TILT ANGLE
+bool safetyCheck_on_positionAndTilt(CrazyflieData data);
 
-void flyingStateRequestCallback(const IntWithHeader & commandMsg);
 
 
+// FUNCTIONS THAT MANAGE THE CHANGES TO THE FLYING STATE
+// > For changing between possible state of:
+//   {take-off,flying,take-off,motors-off}
+void requestChangeFlyingStateTo(int new_state);
+// > For changing to take-off
+void requestChangeFlyingStateToTakeOff();
+// > For changing to land
+void requestChangeFlyingStateToLand();
+// > Callback that the take off phase is complete
+void takeOffTimerCallback(const ros::TimerEvent&)
+// > Callback that the landing phase is complete
+void landTimerCallback(const ros::TimerEvent&)
 
 
-// void loadSafeController();
-// void loadDemoController();
-// void loadStudentController();
-// void loadMpcController();
-// void loadRemoteController();
-// void loadTuningController();
-// void loadPickerController();
-// void loadTemplateController();
 
-void loadController( std::string paramter_name , ros::ServiceClient& serviceClient );
 
-void sendMessageUsingController(int controller);
+// FUNCTIONS FOR SELECTING WHICH CONTROLLER TO USE
+// > For setting the controller that is actually used
 void setInstantController(int controller);
+// > For retrieving the value of the class variable
 int getInstantController();
+// > For setting the controller that it to be used
+//   during the normal "flying" state
 void setControllerNominallySelected(int controller);
+// > For retrieving the value of the class variable
 int getControllerNominallySelected();
 
 
 
+// THE CALLBACK THAT A NEW FLYING STATE WAS REQUESTED
+// > These requests come from the "Flying Agent GUI"
+// > The options are: {take-off,land,motor-off,controller}
+void flyingStateOrControllerRequestCallback(const IntWithHeader & commandMsg);
+
+
+
 // THE CALLBACK THAT THE CRAZY RADIO STATUS CHANGED
 void crazyRadioStatusCallback(const std_msgs::Int32& msg);
 
+
+
 // THE CALLBACK THAT AN EMERGENCY STOP MESSAGE WAS RECEIVED
 void emergencyStopReceivedCallback(const IntWithHeader & msg);
 
+
+
 // THE SERVICE CALLBACK REQUESTING THE CURRENT FLYING STATE
 bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIntService::Response &response);
 
+
+
 // FOR THE BATTERY STATE CALLBACK
 void batteryMonitorStateChangedCallback(std_msgs::Int32 msg);
 
-// FOR THE SAFETY CHECKS ON POSITION AND TILT ANGLE
-bool safetyCheck(CrazyflieData data);
 
-// THE CALLBACK THAT THE CONTEXT DATABASE CHANGED
-void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
 
-// FOR LOADING THE CONTEXT OF THIS AGENT
+// FUNCTIONS FOR THE CONTEXT OF THIS AGENT
+// > Callback that the context database changed
+void crazyflieContextDatabaseChangedCallback(const std_msgs::Int32& msg);
+// > For loading the context of this agent
 void loadCrazyflieContext();
 
+
+
+// FUNCTIONS FOR CREATING THE CONTROLLER SERVICE CLIENT
+// > For creating a service client from the name
+//   of the YAML parameter
+void createControllerServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient );
+// > Callback for the timer so that all services servers
+//   exists before we try to create the clients
+void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&);
+
+
+
 // FOR LOADING THE YAML PARAMETERS
 void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
 void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
index 1d3c4806..a5825598 100755
--- a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
@@ -1,17 +1,33 @@
-safeController:     "SafeControllerService/RateController"
+# The name the controller services advertised by
+# each of the controller nodes.
 defaultController:  "DefaultControllerService/DefaultController"
-demoController:     "DemoControllerService/DemoController"
 studentController:  "StudentControllerService/StudentController"
-mpcController:      "MpcControllerService/MpcController"
-remoteController:   "RemoteControllerService/RemoteController"
 tuningController:   "TuningControllerService/TuningController"
 pickerController:   "PickerControllerService/PickerController"
 templateController: "TemplateControllerService/TemplateController"
 
-# Flag for whether to use angle for switching to the Default Controller
+# The name of the service advertised by the Default
+# Controller for requests manoeuvres to be performed
+defaultController_requestManoeuvre: "DefaultControllerService/RequestManoeuvre"
+
+# Flag for whether to use angle for switching
+# to the Default Controller
 isEnabled_strictSafety: true
 maxTiltAngle_for_strictSafety_degrees: 70
 
-battery_threshold_while_flying: 2.60       # in V
-battery_threshold_while_motors_off: 3.30   # in V
-battery_polling_period: 200                # in ms
\ No newline at end of file
+# Number of consecutive occulsions that will deem the
+# object as "long-term" occuled
+consecutive_occulsions_threshold: 10
+
+# Flag for whether the take-off should be performed
+# with the default controller
+shouldPerfom_takeOff_with_defaultController: true
+
+# Flag for whether the landing should be performed
+# with the default controller
+shouldPerfom_landing_with_defaultController: true
+
+
+#battery_threshold_while_flying: 2.60       # in V
+#battery_threshold_while_motors_off: 3.30   # in V
+#battery_polling_period: 200                # in ms
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 7f455863..d6e0a5d8 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -59,6 +59,75 @@
 
 
 
+//    ------------------------------------------------------------------------------
+//    RRRR   EEEEE   QQQ   U   U  EEEEE   SSSS  TTTTT
+//    R   R  E      Q   Q  U   U  E      S        T
+//    RRRR   EEE    Q   Q  U   U  EEE     SSS     T
+//    R   R  E      Q  Q   U   U  E          S    T
+//    R   R  EEEEE   QQ Q   UUU   EEEEE  SSSS     T
+//    
+//    M   M    A    N   N   OOO   EEEEE  U   U  V   V  RRRR   EEEEE
+//    MM MM   A A   NN  N  O   O  E      U   U  V   V  R   R  E
+//    M M M  A   A  N N N  O   O  EEE    U   U  V   V  RRRR   EEE
+//    M   M  AAAAA  N  NN  O   O  E      U   U   V V   R   R  E
+//    M   M  A   A  N   N   OOO   EEEEE   UUU     V    R   R  EEEEE
+//    ------------------------------------------------------------------------------
+
+// CALLBACK FOR THE REQUEST MANOEUVRE SERVICE
+bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Response &response)
+{
+	// Extract the requested manoeuvre
+	int requestedManoeuvre = request.data;
+
+	// Switch between the possible manoeuvres
+	switch (requestedManoeuvre)
+	{
+		case DEFAULT_CONTROLLER_REQUEST_TAKE_OFF:
+		{
+			// Inform the user
+			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform take-off manoeuvre.");
+			// Reset the time variable
+			m_time_in_seconds = 0.0;
+			// Update the state accordingly
+			m_current_state = DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS;
+			// Fill in the response duration in milliseconds
+			response.data = 3000;
+			break;
+		}
+
+		case DEFAULT_CONTROLLER_REQUEST_LANDING:
+		{
+			// Inform the user
+			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform landing manoeuvre.");
+			// Reset the time variable
+			m_time_in_seconds = 0.0;
+			// Update the state accordingly
+			m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN;
+			// Fill in the response duration in milliseconds
+			response.data = 2000;
+			break;
+		}
+
+		default:
+		{
+			// Inform the user
+			ROS_INFO("[DEFAULT CONTROLLER] The requested manoeuvre is not recognised. Hence switching to stand-by state.");
+			// Update the state to standby
+			m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
+			// Fill in the response duration in milliseconds
+			response.data = 0;
+			break;
+		}
+	}
+
+	// Publish the change
+	publishCurrentSetpointAndState();
+
+	// Return success
+	return true;
+}
+
+
 //    ------------------------------------------------------------------------------
 //     OOO   U   U  TTTTT  EEEEE  RRRR 
 //    O   O  U   U    T    E      R   R
@@ -66,111 +135,22 @@
 //    O   O  U   U    T    E      R  R
 //     OOO    UUU     T    EEEEE  R   R
 //
-//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L           L       OOO    OOO   PPPP
-//    C      O   O  NN  N    T    R   R  O   O  L           L      O   O  O   O  P   P
-//    C      O   O  N N N    T    RRRR   O   O  L           L      O   O  O   O  PPPP
-//    C      O   O  N  NN    T    R  R   O   O  L           L      O   O  O   O  P
-//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL       LLLLL   OOO    OOO   P
+//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L
+//    C      O   O  NN  N    T    R   R  O   O  L
+//    C      O   O  N N N    T    RRRR   O   O  L
+//    C      O   O  N  NN    T    R  R   O   O  L
+//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL
+//
+//    L       OOO    OOO   PPPP
+//    L      O   O  O   O  P   P
+//    L      O   O  O   O  PPPP
+//    L      O   O  O   O  P
+//    LLLLL   OOO    OOO   P
 //    ----------------------------------------------------------------------------------
 
-// This function is the callback that is linked to the "DefaultController" service that
-// is advertised in the main function. This must have arguments that match the
-// "input-output" behaviour defined in the "Controller.srv" file (located in the "srv"
-// folder)
-//
-// The arument "request" is a structure provided to this service with the following two
-// properties:
-// request.ownCrazyflie
-// This property is itself a structure of type "CrazyflieData",  which is defined in the
-// file "CrazyflieData.msg", and has the following properties
-// string crazyflieName
-//     float64 x                         The x position of the Crazyflie [metres]
-//     float64 y                         The y position of the Crazyflie [metres]
-//     float64 z                         The z position of the Crazyflie [metres]
-//     float64 roll                      The roll component of the intrinsic Euler angles [radians]
-//     float64 pitch                     The pitch component of the intrinsic Euler angles [radians]
-//     float64 yaw                       The yaw component of the intrinsic Euler angles [radians]
-//     float64 acquiringTime #delta t    The time elapsed since the previous "CrazyflieData" was received [seconds]
-//     bool occluded                     A boolean indicted whether the Crazyflie for visible at the time of this measurement
-// The values in these properties are directly the measurement taken by the Vicon
-// motion capture system of the Crazyflie that is to be controlled by this service
-//
-// request.otherCrazyflies
-// This property is an array of "CrazyflieData" structures, what allows access to the
-// Vicon measurements of other Crazyflies.
-//
-// The argument "response" is a structure that is expected to be filled in by this
-// service by this function, it has only the following property
-// response.ControlCommand
-// This property is iteself a structure of type "ControlCommand", which is defined in
-// the file "ControlCommand.msg", and has the following properties:
-//     float32 roll                      The command sent to the Crazyflie for the body frame x-axis
-//     float32 pitch                     The command sent to the Crazyflie for the body frame y-axis
-//     float32 yaw                       The command sent to the Crazyflie for the body frame z-axis
-//     uint16 motorCmd1                  The command sent to the Crazyflie for motor 1
-//     uint16 motorCmd2                  The command sent to the Crazyflie for motor 1
-//     uint16 motorCmd3                  The command sent to the Crazyflie for motor 1
-//     uint16 motorCmd4                  The command sent to the Crazyflie for motor 1
-//     uint8 onboardControllerType       The flag sent to the Crazyflie for indicating how to implement the command
-// 
-// IMPORTANT NOTES FOR "onboardControllerType"  AND AXIS CONVENTIONS
-// > The allowed values for "onboardControllerType" are in the "Defines"
-//   section in the header file, they are:
-//   - CF_COMMAND_TYPE_MOTORS
-//   - CF_COMMAND_TYPE_RATE
-//   - CF_COMMAND_TYPE_ANGLE
-//
-// > For completeing the class exercises it is only required to use
-//   the CF_COMMAND_TYPE_RATE option.
-//
-// > For the CF_COMMAND_TYPE_RATE optoin:
-//   1) 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.
-//   2) the ".motorCmd1" to ".motorCmd4" properties of
-//      "response.ControlCommand" are the baseline motor commands
-//      requested from the Crazyflie, with the adjustment for body rates
-//      being added on top of this in the firmware (i.e., as per the
-//      code of the "distribute_power" found in the firmware).
-//   3) the axis convention for the roll, pitch, and yaw body rates
-//      returned in "response.ControlCommand" should use right-hand
-//      coordinate axes with x-forward and z-upwards (i.e., the positive
-//      z-axis is aligned with the direction of positive thrust). To
-//      assist, the following is an ASCII art of this convention.
-//
-// ASCII ART OF THE CRAZYFLIE 2.0 LAYOUT
-//
-//  > This is a top view,
-//  > M1 to M4 stand for Motor 1 to Motor 4,
-//  > "CW"  indicates that the motor rotates Clockwise,
-//  > "CCW" indicates that the motor rotates Counter-Clockwise,
-//  > By right-hand axis convention, the positive z-direction points our of the screen,
-//  > This being a "top view" means tha the direction of positive thrust produced
-//    by the propellers is also out of the screen.
-//
-//        ____                         ____
-//       /    \                       /    \
-//  (CW) | M4 |           x           | M1 | (CCW)
-//       \____/\          ^          /\____/
-//            \ \         |         / /
-//             \ \        |        / /
-//              \ \______ | ______/ /
-//               \        |        /
-//                |       |       |
-//        y <-------------o       |
-//                |               |
-//               / _______________ \
-//              / /               \ \
-//             / /                 \ \
-//        ____/ /                   \ \____
-//       /    \/                     \/    \
-// (CCW) | M3 |                       | M2 | (CW)
-//       \____/                       \____/
-//
-//
-//
-// This function WILL NEED TO BE edited for successful completion of the classroom exercise
+
+
+// THE MAIN CONTROL FUNCTION CALLED FROM THE FLYING AGENT CLIENT
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response)
 {
 
@@ -178,6 +158,9 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// computation here, or you may find it convienient to create functions
 	// to keep you code cleaner
 
+	// Increment time
+	m_time_in_seconds += m_control_deltaT;
+
 
 	// Define a local array to fill in with the state error
 	float stateErrorInertial[9];
@@ -228,86 +211,104 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 
 
-	
-	// YAW CONTROLLER
-
-	// Perform the "-Kx" LQR computation for the yaw rate
-	// to respond with
-	float yawRate_forResponse = 0;
-	for(int i = 0; i < 9; ++i)
+	if (m_current_state == DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS)
 	{
-		yawRate_forResponse -= m_gainMatrixYawRate[i] * stateErrorBody[i];
+		// Compute the "spinning" thrust
+		float thrust_for_spinning = 1000.0 + min(0.4,m_time_in_seconds) * 10000.0;
+
+		response.controlOutput.roll  = 0.0;
+		response.controlOutput.pitch = 0.0;
+		response.controlOutput.yaw   = 0.0;
+		response.controlOutput.motorCmd1 = thrust_for_spinning;
+		response.controlOutput.motorCmd2 = thrust_for_spinning;
+		response.controlOutput.motorCmd3 = thrust_for_spinning;
+		response.controlOutput.motorCmd4 = thrust_for_spinning;
+		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 	}
-	// Put the computed yaw rate into the "response" variable
-	response.controlOutput.yaw = yawRate_forResponse;
+	else
+	{
 
 
+		
+		// YAW CONTROLLER
 
+		// Perform the "-Kx" LQR computation for the yaw rate
+		// to respond with
+		float yawRate_forResponse = 0;
+		for(int i = 0; i < 9; ++i)
+		{
+			yawRate_forResponse -= m_gainMatrixYawRate[i] * stateErrorBody[i];
+		}
+		// Put the computed yaw rate into the "response" variable
+		response.controlOutput.yaw = yawRate_forResponse;
 
-	// ALITUDE CONTROLLER (i.e., z-controller)
-	
-	// Perform the "-Kx" LQR computation for the thrust adjustment
-	// to use for computing the response with
-	float thrustAdjustment = 0;
-	for(int i = 0; i < 9; ++i)
-	{
-		thrustAdjustment -= m_gainMatrixThrust[i] * stateErrorBody[i];
-	}
 
-	// Add the feed-forward thrust before putting in the response
-	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
-	float thrust_per_motor = thrustAdjustment + feed_forward_thrust_per_motor;
 
-	// > NOTE: the function "computeMotorPolyBackward" converts the
-	//         input argument from Newtons to the 16-bit command
-	//         expected by the Crazyflie.
-	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrust_per_motor);
-	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrust_per_motor);
-	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrust_per_motor);
-	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrust_per_motor);
 
-	
-	// BODY FRAME X CONTROLLER
+		// ALITUDE CONTROLLER (i.e., z-controller)
+		
+		// Perform the "-Kx" LQR computation for the thrust adjustment
+		// to use for computing the response with
+		float thrustAdjustment = 0;
+		for(int i = 0; i < 9; ++i)
+		{
+			thrustAdjustment -= m_gainMatrixThrust[i] * stateErrorBody[i];
+		}
 
-	// Perform the "-Kx" LQR computation for the pitch rate
-	// to respoond with
-	float pitchRate_forResponse = 0;
-	for(int i = 0; i < 9; ++i)
-	{
-		pitchRate_forResponse -= m_gainMatrixPitchRate[i] * stateErrorBody[i];
-	}
-	// Put the computed pitch rate into the "response" variable
-	response.controlOutput.pitch = pitchRate_forResponse;
+		// Add the feed-forward thrust before putting in the response
+		float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
+		float thrust_per_motor = thrustAdjustment + feed_forward_thrust_per_motor;
+
+		// > NOTE: the function "computeMotorPolyBackward" converts the
+		//         input argument from Newtons to the 16-bit command
+		//         expected by the Crazyflie.
+		response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrust_per_motor);
+		response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrust_per_motor);
+		response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrust_per_motor);
+		response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrust_per_motor);
+
+		
+		// BODY FRAME X CONTROLLER
+
+		// Perform the "-Kx" LQR computation for the pitch rate
+		// to respoond with
+		float pitchRate_forResponse = 0;
+		for(int i = 0; i < 9; ++i)
+		{
+			pitchRate_forResponse -= m_gainMatrixPitchRate[i] * stateErrorBody[i];
+		}
+		// Put the computed pitch rate into the "response" variable
+		response.controlOutput.pitch = pitchRate_forResponse;
 
 
 
 
-	// BODY FRAME Y CONTROLLER
+		// BODY FRAME Y CONTROLLER
 
-	// Instantiate the local variable for the roll rate that will be requested
-	// from the Crazyflie's on-baord "inner-loop" controller
-	
+		// Instantiate the local variable for the roll rate that will be requested
+		// from the Crazyflie's on-baord "inner-loop" controller
+		
 
-	// Perform the "-Kx" LQR computation for the roll rate
-	// to respoond with
-	float rollRate_forResponse = 0;
-	for(int i = 0; i < 9; ++i)
-	{
-		rollRate_forResponse -= m_gainMatrixRollRate[i] * stateErrorBody[i];
+		// Perform the "-Kx" LQR computation for the roll rate
+		// to respoond with
+		float rollRate_forResponse = 0;
+		for(int i = 0; i < 9; ++i)
+		{
+			rollRate_forResponse -= m_gainMatrixRollRate[i] * stateErrorBody[i];
+		}
+		// Put the computed roll rate into the "response" variable
+		response.controlOutput.roll = rollRate_forResponse;
+
+		
+		
+		// PREPARE AND RETURN THE VARIABLE "response"
+
+		/*choosing the Crazyflie onBoard controller type.
+		it can either be Motor, Rate or Angle based */
+		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
+		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 	}
-	// Put the computed roll rate into the "response" variable
-	response.controlOutput.roll = rollRate_forResponse;
-
-	
-	
-	// PREPARE AND RETURN THE VARIABLE "response"
-
-	/*choosing the Crazyflie onBoard controller type.
-	it can either be Motor, Rate or Angle based */
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
-	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
-	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
-
 
 
 
@@ -401,30 +402,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 //    BBBB    OOO   DDDD     Y         F      R   R  A   A  M   M  EEEEE
 //    ----------------------------------------------------------------------------------
 
-// The arguments for this function are as follows:
-// stateInertial
-// This is an array of length 9 with the estimates the error of of the following values
-// relative to the sepcifed setpoint:
-//     stateInertial[0]    x position of the Crazyflie relative to the inertial frame origin [meters]
-//     stateInertial[1]    y position of the Crazyflie relative to the inertial frame origin [meters]
-//     stateInertial[2]    z position of the Crazyflie relative to the inertial frame origin [meters]
-//     stateInertial[3]    x-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
-//     stateInertial[4]    y-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
-//     stateInertial[5]    z-axis component of the velocity of the Crazyflie in the inertial frame [meters/second]
-//     stateInertial[6]    The roll  component of the intrinsic Euler angles [radians]
-//     stateInertial[7]    The pitch component of the intrinsic Euler angles [radians]
-//     stateInertial[8]    The yaw   component of the intrinsic Euler angles [radians]
-// 
-// stateBody
-// This is an empty array of length 9, this function should fill in all elements of this
-// array with the same ordering as for the "stateInertial" argument, expect that the (x,y)
-// position and (x,y) velocities are rotated into the body frame.
-//
-// yaw_measured
-// 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 classroom exercise
+// ROTATES THE (x,y) COMPONENTS BY THE PROVIDED "yaw" ANGLE
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured)
 {
 
@@ -465,11 +443,10 @@ void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float y
 //     CCCC   OOO   N   N    V    EEEEE  R   R  SSSS   III   OOO   N   N
 //    ----------------------------------------------------------------------------------
 
-// This function DOES NEED TO BE edited for successful completion of
-// the exercise
+// CONVERTS A THURST IN NEWTONS TO A 16-BIT NUMBER
 float computeMotorPolyBackward(float thrust)
 {
-	// Compute the 16-but command that would produce the requested
+	// Compute the 16-bit command that would produce the requested
 	// "thrust" based on the quadratic mapping that is described
 	// by the coefficients in the "yaml_motorPoly" variable.
 	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
@@ -574,11 +551,30 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 	response.setpointWithHeader.y   = m_setpoint[1];
 	response.setpointWithHeader.z   = m_setpoint[2];
 	response.setpointWithHeader.yaw = m_setpoint[3];
+	// Put the current state into the "buttonID" field
+	response.buttonID = m_current_state;
 	// Return
 	return true;
 }
 
 
+// PUBLISH THE CURRENT SETPOINT SO THAT THE NETWORK IS UPDATED
+void publishCurrentSetpointAndState()
+{
+	// Instantiate a local variable of type "SetpointWithHeader"
+	SetpointWithHeader msg;
+	// Fill in the setpoint
+	msg.x   = m_setpoint[0];
+	msg.y   = m_setpoint[1];
+	msg.z   = m_setpoint[2];
+	msg.yaw = m_setpoint[3];
+	// Put the current state into the "buttonID" field
+	response.buttonID = m_current_state;
+	// Publish the message
+	m_setpointChangedPublisher.publish(msg);
+}
+
+
 
 
 
@@ -656,6 +652,8 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 
 
 
+
+
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
 //    L      O   O   A A   D   D
@@ -765,6 +763,9 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	//   gravity (i.e., mg) in units of [Newtons]
 	m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81/1000.0;
 
+	// > Conver the control frequency to a delta T
+	m_control_deltaT = 1.0 / yaml_control_frequency;
+
 	// DEBUGGING: Print out one of the computed quantities
 	ROS_INFO_STREAM("[DEFAULT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << m_cf_weight_in_newtons);
 }
@@ -955,7 +956,7 @@ int main(int argc, char* argv[])
 	// an integer (that is essentially ignored), and is expected to respond
 	// with the current setpoint of the controller. When a request is made
 	// of this service the "getCurrentSetpointCallback" function is called.
-	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);	
+	ros::ServiceServer getCurrentSetpointService = nodeHandle.advertiseService("GetCurrentSetpoint", getCurrentSetpointCallback);
 
 
 
@@ -967,7 +968,7 @@ int main(int argc, char* argv[])
 	// that should be sent via the Crazyradio and requested from the Crazyflie, i.e.,
 	// this is where the "outer loop" controller function starts. When a request is made
 	// of this service the "calculateControlOutput" function is called.
-	ros::ServiceServer service = nodeHandle.advertiseService("DefaultController", calculateControlOutput);
+	ros::ServiceServer controllerService = nodeHandle.advertiseService("DefaultController", calculateControlOutput);
 
 	// Instantiate the local variable "customCommandSubscriber" to be a "ros::Subscriber"
 	// type variable that subscribes to the "GUIButton" topic and calls the class
@@ -977,6 +978,28 @@ int main(int argc, char* argv[])
 
 
 
+	// Instantiate the local variable "service" to be a "ros::ServiceServer"
+	// type variable that advertises the service called:
+	// >> "RequestManoeuvre"
+	// This service has the input-output behaviour defined in the
+	// "IntIntService.srv" file (located in the "srv" folder).
+	// This service, when called, is provided with what manoeuvre
+	// is requested and responds with the duration that menoeuvre
+	// will take to perform (in milliseconds)
+	ros::ServiceServer requestManoeuvreService = nodeHandle.advertiseService("RequestManoeuvre", requestManoeuvreCallback);
+
+
+
+	// Instantiate the class variable "m_stateChangedPublisher" to
+	// be a "ros::Publisher". This variable advertises under the name
+	// "SetpointChanged" and is a message with the structure defined
+	// in the file "IntWithHeader.msg" (located in the "msg" folder).
+	// This publisher is used by the "flying agent GUI" to update the
+	// field that displays the current state for this controller.
+	m_stateChangedPublisher = nodeHandle.advertise<IntWithHeader>("StateChanged", 1);
+
+
+
 	// Print out some information to the user.
 	ROS_INFO("[DEFAULT CONTROLLER] Service ready :-)");
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 00a01201..e48d3d11 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -59,178 +59,128 @@
 
 
 
+//    ----------------------------------------------------------------------------------
+//    M   M   OOO   TTTTT  III   OOO   N   N
+//    MM MM  O   O    T     I   O   O  NN  N
+//    M M M  O   O    T     I   O   O  N N N
+//    M   M  O   O    T     I   O   O  N  NN
+//    M   M   OOO     T    III   OOO   N   N
+//
+//     CCCC    A    PPPP   TTTTT  U   U  RRRR   EEEEE
+//    C       A A   P   P    T    U   U  R   R  E
+//    C      A   A  PPPP     T    U   U  RRRR   EEE
+//    C      AAAAA  P        T    U   U  R   R  E
+//     CCCC  A   A  P        T     UUU   R   R  EEEEE
+//    ----------------------------------------------------------------------------------
 
-
-
-
-
-
-
-
-
-// void takeOffCF(CrazyflieData& current_local_coordinates) //local because the setpoint is in local coordinates
-// {
-//     // set the setpoint and call safe controller
-//     Setpoint setpoint_msg;
-//     setpoint_msg.x = current_local_coordinates.x;           // previous one
-//     setpoint_msg.y = current_local_coordinates.y;           //previous one
-//     setpoint_msg.z = current_local_coordinates.z + yaml_take_off_distance;           //previous one plus some offset
-//     // setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
-//     setpoint_msg.yaw = 0.0;
-//     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-//     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();
-//     setInstantController(SAFE_CONTROLLER);
-//     // when do we finish? after some time with delay?
-
-//     // update variable that keeps track of current setpoint
-//     setCurrentSafeSetpoint(setpoint_msg);
-// }
-
-// void landCF(CrazyflieData& current_local_coordinates)
-// {
-//     // set the setpoint and call safe controller
-//     Setpoint setpoint_msg;
-//     setpoint_msg.x = current_local_coordinates.x;           // previous one
-//     setpoint_msg.y = current_local_coordinates.y;           //previous one
-//     setpoint_msg.z = yaml_landing_distance;           //previous one plus some offset
-//     setpoint_msg.yaw = current_local_coordinates.yaw;          //previous one
-//     safeControllerServiceSetpointPublisher.publish(setpoint_msg);
-
-//     // now, use safe controller to go to that setpoint
-//     loadSafeController();
-//     setInstantController(SAFE_CONTROLLER);
-//     setCurrentSafeSetpoint(setpoint_msg);
-// }
-
-
-
-
-// void goToControllerSetpoint()
-// {
-//     safeControllerServiceSetpointPublisher.publish(controller_setpoint);
-//     setCurrentSafeSetpoint(controller_setpoint);
-// }
-
-
-//is called when new data from Vicon arrives
+// CALLBACK RUN EVERY TIME NEW MOTION CAPTURE DATA IS RECEIVED
 void viconCallback(const ViconData& viconData)
 {
-    // NOTE: THIS FUNCTION IS CALL AT THE FREQUENCY OF THE MOTION
-    //       CAPTURE SYSTEM. HENCE ANY OPTERATIONS PERFORMED IN
-    //       THIS FUNCTION MUST BE NON-BLOCKING.
+	// NOTE: THIS FUNCTION IS CALL AT THE FREQUENCY OF THE MOTION
+	//       CAPTURE SYSTEM. HENCE ANY OPTERATIONS PERFORMED IN
+	//       THIS FUNCTION MUST BE NON-BLOCKING.
 
-    // Initialise a counter of consecutive frames of motion
-    // capture data where the agent is occuled
-    static int number_of_consecutive_occulsions = 0;
+	// Initialise a counter of consecutive frames of motion
+	// capture data where the agent is occuled
+	static int number_of_consecutive_occulsions = 0;
 
-    // Initilise a variable for the pose data of this agent
-    CrazyflieData poseDataForThisAgent;
+	// Initilise a variable for the pose data of this agent
+	CrazyflieData poseDataForThisAgent;
 
-    // Extract the pose data from the full motion capture array
-    // NOTE: that if the return index is a negative then this
-    //       indicates that the pose data was not found.
-    m_poseDataIndex = getPoseDataForObjectNameWithExpectedIndex( viconData, m_context.crazyflieName , m_poseDataIndex , poseDataForThisAgent );
+	// Extract the pose data from the full motion capture array
+	// NOTE: that if the return index is a negative then this
+	//       indicates that the pose data was not found.
+	m_poseDataIndex = getPoseDataForObjectNameWithExpectedIndex( viconData, m_context.crazyflieName , m_poseDataIndex , poseDataForThisAgent );
 
 
-    // Detecting time-out of the motion capture data
-    // > Update the flag
-    m_isAvailable_mocap_data = true;
-    // > Stop any previous instance that might still be running
-    m_timer_mocap_timeout_check.stop();
-    // > Set the period again (second argument is reset)
-    m_timer_mocap_timeout_check.setPeriod( ros::Duration(yaml_mocap_timeout_duration), true);
-    // > Start the timer again
-    m_timer_mocap_timeout_check.start();
-
-
-    // Only continue if:
-    // (1) the pose for this agent was found, and
-    // (2) the flying state is something other than MOTORS-OFF
-    if (
-        (m_poseDataIndex >= 0)
-        and
-        (m_flying_state != STATE_MOTORS_OFF)
-        and
-        (m_controllers_avialble)
-    )
-    {
-        // Initliase the "Contrller" service call variable
-        Controller controllerCall;
-
-        // Fill in the pose data for this agent
-        controllerCall.request.ownCrazyflie = poseDataForThisAgent;
-
-        // Initialise a node handle, needed for starting timers
-        ros::NodeHandle nodeHandle("~");
-
-        // If the object is NOT occluded,
-        // then proceed to make the "Controller Service Call" that
-        // compute the controller output.
-        if(!poseDataForThisAgent.occluded)
-        {
-        	// Reset the "consecutive occulsions" flag
-        	number_of_consecutive_occulsions = 0;
+	// Detecting time-out of the motion capture data
+	// > Update the flag
+	m_isAvailable_mocap_data = true;
+	// > Stop any previous instance that might still be running
+	m_timer_mocap_timeout_check.stop();
+	// > Set the period again (second argument is reset)
+	m_timer_mocap_timeout_check.setPeriod( ros::Duration(yaml_mocap_timeout_duration), true);
+	// > Start the timer again
+	m_timer_mocap_timeout_check.start();
+
+
+	// Only continue if:
+	// (1) the pose for this agent was found, and
+	// (2) the flying state is something other than MOTORS-OFF
+	if (
+		(m_poseDataIndex >= 0)
+		and
+		(m_flying_state != STATE_MOTORS_OFF)
+		and
+		(m_controllers_avialble)
+	)
+	{
+		// Initliase the "Contrller" service call variable
+		Controller controllerCall;
 
-            // PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
-            if ( getInstantController() != DEFAULT_CONTROLLER )
-            {
-                if ( !safetyCheck(poseDataForThisAgent) )
-                {
-                    setInstantController(DEFAULT_CONTROLLER);
-                    ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to DEFAULT CONTROLLER");
-                }
-            }
+		// Fill in the pose data for this agent
+		controllerCall.request.ownCrazyflie = poseDataForThisAgent;
 
-            // Initialise a local boolean success variable
-            bool isSuccessful_controllerCall = false;
+		// If the object is NOT occluded,
+		// then proceed to make the "Controller Service Call" that
+		// compute the controller output.
+		if(!poseDataForThisAgent.occluded)
+		{
+			// Reset the "consecutive occulsions" flag
+			number_of_consecutive_occulsions = 0;
 
+			// PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
+			if ( getInstantController() != DEFAULT_CONTROLLER )
+			{
+				if ( !safetyCheck_on_positionAndTilt(poseDataForThisAgent) )
+				{
+					setInstantController(DEFAULT_CONTROLLER);
+					ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to DEFAULT CONTROLLER");
+				}
+			}
 
+			// Initialise a local boolean success variable
+			bool isSuccessful_controllerCall = false;
 
-            isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+			// Call the controller service client
+			isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
 
-            // Ensure success and enforce safety
-            if(!isSuccessful_controllerCall)
-            {
-                // Let the user know that the controller call failed
-                ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
-
-                // Switch to the default controller,
-                // if it was not already the active controller
-                if ( getInstantController() != DEFAULT_CONTROLLER )
-                {
-                    // Set the DEFAULT controller to be active
-                    setInstantController(DEFAULT_CONTROLLER);
-                    // Try the controller call
-                    isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
-                    // Inform the user is not successful
-                    if ( !isSuccessful_controllerCall )
-                    {
-                        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Also failed to call the DEFAULT controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
-                    }
-                }
-            }
+			// Ensure success and enforce safety
+			if(!isSuccessful_controllerCall)
+			{
+				// Let the user know that the controller call failed
+				ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+
+				// Switch to the default controller,
+				// if it was not already the active controller
+				if ( getInstantController() != DEFAULT_CONTROLLER )
+				{
+					// Set the DEFAULT controller to be active
+					setInstantController(DEFAULT_CONTROLLER);
+					// Try the controller call
+					isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+					// Inform the user is not successful
+					if ( !isSuccessful_controllerCall )
+					{
+						ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Also failed to call the DEFAULT controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+					}
+				}
+			}
 
-            // Send the command to the CrazyRadio
-            // > IF SUCCESSFUL
-            if (isSuccessful_controllerCall)
-            {
-                m_commaNdfOrsendiNgTocrazyflIepublisher.publish(controllerCall.response.controlOutput);
-            }
-            // > ELSE SEND ZERO OUTPUT COMMAND
-            else
-            {
-                // Send the command to turn the motors off
-                sendZeroOutputCommandForMotors();
-                // And change the state to motor-off
-                changeFlyingStateTo(STATE_MOTORS_OFF);
-            }
+			// Send the command to the CrazyRadio
+			// > IF SUCCESSFUL
+			if (isSuccessful_controllerCall)
+			{
+				m_commaNdfOrsendiNgTocrazyflIepublisher.publish(controllerCall.response.controlOutput);
+			}
+			// > ELSE SEND ZERO OUTPUT COMMAND
+			else
+			{
+				// Send the command to turn the motors off
+				sendZeroOutputCommandForMotors();
+				// And change the state to motor-off
+				requestChangeFlyingStateTo(STATE_MOTORS_OFF);
+			}
 		}
 		else
 		{
@@ -246,17 +196,17 @@ void viconCallback(const ViconData& viconData)
 				// Update the flag
 				m_isOcculded_mocap_data = true;
 				// Send the command to turn the motors off
-		        sendZeroOutputCommandForMotors();
-		        // Update the flying state
-		        changeFlyingStateTo( STATE_MOTORS_OFF );
+				sendZeroOutputCommandForMotors();
+				// Update the flying state
+				requestChangeFlyingStateTo( STATE_MOTORS_OFF );
 			}
-        } // END OF: "if(!global.occluded)"
+		} // END OF: "if(!poseDataForThisAgent.occluded)"
 
-    }
-    else
-    {
-        // Send the command to turn the motors off
-        sendZeroOutputCommandForMotors();
+	}
+	else
+	{
+		// Send the command to turn the motors off
+		sendZeroOutputCommandForMotors();
 
 	} // END OF: "if ( (m_poseDataIndex >= 0) and (m_flying_state != STATE_MOTORS_OFF) )"
 
@@ -338,7 +288,7 @@ void coordinatesToLocal(CrazyflieData& cf)
 void timerCallback_mocap_timeout_check(const ros::TimerEvent&)
 {
 	// Update the flag
-	m_isAvailable_mocap_data = true;
+	m_isAvailable_mocap_data = false;
 	// Inform the user
 	ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Motion Capture Data has been unavailable for " << yaml_mocap_timeout_duration << " seconds." );
 	// Ensure that the motors are turned off
@@ -347,7 +297,7 @@ void timerCallback_mocap_timeout_check(const ros::TimerEvent&)
 		// Send the command to turn the motors off
         sendZeroOutputCommandForMotors();
         // Update the flying state
-        changeFlyingStateTo( STATE_MOTORS_OFF );
+        requestChangeFlyingStateTo( STATE_MOTORS_OFF );
 	}
 }
 
@@ -363,42 +313,75 @@ void sendZeroOutputCommandForMotors()
 
 
 
+//    ----------------------------------------------------------------------------------
+//     SSSS    A    FFFFF  EEEEE  TTTTT  Y   Y
+//    S       A A   F      E        T     Y Y
+//     SSS   A   A  FFF    EEE      T      Y
+//        S  AAAAA  F      E        T      Y
+//    SSSS   A   A  F      EEEEE    T      Y
+//
+//     CCCC  H   H  EEEEE   CCCC  K   K   SSSS
+//    C      H   H  E      C      K  K   S
+//    C      HHHHH  EEE    C      KKK     SSS
+//    C      H   H  E      C      K  K       S
+//     CCCC  H   H  EEEEE   CCCC  K   K  SSSS
+//    ----------------------------------------------------------------------------------
 
-
-
-
-void changeFlyingStateTo(int new_state)
+// Checks if crazyflie is within allowed area
+bool safetyCheck_on_positionAndTilt(CrazyflieData data)
 {
-    if(crazyradio_status == CRAZY_RADIO_STATE_CONNECTED)
+    // Check on the X position
+    if((data.x < m_context.localArea.xmin) or (data.x > m_context.localArea.xmax))
     {
-        ROS_INFO("[FLYING AGENT CLIENT] Change state to: %d", new_state);
-        m_flying_state== = new_state;
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] x safety failed");
+        return false;
     }
-    else
+    // Check on the Y position
+    if((data.y < m_context.localArea.ymin) or (data.y > m_context.localArea.ymax))
     {
-        ROS_INFO("[FLYING AGENT CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
-        m_flying_state = STATE_MOTORS_OFF;
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] y safety failed");
+        return false;
+    }
+    // Check on the Z position
+    if((data.z < m_context.localArea.zmin) or (data.z > m_context.localArea.zmax))
+    {
+        ROS_INFO_STREAM("[FLYING AGENT CLIENT] z safety failed");
+        return false;
     }
 
-    // Set the class variable flag that the
-    // flying state was changed
-    //m_changed_flying_state_flag = true;
-
-    // Publish a message with the new flying state
-    std_msgs::Int32 flying_state_msg;
-    flying_state_msg.data = m_flying_state;
-    flyingStatePublisher.publish(flying_state_msg);
-}
-
-
-void takeOffTimerCallback(const ros::TimerEvent&)
-{
-    //finished_take_off = true;
-}
+    // Check the title angle (if required)
+    // > The tilt anlge between the body frame and inertial frame z-axis is
+    //   give by:
+    //   tilt angle  =  1 / ( cos(roll)*cos(pitch) )
+    // > But this would be too sensitve to a divide by zero error, so instead
+    //   we just check if each angle separately exceeds the limit
+    if(yaml_isEnabled_strictSafety)
+    {
+        // Check on the ROLL angle
+        if(
+            (data.roll > m_maxTiltAngle_for_strictSafety_redians)
+            or
+            (data.roll < -m_maxTiltAngle_for_strictSafety_redians)
+        )
+        {
+            ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
+            return false;
+        }
+        // Check on the PITCH angle
+        if(
+            (data.pitch > m_maxTiltAngle_for_strictSafety_redians)
+            or
+            (data.pitch < -m_maxTiltAngle_for_strictSafety_redians)
+        )
+        {
+            ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
+            return false;
+        }
+    }
 
-void landTimerCallback(const ros::TimerEvent&)
-{
-    //finished_land = true;
+    // If the code makes it to here then all the safety checks passed,
+    // Hence return "true"
+    return true;
 }
 
 
@@ -408,89 +391,252 @@ void landTimerCallback(const ros::TimerEvent&)
 
 
 
+//    ----------------------------------------------------------------------------------
+//    FFFFF L      Y   Y  III  N   N   GGGG
+//    F     L       Y Y    I   NN  N  G
+//    FFF   L        Y     I   N N N  G
+//    F     L        Y     I   N  NN  G   G
+//    F     LLLLL    Y    III  N   N   GGGG
+//
+//     SSSS  TTTTT    A    TTTTT  EEEEE
+//    S        T     A A     T    E
+//     SSS     T    A   A    T    EEE
+//        S    T    AAAAA    T    E
+//    SSSS     T    A   A    T    EEEEE
+//    ----------------------------------------------------------------------------------
 
 
+void requestChangeFlyingStateTo(int new_state)
+{
+    if(m_crazyradio_status != CRAZY_RADIO_STATE_CONNECTED)
+    {
+        ROS_INFO("[FLYING AGENT CLIENT] Disconnected and trying to change state. State goes to MOTORS OFF");
+        m_flying_state = STATE_MOTORS_OFF;
+    }
+    else
+    {
+        // Switch between the possible new states
+        switch (new_state)
+        {
+        	case STATE_TAKE_OFF:
+        	{
+        		requestChangeFlyingStateToTakeOff();
+        		break;
+        	}
+
+        	case STATE_FLYING:
+        	{
+        		// This should never be called
+        		break;
+        	}
+
+        	case STATE_LAND:
+        	{
+        		requestChangeFlyingStateToLand();
+        		break;
+        	}
+
+        	case STATE_MOTORS_OFF:
+        	{
+        		ROS_INFO("[FLYING AGENT CLIENT] Change state to MOTORS OFF");
+        		m_flying_state = new_state;
+        		break;
+        	}
+
+        	default:
+        	{
+        		ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Request state of " << new_state << " not recognised. Hence changing to MOTORS OFF.");
+        		m_flying_state = new_state;
+        		break;
+        	}
+        }
 
+    }
 
+    // Publish a message with the new flying state
+    std_msgs::Int32 flying_state_msg;
+    flying_state_msg.data = m_flying_state;
+    flyingStatePublisher.publish(flying_state_msg);
+}
 
+void requestChangeFlyingStateToTakeOff()
+{
+	// Only allow taking off from the MOTORS OFF state
+	if (m_flying_state != STATE_MOTORS_OFF)
+	{
+		ROS_ERROR("[FLYING AGENT CLIENT] Request to TAKE OFF was not implemented because the current state is NOT the MOTORS OFF state.");
+	}
+	else
+	{
+		// Check that the Motion Capture data is available
+		if ( m_isAvailable_mocap_data and !m_isOcculded_mocap_data )
+		{
+			// Check whether a "controller" take-off should
+			// be performed, and that not already in the
+			// "take-off" state
+			if (
+				(yaml_shouldPerfom_takeOff_with_defaultController)
+				and
+				(m_flying_state != STATE_TAKE_OFF)
+			)
+			{
+				// Call the service offered by the default
+				// controller for how long a take-off will take
+				dfall_pkg::IntIntService requestManoeurveCall;
+				requestManoeurveCall.request.data = DEFAULT_CONTROLLER_REQUEST_TAKE_OFF;
+				if(m_defaultController_requestManoeuvre.call(requestManoeurveCall))
+				{
+					// Extract the duration
+					float take_off_duration = float(requestManoeurveCall.response.data) / 1000.0;
+					// Start the timer
+					// > Stop any previous instance
+					m_timer_takeoff_complete.stop();
+					// > Set the period again (second argument is reset)
+					m_timer_takeoff_complete.setPeriod( ros::Duration(take_off_duration), true);
+					// > Start the timer
+					m_timer_takeoff_complete.start();
+					// Inform the user
+					ROS_INFO_STREAM("[FLYING AGENT CLIENT] Changed state to STATE_TAKE_OFF for a duration of " << take_off_duration << " seconds.");
+					// Update the class variable
+					m_flying_state = STATE_TAKE_OFF;
+				}
+				else
+				{
+					// Inform the user
+					ROS_INFO("[FLYING AGENT CLIENT] Failed to get take-off duration from Default controller. Switching to MOTORS-OFF.");
+					// Update the class variable
+					m_flying_state = STATE_MOTORS_OFF;
+				}
+			}
+			// Otherwise, just switch straight to the
+			// "flying" state
+			else
+			{
+				// Inform the user
+				ROS_INFO("[FLYING AGENT CLIENT] Changed state directly to STATE_FLYING");
+				// Update the class variable
+				m_flying_state = STATE_FLYING;
+			}
+		}
+		else
+		{
+			// Inform the user of the problem
+			if (!m_isAvailable_mocap_data)
+			{
+				ROS_ERROR("[FLYING AGENT CLIENT] Take-off not possible because the motion capture data is unavailable.");
+			}
+			if (m_isOcculded_mocap_data)
+			{
+				ROS_ERROR("[FLYING AGENT CLIENT] Take-off not possible because the object is \"long-term\" occuled.");
+			}
+		}
+	}
+}
 
 
+void requestChangeFlyingStateToLand()
+{
+	// Only allow landing from the TAKE-OFF and FLYING state
+	if (
+		(m_flying_state != STATE_TAKE_OFF)
+		and
+		(m_flying_state != STATE_FLYING)
+	)
+	{
+		ROS_ERROR("[FLYING AGENT CLIENT] Request to LAND was not implemented because the current state is NOT the TAKE-OFF or FLYING state.");
+	}
+	else
+	{
+		// Check whether a "controller" take-off should
+		// be performed, and that not already in the
+		// "land" state
+		if (
+			(yaml_shouldPerfom_landing_with_defaultController)
+			and
+			(m_flying_state != STATE_LAND)
+		)
+		{
+			// Call the service offered by the default
+			// controller for how long a landing will take
+			dfall_pkg::IntIntService requestManoeurveCall;
+			requestManoeurveCall.request.data = DEFAULT_CONTROLLER_REQUEST_LANDING;
+			if(m_defaultController_requestManoeuvre.call(requestManoeurveCall))
+			{
+				// Extract the duration
+				float land_duration = float(requestManoeurveCall.response.data) / 1000.0;
+				// Start the timer
+				// > Stop any previous instance
+				m_timer_land_complete.stop();
+				// > Set the period again (second argument is reset)
+				m_timer_land_complete.setPeriod( ros::Duration(take_off_duration), true);
+				// > Start the timer
+				m_timer_land_complete.start();
+				// Inform the user
+				ROS_INFO_STREAM("[FLYING AGENT CLIENT] Changed state to STATE_TAKE_OFF for a duration of " << land_duration << " seconds.");
+				// Update the class variable
+				m_flying_state = STATE_LAND;
+			}
+			else
+			{
+				// Inform the user
+				ROS_INFO("[FLYING AGENT CLIENT] Failed to get take-off duration from Default controller. Switching to MOTORS-OFF.");
+				// Update the class variable
+				m_flying_state = STATE_MOTORS_OFF;
+			}
+		}
+		// Otherwise, just switch straight to the
+		// "motors off" state
+		else
+		{
+			// Inform the user
+			ROS_INFO("[FLYING AGENT CLIENT] Changed state directly to STATE_MOTORS_OFF");
+			// Update the class variable
+			m_flying_state = STATE_MOTORS_OFF;
+		}
+	}
+}
 
 
+void timerCallback_takeoff_complete(const ros::TimerEvent&)
+{
+    // Only change to flying if still in the take-off state
+    if (m_flying_state == STATE_TAKE_OFF)
+	{
+		// Inform the user
+		ROS_INFO("[FLYING AGENT CLIENT] Take-off complete, changed state to STATE_FLYING");
+		// Update the class variable
+		m_flying_state = STATE_FLYING;
+	}
+	else
+	{
+		// Inform the user
+		ROS_INFO("[FLYING AGENT CLIENT] Take-off duration elapsed but the agent is no longer in STATE_TAKE_OFF.");
+	}
+}
 
-
-
-
-
-
-
-
-//    ----------------------------------------------------------------------------------
-//    L       OOO     A    DDDD
-//    L      O   O   A A   D   D
-//    L      O   O  A   A  D   D
-//    L      O   O  AAAAA  D   D
-//    LLLLL   OOO   A   A  DDDD
-//
-//
-//     CCCC   OOO   N   N  TTTTT  RRRR    OOO   L      L      EEEEE  RRRR
-//    C      O   O  NN  N    T    R   R  O   O  L      L      E      R   R
-//    C      O   O  N N N    T    RRRR   O   O  L      L      EEE    RRRR
-//    C      O   O  N  NN    T    R   R  O   O  L      L      E      R   R
-//     CCCC   OOO   N   N    T    R   R   OOO   LLLLL  LLLLL  EEEEE  R   R
-//    ----------------------------------------------------------------------------------
-
-
-// CREATE A "CONTROLLER" TYPE SERVICE CLIENT
-// NOTE: that in the "ros::service::createClient" function the
-//       second argument is a boolean that specifies whether the 
-//       service is persistent or not. In the ROS documentation a
-//       persistent connection is described as:
-//   "Persistent connections should be used carefully. They greatly
-//    improve performance for repeated requests, but they also make
-//    your client more fragile to service failures. Clients using
-//    persistent connections should implement their own reconnection
-//    logic in the event that the persistent connection fails."
-void loadController( std::string paramter_name , ros::ServiceClient& serviceClient )
+void timerCallback_land_complete(const ros::TimerEvent&)
 {
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    // Only change to flying if still in the take-off state
+    if (m_flying_state == STATE_LAND)
+	{
+		// Inform the user
+		ROS_INFO("[FLYING AGENT CLIENT] Land complete, changed state to STATE_MOTORS_OFF");
+		// Update the class variable
+		m_flying_state = STATE_MOTORS_OFF;
+	}
+	else
+	{
+		// Inform the user
+		ROS_INFO("[FLYING AGENT CLIENT] Land duration elapsed but the agent is no longer in STATE_LAND.");
+	}
+}
+
 
-    std::string controllerName;
-    if(!nodeHandle.getParam(paramter_name, controllerName))
-    {
-        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to get \"" << paramter_name << "\" paramter");
-        return;
-    }
 
-    serviceClient = ros::service::createClient<Controller>(controllerName, true);
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded service: " << serviceClient.getService() <<  ", valid: " << serviceClient.isValid() << ", exists: " << serviceClient.exists() );
-}
 
 
 
-void timerCallback_for_creaTeaLlcontrollerServiceClients(const ros::TimerEvent&)
-{
-    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
-    loadController( "defaultController"  , defaultController );
-    loadController( "studentController"  , studentController );
-    loadController( "tuningController"   , tuningController );
-    loadController( "pickerController"   , pickerController );
-    loadController( "templateController" , templateController );
 
-    // Check that at least the default controller is available
-    // > Setting the flag accordingly
-    if (defaultController)
-    {
-        m_controllers_avialble = true;
-    }
-    else
-    {
-        m_controllers_avialble = false;
-        // Inform the user of the problem
-        ROS_ERROR("[FLYING AGENT CLIENT] The default controller service client (and pressumably all other controllers) could NOT be created.");
-    }
-}
 
 
 
@@ -513,52 +659,60 @@ void timerCallback_for_creaTeaLlcontrollerServiceClients(const ros::TimerEvent&)
 //    ----------------------------------------------------------------------------------
 
 
-
-void sendMessageUsingController(int controller)
-{
-    // Send a message on the topic for informing the Flying
-    // Agent GUI about this update
-    std_msgs::Int32 controller_used_msg;
-    controller_used_msg.data = controller;
-    controllerUsedPublisher.publish(controller_used_msg);
-}
-
-void setInstantController(int controller) //for right now, temporal use
+// THIS SETS THE CONTROLLER THAT IT ACTUALLY BEING USED
+// > During take-off and landing this function is
+//   called to switch to the "Default" controller
+// > The highlighting in the "Flying Agent GUI" should
+//   reflect the instant controller   
+void setInstantController(int controller)
 {
     // Update the class variable
     m_instant_controller = controller;
 
-    
-
+    // Point to the correct service client
     switch(controller)
     {
         case DEFAULT_CONTROLLER:
-            m_instant_controller_service_client = &defaultController;
+            m_instant_controller_service_client = &m_defaultController;
             break;
         case STUDENT_CONTROLLER:
-            m_instant_controller_service_client = &studentController;
+            m_instant_controller_service_client = &m_studentController;
             break;
         case TUNING_CONTROLLER:
-            m_instant_controller_service_client = &tuningController;
+            m_instant_controller_service_client = &m_tuningController;
             break;
         case PICKER_CONTROLLER:
-            m_instant_controller_service_client = &pickerController;
+            m_instant_controller_service_client = &m_pickerController;
             break;
         case TEMPLATE_CONTROLLER:
-            m_instant_controller_service_client = &templateController;
+            m_instant_controller_service_client = &m_templateController;
             break;
         default:
             break;
     }
 
-    sendMessageUsingController(controller);
+    // Publish a message that informs the "Flying Agent
+    // GUI" about this update to the instant controller
+    std_msgs::Int32 controller_used_msg;
+    controller_used_msg.data = controller;
+    controllerUsedPublisher.publish(controller_used_msg);
 }
 
+
+// THIS SIMPLY RETRIEVES THE CLASS VARIABLE
 int getInstantController()
 {
     return m_instant_controller;
 }
 
+
+// THIS SETS THE CONTROLLER THAT IS NOMINALLY SELECTED
+// > This is the controller that will be use as the
+//   "instant controller" when in the "flying" state.
+// > But during take-off and landing, the "Default"
+//   controller is used, and this keeps track of which
+//   controller to switch to after those phases are
+//   complete
 void setControllerNominallySelected(int controller)
 {
     // Update the class variable
@@ -566,13 +720,19 @@ void setControllerNominallySelected(int controller)
 
     // If in state "MOTORS-OFF" or "FLYING",
     // then the change is instant.
-    if(m_flying_state == STATE_MOTORS_OFF || m_flying_state == STATE_FLYING)
+    if (
+    	(m_flying_state == STATE_MOTORS_OFF)
+    	or
+    	(m_flying_state == STATE_FLYING)
+	)
     {
 
         setInstantController(controller); 
     }
 }
 
+
+// THIS SIMPLY RETRIEVES THE CLASS VARIABLE
 int getControllerNominallySelected()
 {
     return m_controller_nominally_selected;
@@ -587,6 +747,31 @@ int getControllerNominallySelected()
 
 
 
+//    ----------------------------------------------------------------------------------
+//     SSSS  TTTTT    A    TTTTT  EEEEE
+//    S        T     A A     T    E
+//     SSS     T    A   A    T    EEE
+//        S    T    AAAAA    T    E
+//    SSSS     T    A   A    T    EEEEE
+//
+//     CCCC    A    L      L      BBBB     A     CCCC  K   K
+//    C       A A   L      L      B   B   A A   C      K  K
+//    C      A   A  L      L      BBBB   A   A  C      KKK
+//    C      AAAAA  L      L      B   B  AAAAA  C      K  K
+//     CCCC  A   A  LLLLL  LLLLL  BBBB   A   A   CCCC  K   K
+//
+//    FFFFF  RRRR    OOO   M   M      GGGG  U   U  III
+//    F      R   R  O   O  MM MM     G      U   U   I
+//    FFF    RRRR   O   O  M M M     G      U   U   I
+//    F      R   R  O   O  M   M     G   G  U   U   I
+//    F      R   R   OOO   M   M      GGGG   UUU   III
+//    ----------------------------------------------------------------------------------
+
+
+
+// THE CALLBACK THAT A NEW FLYING STATE WAS REQUESTED
+// > These requests come from the "Flying Agent GUI"
+// > The options are: {take-off,land,motor-off,controller}
 void flyingStateRequestCallback(const IntWithHeader & msg) {
 
     // Check whether the message is relevant
@@ -641,22 +826,16 @@ void flyingStateRequestCallback(const IntWithHeader & msg) {
 
             case CMD_CRAZYFLY_TAKE_OFF:
                 ROS_INFO("[FLYING AGENT CLIENT] TAKE_OFF Command received");
-                if(m_flying_state == STATE_MOTORS_OFF)
-                {
-                    changeFlyingStateTo(STATE_TAKE_OFF);
-                }
+                requestChangeFlyingStateTo(STATE_TAKE_OFF);
                 break;
 
             case CMD_CRAZYFLY_LAND:
                 ROS_INFO("[FLYING AGENT CLIENT] LAND Command received");
-                if(m_flying_state != STATE_MOTORS_OFF)
-                {
-                    changeFlyingStateTo(STATE_LAND);
-                }
+                requestChangeFlyingStateTo(STATE_LAND);
                 break;
             case CMD_CRAZYFLY_MOTORS_OFF:
                 ROS_INFO("[FLYING AGENT CLIENT] MOTORS_OFF Command received");
-                changeFlyingStateTo(STATE_MOTORS_OFF);
+                requestChangeFlyingStateTo(STATE_MOTORS_OFF);
                 break;
 
             default:
@@ -676,7 +855,7 @@ void flyingStateRequestCallback(const IntWithHeader & msg) {
 void crazyRadioStatusCallback(const std_msgs::Int32& msg)
 {
     ROS_INFO_STREAM("[FLYING AGENT CLIENT] Received message with Crazy Radio Status = " << msg.data );
-    crazyradio_status = msg.data;
+    m_crazyradio_status = msg.data;
 }
 
 
@@ -721,13 +900,6 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn
 
 
 
-
-
-
-
-
-
-
 //    ----------------------------------------------------------------------------------
 //    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
 //    B   B   A A     T      T    E      R   R   Y Y
@@ -747,7 +919,7 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
         if (m_flying_state != STATE_MOTORS_OFF)
         {
             ROS_INFO("[FLYING AGENT CLIENT] low level battery triggered, now landing.");
-            changeFlyingStateTo(STATE_LAND);
+            requestChangeFlyingStateTo(STATE_LAND);
         }
         else
         {
@@ -771,76 +943,7 @@ void batteryMonitorStateChangedCallback(std_msgs::Int32 msg)
 
 
 
-//    ----------------------------------------------------------------------------------
-//     SSSS    A    FFFFF  EEEEE  TTTTT  Y   Y
-//    S       A A   F      E        T     Y Y
-//     SSS   A   A  FFF    EEE      T      Y
-//        S  AAAAA  F      E        T      Y
-//    SSSS   A   A  F      EEEEE    T      Y
-//
-//     CCCC  H   H  EEEEE   CCCC  K   K   SSSS
-//    C      H   H  E      C      K  K   S
-//    C      HHHHH  EEE    C      KKK     SSS
-//    C      H   H  E      C      K  K       S
-//     CCCC  H   H  EEEEE   CCCC  K   K  SSSS
-//    ----------------------------------------------------------------------------------
-
-// Checks if crazyflie is within allowed area
-bool safetyCheck(CrazyflieData data)
-{
-    // Check on the X position
-    if((data.x < m_context.localArea.xmin) or (data.x > m_context.localArea.xmax))
-    {
-        ROS_INFO_STREAM("[FLYING AGENT CLIENT] x safety failed");
-        return false;
-    }
-    // Check on the Y position
-    if((data.y < m_context.localArea.ymin) or (data.y > m_context.localArea.ymax))
-    {
-        ROS_INFO_STREAM("[FLYING AGENT CLIENT] y safety failed");
-        return false;
-    }
-    // Check on the Z position
-    if((data.z < m_context.localArea.zmin) or (data.z > m_context.localArea.zmax))
-    {
-        ROS_INFO_STREAM("[FLYING AGENT CLIENT] z safety failed");
-        return false;
-    }
-
-    // Check the title angle (if required)
-    // > The tilt anlge between the body frame and inertial frame z-axis is
-    //   give by:
-    //   tilt angle  =  1 / ( cos(roll)*cos(pitch) )
-    // > But this would be too sensitve to a divide by zero error, so instead
-    //   we just check if each angle separately exceeds the limit
-    if(yaml_isEnabled_strictSafety)
-    {
-        // Check on the ROLL angle
-        if(
-            (data.roll > m_maxTiltAngle_for_strictSafety_redians)
-            or
-            (data.roll < -m_maxTiltAngle_for_strictSafety_redians)
-        )
-        {
-            ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
-            return false;
-        }
-        // Check on the PITCH angle
-        if(
-            (data.pitch > m_maxTiltAngle_for_strictSafety_redians)
-            or
-            (data.pitch < -m_maxTiltAngle_for_strictSafety_redians)
-        )
-        {
-            ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
-            return false;
-        }
-    }
 
-    // If the code makes it to here then all the safety checks passed,
-    // Hence return "true"
-    return true;
-}
 
 
 
@@ -916,6 +1019,84 @@ void loadCrazyflieContext()
 
 
 
+//    ----------------------------------------------------------------------------------
+//     CCCC  RRRR   EEEEE    A    TTTTT  EEEEE
+//    C      R   R  E       A A     T    E
+//    C      RRRR   EEE    A   A    T    EEE
+//    C      R   R  E      AAAAA    T    E
+//     CCCC  R   R  EEEEE  A   A    T    EEEEE
+//
+//     SSSS  EEEEE  RRRR   V   V  III   CCCC  EEEEE
+//    S      E      R   R  V   V   I   C      E
+//     SSS   EEE    RRRR   V   V   I   C      EEE
+//        S  E      R   R   V V    I   C      E
+//    SSSS   EEEEE  R   R    V    III   CCCC  EEEEE
+//
+//     CCCC  L      III  EEEEE  N   N  TTTTT
+//    C      L       I   E      NN  N    T
+//    C      L       I   EEE    N N N    T
+//    C      L       I   E      N  NN    T
+//     CCCC  LLLLL  III  EEEEE  N   N    T
+//    ----------------------------------------------------------------------------------
+
+
+// CREATE A "CONTROLLER" TYPE SERVICE CLIENT
+// NOTE: that in the "ros::service::createClient" function the
+//       second argument is a boolean that specifies whether the 
+//       service is persistent or not. In the ROS documentation a
+//       persistent connection is described as:
+//   "Persistent connections should be used carefully. They greatly
+//    improve performance for repeated requests, but they also make
+//    your client more fragile to service failures. Clients using
+//    persistent connections should implement their own reconnection
+//    logic in the event that the persistent connection fails."
+void createControllerServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient )
+{
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+    std::string controllerName;
+    if(!nodeHandle.getParam(paramter_name, controllerName))
+    {
+        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to get \"" << paramter_name << "\" paramter");
+        return;
+    }
+
+    serviceClient = ros::service::createClient<Controller>(controllerName, true);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded service: " << serviceClient.getService() <<  ", valid: " << serviceClient.isValid() << ", exists: " << serviceClient.exists() );
+}
+
+
+
+void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&)
+{
+    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
+    createControllerServiceClientFromParameterName( "defaultController"  , m_defaultController );
+    createControllerServiceClientFromParameterName( "studentController"  , m_studentController );
+    createControllerServiceClientFromParameterName( "tuningController"   , m_tuningController );
+    createControllerServiceClientFromParameterName( "pickerController"   , m_pickerController );
+    createControllerServiceClientFromParameterName( "templateController" , m_templateController );
+
+    // INITIALISE THE SERVICE FOR REQUESTING THE DEFAULT
+    // CONTROLLER TO PERFORM MANOEUVRES
+    createControllerServiceClientFromParameterName( "defaultController_requestManoeuvre" , m_defaultController_requestManoeuvre );
+
+    // Check that at least the default controller is available
+    // > Setting the flag accordingly
+    if (defaultController)
+    {
+        m_controllers_avialble = true;
+    }
+    else
+    {
+        m_controllers_avialble = false;
+        // Inform the user of the problem
+        ROS_ERROR("[FLYING AGENT CLIENT] The default controller service client (and pressumably all other controllers) could NOT be created.");
+    }
+}
+
+
+
 
 
 //    ----------------------------------------------------------------------------------
@@ -991,6 +1172,18 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
     // Flag for whether to use angle for switching to the Safe Controller
     yaml_isEnabled_strictSafety = getParameterBool(nodeHandle_for_paramaters,"isEnabled_strictSafety");
     yaml_maxTiltAngle_for_strictSafety_degrees = getParameterFloat(nodeHandle_for_paramaters,"maxTiltAngle_for_strictSafety_degrees");
+
+    // Number of consecutive occulsions that will deem the
+    // object as "long-term" occuled
+	consecutive_occulsions_threshold = getParameterInt(nodeHandle_for_paramaters,"consecutive_occulsions_threshold");
+
+	// Flag for whether the take-off should be performed
+	//  with the default controller
+	yaml_shouldPerfom_takeOff_with_defaultController = getParameterBool(nodeHandle_for_paramaters,"shouldPerfom_takeOff_with_defaultController");
+
+	// Flag for whether the landing should be performed
+	// with the default controller
+	yaml_shouldPerfom_landing_with_defaultController = getParameterBool(nodeHandle_for_paramaters,"shouldPerfom_landing_with_defaultController");
     
     // DEBUGGING: Print out one of the parameters that was loaded
     ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched ClientConfig/isEnabled_strictSafety = " << yaml_isEnabled_strictSafety);
@@ -1106,7 +1299,7 @@ int main(int argc, char* argv[])
     //   seconds and in the call back all the controller service
     //   clients are created.
     m_controllers_avialble = false;
-    m_timer_for_createAllControllerServiceClients = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_creaTeaLlcontrollerServiceClients, true);
+    m_timer_for_createAllControllerServiceClients = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_createAllcontrollerServiceClients, true);
 
 
 
@@ -1199,7 +1392,7 @@ int main(int argc, char* argv[])
 
 
     // crazy radio status
-    crazyradio_status = CRAZY_RADIO_STATE_DISCONNECTED;
+    m_crazyradio_status = CRAZY_RADIO_STATE_DISCONNECTED;
 
     // publish first flying state data
     std_msgs::Int32 flying_state_msg;
@@ -1249,7 +1442,7 @@ int main(int argc, char* argv[])
     // Advertise the service for the current flying state
     ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("getCurrentFlyingState", getCurrentFlyingStateServiceCallback);
 
-    
+
 
     // Open a ROS "bag" to store data for post-analysis
 	// std::string package_path;
@@ -1258,9 +1451,9 @@ int main(int argc, char* argv[])
 	// std::string record_file = package_path + "LoggingFlyingAgentClient.bag";
 	// bag.open(record_file, rosbag::bagmode::Write);
 
-    ros::spin();
+	ros::spin();
 
-    // Close the ROS "bag" that was opened to store data for post-analysis
+	// Close the ROS "bag" that was opened to store data for post-analysis
 	//bag.close();
 
     return 0;
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index e3209a6b..a1bbba1a 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -505,7 +505,7 @@ void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float y
 // the exercise
 float computeMotorPolyBackward(float thrust)
 {
-	// Compute the 16-but command that would produce the requested
+	// Compute the 16-bit command that would produce the requested
 	// "thrust" based on the quadratic mapping that is described
 	// by the coefficients in the "yaml_motorPoly" variable.
 	float cmd_16bit = (-yaml_motorPoly[1] + sqrt(yaml_motorPoly[1] * yaml_motorPoly[1] - 4 * yaml_motorPoly[2] * (yaml_motorPoly[0] - thrust))) / (2 * yaml_motorPoly[2]);
-- 
GitLab


From d4f478545e46c93c74843319bdd433c34b97bc82 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Tue, 12 Feb 2019 19:18:17 +0100
Subject: [PATCH 79/87] Now compiles in ROS. Flying agent cleint seems to work
 well with the new structure. Default controller still needs implementing

---
 .../include/nodes/DefaultControllerService.h  |   1 +
 .../include/nodes/FlyingAgentClient.h         |  20 +-
 .../src/dfall_pkg/param/ClientConfig.yaml     |   3 +
 .../src/nodes/DefaultControllerService.cpp    |  18 +-
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp | 177 ++++++++++++------
 5 files changed, 138 insertions(+), 81 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 8da4fa3c..12e9add7 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -67,6 +67,7 @@
 #include "dfall_pkg/DebugMsg.h"
 
 // Include the DFALL service types
+#include "dfall_pkg/IntIntService.h"
 #include "dfall_pkg/LoadYamlFromFilename.h"
 #include "dfall_pkg/GetSetpointService.h"
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 863c8c7c..f315d7de 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -138,6 +138,8 @@ int yaml_consecutive_occulsions_threshold = 10;
 // > Timer that when triggered determines that the
 //   "m_isAvailable_mocap_data" variable becomes true
 ros::Timer m_timer_mocap_timeout_check;
+// > Time out duration after which Mocap is considered unavailable
+float yaml_mocap_timeout_duration = 1.0;
 
 
 
@@ -148,7 +150,7 @@ ros::Timer m_timer_mocap_timeout_check;
 bool yaml_isEnabled_strictSafety = true;
 // > The maximum allowed tilt angle, in degrees and radians
 float yaml_maxTiltAngle_for_strictSafety_degrees = 70;
-float m_maxTiltAngle_for_strictSafety_redians = 70 * DEG2RAD;
+float m_maxTiltAngle_for_strictSafety_radians = 70 * DEG2RAD;
 
 
 
@@ -158,7 +160,7 @@ int m_flying_state;
 // > Booleans for whether the {take-off,landing} should
 //   be performed with the default controller
 bool yaml_shouldPerfom_takeOff_with_defaultController = true;
-bool yaml_shouldPerfom_takeOff_with_defaultController = true;
+bool yaml_shouldPerfom_landing_with_defaultController = true;
 // > Service Clients for requesting the Default controller
 //   to perform a {take-off,landing} maneouvre
 ros::ServiceClient m_defaultController_requestManoeuvre;
@@ -180,7 +182,7 @@ ros::ServiceClient* m_instant_controller_service_client;
 bool m_controllers_avialble = false;
 // > Timer for creating the controller service client after
 //   some delay
-ros::Timer timer_for_loadAllControllers;
+ros::Timer m_timer_for_createAllControllerServiceClients;
 // > Integer indicating the controller that has been
 //   requested. This controller is used during the "flying"
 //   state, and the "Default" controller is used during the
@@ -220,10 +222,10 @@ ros::ServiceClient centralManager;
 // to the Crazyflie (the CrazyRadio node listen to this
 // publisher and actually send the commands)
 // {onboardControllerType,roll,pitch,yaw,motorCmd1,motorCmd2,motorCmd3,motorCmd4}
-ros::Publisher commandForSendingToCrazyfliePublisher;
+ros::Publisher m_commandForSendingToCrazyfliePublisher;
 
 // Publisher for the current flying state of this Flying Agent Client
-ros::Publisher flyingStatePublisher;
+ros::Publisher m_flyingStatePublisher;
 
 // Publisher for the commands of:
 // {take-off,land,motors-off, and which controller to use}
@@ -288,10 +290,9 @@ void requestChangeFlyingStateToTakeOff();
 // > For changing to land
 void requestChangeFlyingStateToLand();
 // > Callback that the take off phase is complete
-void takeOffTimerCallback(const ros::TimerEvent&)
+void takeOffTimerCallback(const ros::TimerEvent&);
 // > Callback that the landing phase is complete
-void landTimerCallback(const ros::TimerEvent&)
-
+void landTimerCallback(const ros::TimerEvent&);
 
 
 
@@ -347,6 +348,9 @@ void loadCrazyflieContext();
 // > For creating a service client from the name
 //   of the YAML parameter
 void createControllerServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient );
+// > For creating an IntInt service client from the
+//   name of a YAML paramter
+void createIntIntServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient );
 // > Callback for the timer so that all services servers
 //   exists before we try to create the clients
 void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&);
diff --git a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
index a5825598..b6d75db6 100755
--- a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
@@ -19,6 +19,9 @@ maxTiltAngle_for_strictSafety_degrees: 70
 # object as "long-term" occuled
 consecutive_occulsions_threshold: 10
 
+# Time out duration after which Mocap is considered unavailable
+mocap_timeout_duration: 2.0
+
 # Flag for whether the take-off should be performed
 # with the default controller
 shouldPerfom_takeOff_with_defaultController: true
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index d6e0a5d8..be6ec834 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -214,7 +214,11 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	if (m_current_state == DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS)
 	{
 		// Compute the "spinning" thrust
-		float thrust_for_spinning = 1000.0 + min(0.4,m_time_in_seconds) * 10000.0;
+		float thrust_for_spinning = 1000.0;
+		if (m_time_in_seconds < 0.8)
+			thrust_for_spinning += m_time_in_seconds * 10000.0;
+		else
+			thrust_for_spinning += 8000.0;
 
 		response.controlOutput.roll  = 0.0;
 		response.controlOutput.pitch = 0.0;
@@ -552,7 +556,7 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 	response.setpointWithHeader.z   = m_setpoint[2];
 	response.setpointWithHeader.yaw = m_setpoint[3];
 	// Put the current state into the "buttonID" field
-	response.buttonID = m_current_state;
+	response.setpointWithHeader.buttonID = m_current_state;
 	// Return
 	return true;
 }
@@ -569,7 +573,7 @@ void publishCurrentSetpointAndState()
 	msg.z   = m_setpoint[2];
 	msg.yaw = m_setpoint[3];
 	// Put the current state into the "buttonID" field
-	response.buttonID = m_current_state;
+	msg.buttonID = m_current_state;
 	// Publish the message
 	m_setpointChangedPublisher.publish(msg);
 }
@@ -990,14 +994,6 @@ int main(int argc, char* argv[])
 
 
 
-	// Instantiate the class variable "m_stateChangedPublisher" to
-	// be a "ros::Publisher". This variable advertises under the name
-	// "SetpointChanged" and is a message with the structure defined
-	// in the file "IntWithHeader.msg" (located in the "msg" folder).
-	// This publisher is used by the "flying agent GUI" to update the
-	// field that displays the current state for this controller.
-	m_stateChangedPublisher = nodeHandle.advertise<IntWithHeader>("StateChanged", 1);
-
 
 
 	// Print out some information to the user.
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index e48d3d11..288af49a 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -106,81 +106,97 @@ void viconCallback(const ViconData& viconData)
 
 	// Only continue if:
 	// (1) the pose for this agent was found, and
+	// (2) the controllers are actually available
 	// (2) the flying state is something other than MOTORS-OFF
 	if (
 		(m_poseDataIndex >= 0)
 		and
-		(m_flying_state != STATE_MOTORS_OFF)
-		and
 		(m_controllers_avialble)
 	)
 	{
-		// Initliase the "Contrller" service call variable
-		Controller controllerCall;
-
-		// Fill in the pose data for this agent
-		controllerCall.request.ownCrazyflie = poseDataForThisAgent;
 
-		// If the object is NOT occluded,
-		// then proceed to make the "Controller Service Call" that
-		// compute the controller output.
+		// Only continue if:
+		// (1) the agent is NOT occulded
 		if(!poseDataForThisAgent.occluded)
 		{
+			// Update the flag
+			m_isOcculded_mocap_data = false;
 			// Reset the "consecutive occulsions" flag
 			number_of_consecutive_occulsions = 0;
 
-			// PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
-			if ( getInstantController() != DEFAULT_CONTROLLER )
+
+			// Only continue if:
+			// (1) The state is different from MOTORS-OFF
+			if (m_flying_state != STATE_MOTORS_OFF)
 			{
-				if ( !safetyCheck_on_positionAndTilt(poseDataForThisAgent) )
-				{
-					setInstantController(DEFAULT_CONTROLLER);
-					ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to DEFAULT CONTROLLER");
-				}
-			}
 
-			// Initialise a local boolean success variable
-			bool isSuccessful_controllerCall = false;
+				// Initliase the "Contrller" service call variable
+				Controller controllerCall;
 
-			// Call the controller service client
-			isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+				// Fill in the pose data for this agent
+				controllerCall.request.ownCrazyflie = poseDataForThisAgent;
 
-			// Ensure success and enforce safety
-			if(!isSuccessful_controllerCall)
-			{
-				// Let the user know that the controller call failed
-				ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+				
+				
 
-				// Switch to the default controller,
-				// if it was not already the active controller
+				// PERFORM THE SAFTY CHECK (IF NOT THE DEFAULT CONTROLLER)
 				if ( getInstantController() != DEFAULT_CONTROLLER )
 				{
-					// Set the DEFAULT controller to be active
-					setInstantController(DEFAULT_CONTROLLER);
-					// Try the controller call
-					isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
-					// Inform the user is not successful
-					if ( !isSuccessful_controllerCall )
+					if ( !safetyCheck_on_positionAndTilt(poseDataForThisAgent) )
 					{
-						ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Also failed to call the DEFAULT controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+						setInstantController(DEFAULT_CONTROLLER);
+						ROS_INFO_STREAM("[FLYING AGENT CLIENT] safety check failed, switching to DEFAULT CONTROLLER");
 					}
 				}
-			}
 
-			// Send the command to the CrazyRadio
-			// > IF SUCCESSFUL
-			if (isSuccessful_controllerCall)
-			{
-				m_commaNdfOrsendiNgTocrazyflIepublisher.publish(controllerCall.response.controlOutput);
+				// Initialise a local boolean success variable
+				bool isSuccessful_controllerCall = false;
+
+				// Call the controller service client
+				isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+
+				// Ensure success and enforce safety
+				if(!isSuccessful_controllerCall)
+				{
+					// Let the user know that the controller call failed
+					ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to call controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+
+					// Switch to the default controller,
+					// if it was not already the active controller
+					if ( getInstantController() != DEFAULT_CONTROLLER )
+					{
+						// Set the DEFAULT controller to be active
+						setInstantController(DEFAULT_CONTROLLER);
+						// Try the controller call
+						isSuccessful_controllerCall = m_instant_controller_service_client->call(controllerCall);
+						// Inform the user is not successful
+						if ( !isSuccessful_controllerCall )
+						{
+							ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Also failed to call the DEFAULT controller, valid: " << m_instant_controller_service_client->isValid() << ", exists: " << m_instant_controller_service_client->exists());
+						}
+					}
+				}
+
+				// Send the command to the CrazyRadio
+				// > IF SUCCESSFUL
+				if (isSuccessful_controllerCall)
+				{
+					m_commandForSendingToCrazyfliePublisher.publish(controllerCall.response.controlOutput);
+				}
+				// > ELSE SEND ZERO OUTPUT COMMAND
+				else
+				{
+					// Send the command to turn the motors off
+					sendZeroOutputCommandForMotors();
+					// And change the state to motor-off
+					requestChangeFlyingStateTo(STATE_MOTORS_OFF);
+				}
 			}
-			// > ELSE SEND ZERO OUTPUT COMMAND
 			else
 			{
 				// Send the command to turn the motors off
 				sendZeroOutputCommandForMotors();
-				// And change the state to motor-off
-				requestChangeFlyingStateTo(STATE_MOTORS_OFF);
-			}
+			} // END OF: "if (m_flying_state != STATE_MOTORS_OFF)"
 		}
 		else
 		{
@@ -195,6 +211,8 @@ void viconCallback(const ViconData& viconData)
 			{
 				// Update the flag
 				m_isOcculded_mocap_data = true;
+				// Inform the user
+				ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Agent was occluded for more than " << yaml_consecutive_occulsions_threshold << " consecutive frames." );
 				// Send the command to turn the motors off
 				sendZeroOutputCommandForMotors();
 				// Update the flying state
@@ -208,7 +226,7 @@ void viconCallback(const ViconData& viconData)
 		// Send the command to turn the motors off
 		sendZeroOutputCommandForMotors();
 
-	} // END OF: "if ( (m_poseDataIndex >= 0) and (m_flying_state != STATE_MOTORS_OFF) )"
+	} // END OF: "if ( (m_poseDataIndex >= 0) and (m_controllers_avialble) )"
 
 }
 
@@ -306,7 +324,7 @@ void sendZeroOutputCommandForMotors()
 {
 	ControlCommand zeroOutput = ControlCommand(); //everything set to zero
     zeroOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS; //set to motor_mode
-    m_commaNdfOrsendiNgTocrazyflIepublisher.publish(zeroOutput);
+    m_commandForSendingToCrazyfliePublisher.publish(zeroOutput);
 }
 
 
@@ -359,9 +377,9 @@ bool safetyCheck_on_positionAndTilt(CrazyflieData data)
     {
         // Check on the ROLL angle
         if(
-            (data.roll > m_maxTiltAngle_for_strictSafety_redians)
+            (data.roll > m_maxTiltAngle_for_strictSafety_radians)
             or
-            (data.roll < -m_maxTiltAngle_for_strictSafety_redians)
+            (data.roll < -m_maxTiltAngle_for_strictSafety_radians)
         )
         {
             ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
@@ -369,9 +387,9 @@ bool safetyCheck_on_positionAndTilt(CrazyflieData data)
         }
         // Check on the PITCH angle
         if(
-            (data.pitch > m_maxTiltAngle_for_strictSafety_redians)
+            (data.pitch > m_maxTiltAngle_for_strictSafety_radians)
             or
-            (data.pitch < -m_maxTiltAngle_for_strictSafety_redians)
+            (data.pitch < -m_maxTiltAngle_for_strictSafety_radians)
         )
         {
             ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
@@ -456,7 +474,7 @@ void requestChangeFlyingStateTo(int new_state)
     // Publish a message with the new flying state
     std_msgs::Int32 flying_state_msg;
     flying_state_msg.data = m_flying_state;
-    flyingStatePublisher.publish(flying_state_msg);
+    m_flyingStatePublisher.publish(flying_state_msg);
 }
 
 void requestChangeFlyingStateToTakeOff()
@@ -568,7 +586,7 @@ void requestChangeFlyingStateToLand()
 				// > Stop any previous instance
 				m_timer_land_complete.stop();
 				// > Set the period again (second argument is reset)
-				m_timer_land_complete.setPeriod( ros::Duration(take_off_duration), true);
+				m_timer_land_complete.setPeriod( ros::Duration(land_duration), true);
 				// > Start the timer
 				m_timer_land_complete.start();
 				// Inform the user
@@ -606,6 +624,10 @@ void timerCallback_takeoff_complete(const ros::TimerEvent&)
 		ROS_INFO("[FLYING AGENT CLIENT] Take-off complete, changed state to STATE_FLYING");
 		// Update the class variable
 		m_flying_state = STATE_FLYING;
+		// Publish a message with the new flying state
+		std_msgs::Int32 flying_state_msg;
+		flying_state_msg.data = m_flying_state;
+		m_flyingStatePublisher.publish(flying_state_msg);
 	}
 	else
 	{
@@ -623,6 +645,10 @@ void timerCallback_land_complete(const ros::TimerEvent&)
 		ROS_INFO("[FLYING AGENT CLIENT] Land complete, changed state to STATE_MOTORS_OFF");
 		// Update the class variable
 		m_flying_state = STATE_MOTORS_OFF;
+		// Publish a message with the new flying state
+		std_msgs::Int32 flying_state_msg;
+		flying_state_msg.data = m_flying_state;
+		m_flyingStatePublisher.publish(flying_state_msg);
 	}
 	else
 	{
@@ -1067,6 +1093,23 @@ void createControllerServiceClientFromParameterName( std::string paramter_name ,
 }
 
 
+void createIntIntServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient )
+{
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+
+    std::string controllerName;
+    if(!nodeHandle.getParam(paramter_name, controllerName))
+    {
+        ROS_ERROR_STREAM("[FLYING AGENT CLIENT] Failed to get \"" << paramter_name << "\" paramter");
+        return;
+    }
+
+    serviceClient = ros::service::createClient<IntIntService>(controllerName, true);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] Loaded service: " << serviceClient.getService() <<  ", valid: " << serviceClient.isValid() << ", exists: " << serviceClient.exists() );
+}
+
+
 
 void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&)
 {
@@ -1079,11 +1122,11 @@ void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&)
 
     // INITIALISE THE SERVICE FOR REQUESTING THE DEFAULT
     // CONTROLLER TO PERFORM MANOEUVRES
-    createControllerServiceClientFromParameterName( "defaultController_requestManoeuvre" , m_defaultController_requestManoeuvre );
+    createIntIntServiceClientFromParameterName( "defaultController_requestManoeuvre" , m_defaultController_requestManoeuvre );
 
     // Check that at least the default controller is available
     // > Setting the flag accordingly
-    if (defaultController)
+    if (m_defaultController)
     {
         m_controllers_avialble = true;
     }
@@ -1175,7 +1218,10 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 
     // Number of consecutive occulsions that will deem the
     // object as "long-term" occuled
-	consecutive_occulsions_threshold = getParameterInt(nodeHandle_for_paramaters,"consecutive_occulsions_threshold");
+	yaml_consecutive_occulsions_threshold = getParameterInt(nodeHandle_for_paramaters,"consecutive_occulsions_threshold");
+
+	// Time out duration after which Mocap is considered unavailable
+	yaml_mocap_timeout_duration = getParameterFloat(nodeHandle_for_paramaters,"mocap_timeout_duration");
 
 	// Flag for whether the take-off should be performed
 	//  with the default controller
@@ -1192,10 +1238,10 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 
     // PROCESS THE PARAMTERS
     // Convert from degrees to radians
-    m_maxTiltAngle_for_strictSafety_redians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
+    m_maxTiltAngle_for_strictSafety_radians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
 
     // DEBUGGING: Print out one of the processed values
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_redians = " << m_maxTiltAngle_for_strictSafety_redians);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_radians = " << m_maxTiltAngle_for_strictSafety_radians);
 }
 
 
@@ -1312,6 +1358,13 @@ int main(int argc, char* argv[])
     m_timer_mocap_timeout_check.stop();
     
 
+    // INITIALISE THE TAKE-OFF AND LANDING COMPLETE TIMERS
+    // > And stop it immediately
+    m_timer_takeoff_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
+    m_timer_takeoff_complete.stop();
+    m_timer_land_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
+    m_timer_land_complete.stop();
+
 
 
 
@@ -1353,7 +1406,7 @@ int main(int argc, char* argv[])
     // PUBLISHER FOR COMMANDING THE CRAZYFLIE
     // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
 	//ros::Publishers to advertise the control output
-	m_commaNdfOrsendiNgTocrazyflIepublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
+	m_commandForSendingToCrazyfliePublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
 	//this topic lets the FlyingAgentClient listen to the terminal commands
     //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
@@ -1381,7 +1434,7 @@ int main(int argc, char* argv[])
     // PUBLISHER FOR THE FLYING STATE
     // Possible states: {MOTORS-OFF,TAKE-OFF,FLYING,LAND}
     // This topic will publish flying state whenever it changes.
-    flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
+    m_flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
 
     
 
@@ -1397,7 +1450,7 @@ int main(int argc, char* argv[])
     // publish first flying state data
     std_msgs::Int32 flying_state_msg;
     flying_state_msg.data = m_flying_state;
-    flyingStatePublisher.publish(flying_state_msg);
+    m_flyingStatePublisher.publish(flying_state_msg);
 
     // SafeControllerServicePublisher:
     ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
-- 
GitLab


From 8147411e13f1b836386695f424271c14f92dbdd5 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 12 Feb 2019 23:57:05 +0100
Subject: [PATCH 80/87] Continued with implementing the Default Controller
 manoeurves

---
 .../nodes/DefaultControllerConstants.h        |   8 +-
 .../include/nodes/DefaultControllerService.h  | 166 ++++-
 .../include/nodes/PickerControllerService.h   |  14 +-
 .../dfall_pkg/param/DefaultController.yaml    |  71 +-
 .../src/nodes/DefaultControllerService.cpp    | 617 +++++++++++++-----
 5 files changed, 681 insertions(+), 195 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
index cf6d6cee..e32c39e2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
@@ -35,7 +35,7 @@
 
 // TO REQUEST MANOEUVRES
 
-#define DEFAULT_CONTROLLER_REQUEST_TAKE_OFF    1
+#define DEFAULT_CONTROLLER_REQUEST_TAKEOFF     1
 #define DEFAULT_CONTROLLER_REQUEST_LANDING     2
 
 
@@ -45,9 +45,9 @@
 #define DEFAULT_CONTROLLER_STATE_STANDBY      99
 
 // > The sequence of states for a TAKE-OFF manoeuvre
-#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS      11
-#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_MOVE_UP          12
-#define DEFAULT_CONTROLLER_STATE_TAKE_OFF_GOTO_SETPOINT    13
+#define DEFAULT_CONTROLLER_STATE_TAKEOFF_SPIN_MOTORS      11
+#define DEFAULT_CONTROLLER_STATE_TAKEOFF_MOVE_UP          12
+#define DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT    13
 
 // > The sequence of states for a LANDING manoeuvre
 #define DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN        21
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 12e9add7..8900c471 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -102,7 +102,30 @@ using namespace dfall_pkg;
 
 // These constants are defined to make the code more readable and adaptable.
 
-// NOTE: manz constants are already defined in the "Constant.h" header file
+// NOTE: many constants are already defined in the "Constant.h" header file
+
+// These constants define the method used for estimating the Inertial
+// frame state.
+// All methods are run at all times, this flag indicates which estimate
+// is passed onto the controller.
+// The following is a short description about each mode:
+//
+// ESTIMATOR_METHOD_FINITE_DIFFERENCE
+//       Takes the poisition and angles directly as measured,
+//       and estimates the velocities as a finite different to the
+//       previous measurement
+//
+// ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION
+//       Uses a 2nd order random walk estimator independently for
+//       each of (x,y,z,roll,pitch,yaw)
+//
+// ESTIMATOR_METHOD_QUADROTOR_MODEL_BASED
+//       Uses the model of the quad-rotor and the previous inputs
+//
+#define ESTIMATOR_METHOD_FINITE_DIFFERENCE          1
+#define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
+
+
 
 
 
@@ -116,13 +139,62 @@ using namespace dfall_pkg;
 //      V    A   A  R   R  III  A   A  BBBB   LLLLL  EEEEE  SSSS
 //    ----------------------------------------------------------------------------------
 
+
+// VARIABLES FOR PERFORMING THE TAKE-OFF AND LANDING MANOEUVRES
+
 // The current state of the Default Controller
 int m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
 
+// A flag for when the state is changed, this is used
+// so that a "one-off" operation can be performed
+// the first time after changing that state
+bool m_current_state_changed = false;
+
 // The elapased time, incremented by counting the motion
 // capture callbacks
 float m_time_in_seconds = 0.0;
 
+// PARAMETERS FROM THE YAML FILE
+
+// Max setpoint change per second
+float yaml_max_setpoint_change_per_second_horizontal = 0.1;
+float yaml_max_setpoint_change_per_second_vertical = 0.1;
+
+// Max error for yaw angle
+float yaml_max_setpoint_error_yaw_degrees = 60.0;
+float yaml_max_setpoint_error_yaw_radians = 60.0 * DEG2RAD;
+
+// The thrust for take off spin motors
+float yaml_takeoff_spin_motors_thrust = 8000;
+// The time for the take off spin(-up) motors
+float takoff_spin_motots_time = 0.8;
+
+// Height change for the take off move-up
+float yaml_takeoff_move_up_start_height = 0.1;
+float yaml_takeoff_move_up_end_height   = 0.4;
+// The time for the take off spin motors
+float yaml_takoff_move_up_time = 1.2;
+
+
+
+// The setpoint to be tracked, the ordering is (x,y,z,yaw),
+// with units [meters,meters,meters,radians]
+float m_setpoint[4] = {0.0,0.0,0.4,0.0};
+
+// The setpoint that is actually used by the controller, this
+// differs from the setpoint when smoothing is turned on
+float m_setpoint_for_controller[4] = {0.0,0.0,0.4,0.0};
+
+// Boolean for whether to limit rate of change of the setpoint
+bool m_shouldSmoothSetpointChanges = true;
+
+
+
+
+
+
+// ------------------------------------------------------
+// VARIABLES THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
 // The ID of the agent that this node is monitoring
 int m_agentID;
@@ -142,15 +214,16 @@ std::string m_namespace_to_coordinator_parameter_service;
 // VARAIBLES FOR VALUES LOADED FROM THE YAML FILE
 // > the mass of the crazyflie, in [grams]
 float yaml_cf_mass_in_grams = 25.0;
-
-// > the coefficients of the 16-bit command to thrust conversion
-//std::vector<float> yaml_motorPoly(3);
-std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
+// > the weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = 0.0;
 
 // > the frequency at which the controller is running
 float yaml_control_frequency = 200.0;
 float m_control_deltaT = (1.0/200.0);
 
+// > the coefficients of the 16-bit command to thrust conversion
+std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
+
 // > the min and max for saturating 16 bit thrust commands
 float yaml_command_sixteenbit_min = 1000;
 float yaml_command_sixteenbit_max = 65000;
@@ -159,25 +232,66 @@ float yaml_command_sixteenbit_max = 65000;
 //   with units [meters,meters,meters,radians]
 std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
 
+// Boolean indiciating whether the "Debug Message" of this
+// agent should be published or not
+bool yaml_shouldPublishDebugMessage = false;
 
+// Boolean indiciating whether the debugging ROS_INFO_STREAM
+// should be displayed or not
+bool yaml_shouldDisplayDebugInfo = false;
 
-// The weight of the Crazyflie in Newtons, i.e., mg
-float m_cf_weight_in_newtons = 0.0;
 
-// The location error of the Crazyflie at the "previous" time step
-float m_previous_stateErrorInertial[9];
 
-// The setpoint to be tracked, the ordering is (x,y,z,yaw),
-// with units [meters,meters,meters,radians]
-std::vector<float>  m_setpoint{0.0,0.0,0.4,0.0};
+// VARIABLES FOR THE CONTROLLER
+
+// The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
+std::vector<float> yaml_gainMatrixThrust_NineStateVector  =  { 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixRollRate                =  { 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00};
+std::vector<float> yaml_gainMatrixPitchRate               =  { 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00};
+std::vector<float> yaml_gainMatrixYawRate                 =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30};
+
+
+
+// VARIABLES FOR THE ESTIMATOR
+
+// Frequency at which the controller is running
+float m_estimator_frequency = 200.0;
 
+// > A flag for which estimator to use:
+int yaml_estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
+// > The current state interial estimate,
+//   for use by the controller
+float m_current_stateInertialEstimate[12];
 
-// The LQR Controller parameters for "LQR_RATE_MODE"
-std::vector<float> m_gainMatrixRollRate    =  { 0.00,-1.71, 0.00, 0.00,-1.33, 0.00, 5.12, 0.00, 0.00};
-std::vector<float> m_gainMatrixPitchRate   =  { 1.71, 0.00, 0.00, 1.33, 0.00, 0.00, 0.00, 5.12, 0.00};
-std::vector<float> m_gainMatrixYawRate     =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.84};
-std::vector<float> m_gainMatrixThrust      =  { 0.00, 0.00, 0.19, 0.00, 0.00, 0.08, 0.00, 0.00, 0.00};
+// > The measurement of the Crazyflie at the "current" time step,
+//   to avoid confusion
+float m_current_xzy_rpy_measurement[6];
 
+// > The measurement of the Crazyflie at the "previous" time step,
+//   used for computing finite difference velocities
+float m_previous_xzy_rpy_measurement[6];
+
+// > The full 12 state estimate maintained by the finite
+//   difference state estimator
+float m_stateInterialEstimate_viaFiniteDifference[12];
+
+// > The full 12 state estimate maintained by the point mass
+//   kalman filter state estimator
+float m_stateInterialEstimate_viaPointMassKalmanFilter[12];
+
+// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
+// > For the (x,y,z) position
+std::vector<float> yaml_PMKF_Ahat_row1_for_positions  =  {  0.6723, 0.0034};
+std::vector<float> yaml_PMKF_Ahat_row2_for_positions  =  {-12.9648, 0.9352};
+std::vector<float> yaml_PMKF_Kinf_for_positions       =  {  0.3277,12.9648};
+// > For the (roll,pitch,yaw) angles
+std::vector<float> yaml_PMKF_Ahat_row1_for_angles     =  {  0.6954, 0.0035};
+std::vector<float> yaml_PMKF_Ahat_row2_for_angles     =  {-11.0342, 0.9448};
+std::vector<float> yaml_PMKF_Kinf_for_angles          =  {  0.3046,11.0342};
+
+
+
+// VARIABLES RELATING TO PUBLISHING
 
 // ROS Publisher for debugging variables
 ros::Publisher m_debugPublisher;
@@ -190,6 +304,10 @@ ros::Publisher m_setpointChangedPublisher;
 
 
 
+
+
+
+
 //    ----------------------------------------------------------------------------------
 //    FFFFF  U   U  N   N   CCCC  TTTTT  III   OOO   N   N
 //    F      U   U  NN  N  C        T     I   O   O  NN  N
@@ -217,6 +335,20 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
+// > This function constructs the error in the body frame
+//   before calling the appropriate control function
+void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response)
+// > The various functions that implement an LQR controller
+void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller::Response &response);
+
+// ESTIMATOR COMPUTATIONS
+void performEstimatorUpdate_forStateInterial(Controller::Request &request);
+void performEstimatorUpdate_forStateInterial_viaFiniteDifference();
+void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter();
+
+// PUBLISHING OF THE DEBUG MESSAGE
+void construct_and_publish_debug_message(Controller::Request &request, Controller::Response &response);
+
 // TRANSFORMATION OF THE (x,y) INERTIAL FRAME ERROR
 // INTO AN (x,y) BODY FRAME ERROR
 void convertIntoBodyFrame(float stateInertial[9], float (&stateBody)[9], float yaw_measured);
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
index f0d015af..37528947 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/PickerControllerService.h
@@ -254,13 +254,13 @@ float m_stateInterialEstimate_viaPointMassKalmanFilter[12];
 
 // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 // > For the (x,y,z) position
-std::vector<float> yaml_PMKF_Ahat_row1_for_positions (2,0.0);
-std::vector<float> yaml_PMKF_Ahat_row2_for_positions (2,0.0);
-std::vector<float> yaml_PMKF_Kinf_for_positions      (2,0.0);
+std::vector<float> yaml_PMKF_Ahat_row1_for_positions  =  {  0.6723, 0.0034};
+std::vector<float> yaml_PMKF_Ahat_row2_for_positions  =  {-12.9648, 0.9352};
+std::vector<float> yaml_PMKF_Kinf_for_positions       =  {  0.3277,12.9648};
 // > For the (roll,pitch,yaw) angles
-std::vector<float> yaml_PMKF_Ahat_row1_for_angles    (2,0.0);
-std::vector<float> yaml_PMKF_Ahat_row2_for_angles    (2,0.0);
-std::vector<float> yaml_PMKF_Kinf_for_angles         (2,0.0);
+std::vector<float> yaml_PMKF_Ahat_row1_for_angles     =  {  0.6954, 0.0035};
+std::vector<float> yaml_PMKF_Ahat_row2_for_angles     =  {-11.0342, 0.9448};
+std::vector<float> yaml_PMKF_Kinf_for_angles          =  {  0.3046,11.0342};
 
 
 
@@ -285,7 +285,7 @@ ros::Publisher m_debugPublisher;
 // VARIABLES RELATING TO COMMUNICATING THE SETPOINT
 
 // ROS Publisher for inform the network about
-// changes to the setpoin
+// changes to the setpoint
 ros::Publisher m_setpointChangedPublisher;
 
 
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index 3c208ca7..d64bc24b 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -1,5 +1,30 @@
+# ------------------------------------------------------
+# PARAMTERS FOR THE TAKE-OFF AND LANDING MANOEUVRES
+
+# Max setpoint change per second
+max_setpoint_change_per_second_horizontal  :  0.20 # [meters]
+max_setpoint_change_per_second_vertical    :  0.10 # [meters]
+
+# Max error for yaw angle
+max_setpoint_error_yaw_degrees: 60
+
+# The thrust for take off spin motors
+takeoff_spin_motors_thrust: 8000
+# The time for the take off spin motors
+takoff_spin_motots_time: 0.8
+
+# Height change for the take off move-up
+takeoff_move_up_start_height: 0.1
+takeoff_move_up_end_height:   0.4
+# The time for the take off spin motors
+takoff_move_up_time: 1.2
+
+
+# ------------------------------------------------------
+# PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
+
 # The mass of the crazyflie, in [grams]
-mass : 28
+mass : 30
 
 # Frequency of the controller, in [hertz]
 control_frequency : 200
@@ -9,8 +34,48 @@ motorPoly : [5.484560e-4, 1.032633e-6, 2.130295e-11]
 
 # The min and max for saturating 16 bit thrust commands
 command_sixteenbit_min : 1000
-command_sixteenbit_max : 65000
+command_sixteenbit_max : 60000
 
 # The default setpoint, the ordering is (x,y,z,yaw),
 # with unit [meters,meters,meters,radians]
-default_setpoint : [0.0, 0.0, 0.4, 0.0]
\ No newline at end of file
+default_setpoint : [0.0, 0.0, 0.4, 0.0]
+
+# Boolean indiciating whether the "Debug Message" of this agent should be published or not
+shouldPublishDebugMessage : false
+
+# Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
+shouldDisplayDebugInfo : false
+
+# The LQR Controller parameters for "mode = 3"
+gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00]
+gainMatrixRollRate                  :  [ 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00]
+gainMatrixPitchRate                 :  [ 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00]
+gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30]
+
+# A flag for which estimator to use, defined as:
+# 1  -  Finite Different Method,
+#       Takes the poisition and angles directly as measured,
+#       and estimates the velocities as a finite different to the
+#       previous measurement
+# 2  -  Point Mass Per Dimension Method
+#       Uses a 2nd order random walk estimator independently for
+#       each of (x,y,z,roll,pitch,yaw)
+# 3  -  Quad-rotor Model Based Method
+#       Uses the model of the quad-rotor and the previous inputs
+estimator_method : 1
+
+# THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
+# > For the (x,y,z) position
+PMKF_Ahat_row1_for_positions  :  [  0.6723, 0.0034]
+PMKF_Ahat_row2_for_positions  :  [-12.9648, 0.9352]
+PMKF_Kinf_for_positions       :  [  0.3277,12.9648]
+# > For the (roll,pitch,yaw) angles
+PMKF_Ahat_row1_for_angles     :  [  0.6954, 0.0035]
+PMKF_Ahat_row2_for_angles     :  [-11.0342, 0.9448]
+PMKF_Kinf_for_angles          :  [  0.3046,11.0342]
+
+#PMKF_Ahat_row1_for_angles     :  [  0.6723, 0.0034]
+#PMKF_Ahat_row2_for_angles     :  [-12.9648, 0.9352]
+#PMKF_Kinf_for_angles          :  [  0.3277,12.9648]
+
+
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index be6ec834..96711b81 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -90,6 +90,7 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 			m_time_in_seconds = 0.0;
 			// Update the state accordingly
 			m_current_state = DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS;
+			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
 			response.data = 3000;
 			break;
@@ -103,6 +104,7 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 			m_time_in_seconds = 0.0;
 			// Update the state accordingly
 			m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN;
+			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
 			response.data = 2000;
 			break;
@@ -114,6 +116,7 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 			ROS_INFO("[DEFAULT CONTROLLER] The requested manoeuvre is not recognised. Hence switching to stand-by state.");
 			// Update the state to standby
 			m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
+			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
 			response.data = 0;
 			break;
@@ -162,185 +165,452 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	m_time_in_seconds += m_control_deltaT;
 
 
-	// Define a local array to fill in with the state error
-	float stateErrorInertial[9];
+	// PERFORM THE ESTIMATOR UPDATE FOR THE INTERIAL FRAME STATE
+	// > After this function is complete the class variable
+	//   "m_current_stateInertialEstimate" is updated and ready
+	//   to be used for subsequent controller copmutations
+	performEstimatorUpdate_forStateInterial(request);
 
-	// Fill in the (x,y,z) position error
-	stateErrorInertial[0] = request.ownCrazyflie.x - m_setpoint[0];
-	stateErrorInertial[1] = request.ownCrazyflie.y - m_setpoint[1];
-	stateErrorInertial[2] = request.ownCrazyflie.z - m_setpoint[2];
 
-	// Compute an estimate of the velocity
-	// > As simply the derivative between the current and previous position
-	stateErrorInertial[3] = (stateErrorInertial[0] - m_previous_stateErrorInertial[0]) * yaml_control_frequency;
-	stateErrorInertial[4] = (stateErrorInertial[1] - m_previous_stateErrorInertial[1]) * yaml_control_frequency;
-	stateErrorInertial[5] = (stateErrorInertial[2] - m_previous_stateErrorInertial[2]) * yaml_control_frequency;
+	// Switch between the possible states
+	switch (m_current_state)
+	{
+		case DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS:
+			computeResponse_for_takeoff_spin_motors(response);
+			break;
 
-	// Fill in the roll and pitch angle measurements directly
-	stateErrorInertial[6] = request.ownCrazyflie.roll;
-	stateErrorInertial[7] = request.ownCrazyflie.pitch;
+		case DEFAULT_CONTROLLER_STATE_TAKEOFF_MOVE_UP:
+			computeResponse_for_takeoff_move_up(response);
+			break;
 
-	// Fill in the yaw angle error
-	// > This error should be "unwrapped" to be in the range
-	//   ( -pi , pi )
-	// > First, get the yaw error into a local variable
-	float yawError = request.ownCrazyflie.yaw - m_setpoint[3];
-	// > Second, "unwrap" the yaw error to the interval ( -pi , pi )
-	while(yawError > PI) {yawError -= 2 * PI;}
-	while(yawError < -PI) {yawError += 2 * PI;}
-	// > Third, put the "yawError" into the "stateError" variable
-	stateErrorInertial[8] = yawError;
+	}
 
+	
 
-	// CONVERSION INTO BODY FRAME
-	// Conver the state erorr from the Inertial frame into the Body frame
-	// > 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 classroom exercise
-	float stateErrorBody[9];
-	convertIntoBodyFrame(stateErrorInertial, stateErrorBody, request.ownCrazyflie.yaw);
+	// CARRY OUT THE CONTROLLER COMPUTATIONS
+	// Call the function that performs the control computations for this mode
+	calculateControlOutput_viaLQRforRates(current_bodyFrameError,request,response);
 
 
-	// SAVE THE STATE ERROR TO BE USED NEXT TIME THIS FUNCTION IS CALLED
-	// > as we have already used previous error we can now update it update it
-	for(int i = 0; i < 9; ++i)
+	// PUBLISH THE DEBUG MESSAGE (if required)
+	if (yaml_shouldPublishDebugMessage)
 	{
-		m_previous_stateErrorInertial[i] = stateErrorInertial[i];
+		construct_and_publish_debug_message(request,response);
 	}
 
+	// Return "true" to indicate that the control computation was performed successfully
+	return true;
+}
 
 
-	if (m_current_state == DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS)
+
+
+void computeResponse_for_takeoff_spin_motors(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
 	{
-		// Compute the "spinning" thrust
-		float thrust_for_spinning = 1000.0;
-		if (m_time_in_seconds < 0.8)
-			thrust_for_spinning += m_time_in_seconds * 10000.0;
-		else
-			thrust_for_spinning += 8000.0;
-
-		response.controlOutput.roll  = 0.0;
-		response.controlOutput.pitch = 0.0;
-		response.controlOutput.yaw   = 0.0;
-		response.controlOutput.motorCmd1 = thrust_for_spinning;
-		response.controlOutput.motorCmd2 = thrust_for_spinning;
-		response.controlOutput.motorCmd3 = thrust_for_spinning;
-		response.controlOutput.motorCmd4 = thrust_for_spinning;
-		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Nothing to perform for this state
+		// Set the change flag back to false
+		m_current_state_changed = false;
 	}
+
+	// Compute the "spinning" thrust
+	float thrust_for_spinning = 1000.0;
+	if (m_time_in_seconds < takoff_spin_motots_time)
+		thrust_for_spinning += yaml_takeoff_spin_motors_thrust * (m_time_in_seconds/takoff_spin_motots_time);
 	else
+		thrust_for_spinning += yaml_takeoff_spin_motors_thrust;
+
+	// Fill in zero for the angle parts
+	response.controlOutput.roll  = 0.0;
+	response.controlOutput.pitch = 0.0;
+	response.controlOutput.yaw   = 0.0;
+
+	// Fill in all motor thrusts as the same
+	response.controlOutput.motorCmd1 = thrust_for_spinning;
+	response.controlOutput.motorCmd2 = thrust_for_spinning;
+	response.controlOutput.motorCmd3 = thrust_for_spinning;
+	response.controlOutput.motorCmd4 = thrust_for_spinning;
+
+	// Specify that using a "motor type" of command
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+
+	// Change to next state after specified time
+	if (m_time_in_seconds > takoff_spin_motots_time)
 	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: take-off move up");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_TAKEOFF_MOVE_UP;
+		m_current_state_changed = true;
+	}
+}
 
 
-		
-		// YAW CONTROLLER
 
-		// Perform the "-Kx" LQR computation for the yaw rate
-		// to respond with
-		float yawRate_forResponse = 0;
-		for(int i = 0; i < 9; ++i)
-		{
-			yawRate_forResponse -= m_gainMatrixYawRate[i] * stateErrorBody[i];
-		}
-		// Put the computed yaw rate into the "response" variable
-		response.controlOutput.yaw = yawRate_forResponse;
+void computeResponse_for_takeoff_move_up(Controller::Response &response)
+{
+	// Initialise a static variable for the starting height and yaw
+	static float initial_height = 0.0;
+	static float initial_yaw = 0.0;
+	// Initialise a static variable for the yaw change
+	static float yaw_start_to_end_diff = 0.0;
+
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Set the current (x,y) location as the setpoint
+		m_setpoint_for_controller[0] = m_current_stateInertialEstimate[0];
+		m_setpoint_for_controller[1] = m_current_stateInertialEstimate[1];
+		// Store the current (z,yaw)
+		initial_height = m_current_stateInertialEstimate[2];
+		initial_yaw = m_current_stateInertialEstimate[8];
+		// Compute the yaw "start-to-end-difference" unwrapped
+		yaw_start_to_end_diff = m_setpoint[3] - initial_yaw;
+		while(yaw_start_to_end_diff > PI) {yaw_start_to_end_diff -= 2 * PI;}
+		while(yaw_start_to_end_diff < -PI) {yaw_start_to_end_diff += 2 * PI;}
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
 
+	// Compute the time elapsed as a proportion
+	float time_elapsed_proportion = m_time_in_seconds / (0.8*yaml_takoff_move_up_time);
+	if (time_elapsed_proportion > 1.0)
+		time_elapsed_proportion = 1.0;
 
+	// Compute the z-height setpoint
+	m_setpoint_for_controller[2] = initial_height + yaml_takeoff_move_up_start_height + time_elapsed_proportion * (yaml_takeoff_move_up_end_height-yaml_takeoff_move_up_start_height);
 
+	// Compute the yaw-setpoint
+	m_setpoint_for_controller[3] = initial_yaw + time_elapsed_proportion * yaw_start_to_end_diff;
 
-		// ALITUDE CONTROLLER (i.e., z-controller)
-		
-		// Perform the "-Kx" LQR computation for the thrust adjustment
-		// to use for computing the response with
-		float thrustAdjustment = 0;
-		for(int i = 0; i < 9; ++i)
-		{
-			thrustAdjustment -= m_gainMatrixThrust[i] * stateErrorBody[i];
-		}
+	// Call the LQR control function
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response)
 
-		// Add the feed-forward thrust before putting in the response
-		float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
-		float thrust_per_motor = thrustAdjustment + feed_forward_thrust_per_motor;
+}
 
-		// > NOTE: the function "computeMotorPolyBackward" converts the
-		//         input argument from Newtons to the 16-bit command
-		//         expected by the Crazyflie.
-		response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrust_per_motor);
-		response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrust_per_motor);
-		response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrust_per_motor);
-		response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrust_per_motor);
 
-		
-		// BODY FRAME X CONTROLLER
 
-		// Perform the "-Kx" LQR computation for the pitch rate
-		// to respoond with
-		float pitchRate_forResponse = 0;
-		for(int i = 0; i < 9; ++i)
-		{
-			pitchRate_forResponse -= m_gainMatrixPitchRate[i] * stateErrorBody[i];
-		}
-		// Put the computed pitch rate into the "response" variable
-		response.controlOutput.pitch = pitchRate_forResponse;
 
 
 
 
-		// BODY FRAME Y CONTROLLER
 
-		// Instantiate the local variable for the roll rate that will be requested
-		// from the Crazyflie's on-baord "inner-loop" controller
-		
 
-		// Perform the "-Kx" LQR computation for the roll rate
-		// to respoond with
-		float rollRate_forResponse = 0;
-		for(int i = 0; i < 9; ++i)
+
+
+
+//    ------------------------------------------------------------------------------
+//    EEEEE   SSSS  TTTTT  III  M   M    A    TTTTT  III   OOO   N   N
+//    E      S        T     I   MM MM   A A     T     I   O   O  NN  N
+//    EEE     SSS     T     I   M M M  A   A    T     I   O   O  N N N
+//    E          S    T     I   M   M  AAAAA    T     I   O   O  N  NN
+//    EEEEE  SSSS     T    III  M   M  A   A    T    III   OOO   N   N
+//    ------------------------------------------------------------------------------
+void performEstimatorUpdate_forStateInterial(Controller::Request &request)
+{
+
+	// PUT THE CURRENT MEASURED DATA INTO THE CLASS VARIABLE
+	// > for (x,y,z) position
+	m_current_xzy_rpy_measurement[0] = request.ownCrazyflie.x;
+	m_current_xzy_rpy_measurement[1] = request.ownCrazyflie.y;
+	m_current_xzy_rpy_measurement[2] = request.ownCrazyflie.z;
+	// > for (roll,pitch,yaw) angles
+	m_current_xzy_rpy_measurement[3] = request.ownCrazyflie.roll;
+	m_current_xzy_rpy_measurement[4] = request.ownCrazyflie.pitch;
+	m_current_xzy_rpy_measurement[5] = request.ownCrazyflie.yaw;
+
+
+	// RUN THE FINITE DIFFERENCE ESTIMATOR
+	performEstimatorUpdate_forStateInterial_viaFiniteDifference();
+
+
+	// RUN THE POINT MASS KALMAN FILTER ESTIMATOR
+	performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter();
+
+
+	// FILLE IN THE STATE INERTIAL ESTIMATE TO BE USED FOR CONTROL
+	switch (yaml_estimator_method)
+	{
+		// Estimator based on finte differences
+		case ESTIMATOR_METHOD_FINITE_DIFFERENCE:
 		{
-			rollRate_forResponse -= m_gainMatrixRollRate[i] * stateErrorBody[i];
+			// Transfer the estimate
+			for(int i = 0; i < 12; ++i)
+			{
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
+			}
+			break;
+		}
+		// Estimator based on Point Mass Kalman Filter
+		case ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION:
+		{
+			// Transfer the estimate
+			for(int i = 0; i < 12; ++i)
+			{
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
+			}
+			break;
+		}
+		// Handle the exception
+		default:
+		{
+			// Display that the "yaml_estimator_method" was not recognised
+			ROS_INFO_STREAM("[PICKER CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'PickerControllerService': the 'yaml_estimator_method' is not recognised.");
+			// Transfer the finite difference estimate by default
+			for(int i = 0; i < 12; ++i)
+			{
+				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
+			}
+			break;
 		}
-		// Put the computed roll rate into the "response" variable
-		response.controlOutput.roll = rollRate_forResponse;
-
-		
-		
-		// PREPARE AND RETURN THE VARIABLE "response"
-
-		/*choosing the Crazyflie onBoard controller type.
-		it can either be Motor, Rate or Angle based */
-		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
-		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
-		// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
 	}
 
 
+	// NOW THAT THE ESTIMATORS HAVE ALL BEEN RUN, PUT THE CURRENT
+	// MEASURED DATA INTO THE CLASS VARIABLE FOR THE PREVIOUS 
+	// > for (x,y,z) position
+	m_previous_xzy_rpy_measurement[0] = m_current_xzy_rpy_measurement[0];
+	m_previous_xzy_rpy_measurement[1] = m_current_xzy_rpy_measurement[1];
+	m_previous_xzy_rpy_measurement[2] = m_current_xzy_rpy_measurement[2];
+	// > for (roll,pitch,yaw) angles
+	m_previous_xzy_rpy_measurement[3] = m_current_xzy_rpy_measurement[3];
+	m_previous_xzy_rpy_measurement[4] = m_current_xzy_rpy_measurement[4];
+	m_previous_xzy_rpy_measurement[5] = m_current_xzy_rpy_measurement[5];
+}
+
+
 
+void performEstimatorUpdate_forStateInterial_viaFiniteDifference()
+{
+	// PUT IN THE CURRENT MEASUREMENT DIRECTLY
+	// > for (x,y,z) position
+	m_stateInterialEstimate_viaFiniteDifference[0]  = m_current_xzy_rpy_measurement[0];
+	m_stateInterialEstimate_viaFiniteDifference[1]  = m_current_xzy_rpy_measurement[1];
+	m_stateInterialEstimate_viaFiniteDifference[2]  = m_current_xzy_rpy_measurement[2];
+	// > for (roll,pitch,yaw) angles
+	m_stateInterialEstimate_viaFiniteDifference[6]  = m_current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaFiniteDifference[7]  = m_current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaFiniteDifference[8]  = m_current_xzy_rpy_measurement[5];
+
+	// COMPUTE THE VELOCITIES VIA FINITE DIFFERENCE
+	// > for (x,y,z) velocities
+	m_stateInterialEstimate_viaFiniteDifference[3]  = (m_current_xzy_rpy_measurement[0] - m_previous_xzy_rpy_measurement[0]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[4]  = (m_current_xzy_rpy_measurement[1] - m_previous_xzy_rpy_measurement[1]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[5]  = (m_current_xzy_rpy_measurement[2] - m_previous_xzy_rpy_measurement[2]) * m_estimator_frequency;
+	// > for (roll,pitch,yaw) velocities
+	m_stateInterialEstimate_viaFiniteDifference[9]  = (m_current_xzy_rpy_measurement[3] - m_previous_xzy_rpy_measurement[3]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[10] = (m_current_xzy_rpy_measurement[4] - m_previous_xzy_rpy_measurement[4]) * m_estimator_frequency;
+	m_stateInterialEstimate_viaFiniteDifference[11] = (m_current_xzy_rpy_measurement[5] - m_previous_xzy_rpy_measurement[5]) * m_estimator_frequency;
+}
 
-	//  ***********************************************************
-	//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
-	//  D   D  E      B   B  U   U  G           MM MM  S      G
-	//  D   D  EEE    BBBB   U   U  G           M M M   SSS   G
-	//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
-	//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
 
-	// DEBUGGING CODE:
-	// As part of the D-FaLL-System we have defined a message type names"DebugMsg".
-	// By fill this message with data and publishing it you can display the data in
-	// real time using rpt plots. Instructions for using rqt plots can be found on
-	// the wiki of the D-FaLL-System repository
 
+void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter()
+{
+	// PERFORM THE KALMAN FILTER UPDATE STEP
+	// > First take a copy of the estimator state
+	float temp_PMKFstate[12];
+	for(int i = 0; i < 12; ++i)
+	{
+		temp_PMKFstate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
+	}
+	// > Now perform update for:
+	// > x position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[0] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[0] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[3] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[0];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[3] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[0] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[3] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[0];
+	// > y position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[1] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[1] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[4] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[1];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[4] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[1] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[4] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[1];
+	// > z position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[2] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[2];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[5] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[2];
+
+	// > roll  position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[6]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[9]  = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[3];
+	// > pitch position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[7]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[10] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[4];
+	// > yaw   position and velocity:
+	m_stateInterialEstimate_viaPointMassKalmanFilter[8]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[5];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[11] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[5];
+}
+
+
+
+
+
+//    ----------------------------------------------------------------------------------
+//    L       QQQ   RRRR
+//    L      Q   Q  R   R
+//    L      Q   Q  RRRR
+//    L      Q  Q   R  R
+//    LLLLL   QQ Q  R   R
+//    ----------------------------------------------------------------------------------
+
+// > This function constructs the error in the body frame
+//   before calling the appropriate control function
+void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response)
+{
+	// Store the current YAW in a local variable
+	float temp_stateInertial_yaw = stateInertial[8];
+
+	// Adjust the INERTIAL (x,y,z) position for the setpoint
+	stateInertial[0] = stateInertial[0] - setpoint[0];
+	stateInertial[1] = stateInertial[1] - setpoint[1];
+	stateInertial[2] = stateInertial[2] - setpoint[2];
+
+	// Clip the z-coordination to within the specified bounds
+	if (stateInertial[2] > 0.40f)
+	{
+		stateInertial[2] = 0.40f;
+	}
+	else if (stateInertial[2] < -0.40f)
+	{
+		stateInertial[2] = -0.40f;
+	}
+
+	// Fill in the yaw angle error
+	// > This error should be "unwrapped" to be in the range
+	//   ( -pi , pi )
+	// > Det the yaw error into a local variable
+	float yawError = stateInertial[8] - setpoint[3];
+	// > "Unwrap" the yaw error to the interval ( -pi , pi )
+	while(yawError > PI) {yawError -= 2 * PI;}
+	while(yawError < -PI) {yawError += 2 * PI;}
+	// Clip the error to within the specified bounds
+		if (yawError>(PI/3))
+	{
+		yawError = (PI/3);
+	}
+	else if (yawError<(-PI/3))
+	{
+		yawError = (-PI/3);
+	}
+	// > Finally, put the "yawError" into the "stateError" variable
+	stateInertial[8] = yawError;
+
+	// CONVERSION INTO BODY FRAME
+	// Convert the state erorr from the Inertial frame into the Body frame
+	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
+
+	calculateControlOutput_viaLQRforRates(bodyFrameError, response);
+}
+
+void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller::Response &response)
+{
+	// PERFORM THE "u=Kx" LQR CONTROLLER COMPUTATION
+
+	// Instantiate the local variables for the following:
+	// > body frame roll rate,
+	// > body frame pitch rate,
+	// > body frame yaw rate,
+	// > total thrust adjustment.
+	// These will be requested from the Crazyflie's on-baord "inner-loop" controller
+	float rollRate_forResponse = 0;
+	float pitchRate_forResponse = 0;
+	float yawRate_forResponse = 0;
+	float thrustAdjustment = 0;
+	
+	// Perform the "-Kx" LQR computation for the rates and thrust:
+	for(int i = 0; i < 9; ++i)
+	{
+		// BODY FRAME Y CONTROLLER
+		rollRate_forResponse  -= yaml_gainMatrixRollRate[i] * stateErrorBody[i];
+		// BODY FRAME X CONTROLLER
+		pitchRate_forResponse -= yaml_gainMatrixPitchRate[i] * stateErrorBody[i];
+		// BODY FRAME YAW CONTROLLER
+		yawRate_forResponse   -= yaml_gainMatrixYawRate[i] * stateErrorBody[i];
+		// > ALITUDE CONTROLLER (i.e., z-controller):
+		thrustAdjustment      -= yaml_gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
+	}
+
+
+	// UPDATE THE "RETURN" THE VARIABLE NAMED "response"
+
+	// Put the computed rates and thrust into the "response" variable
+	// > For roll, pitch, and yaw:
+	response.controlOutput.roll  = rollRate_forResponse;
+	response.controlOutput.pitch = pitchRate_forResponse;
+	response.controlOutput.yaw   = yawRate_forResponse;
+	// > For the thrust adjustment we must add the feed-forward thrust to counter-act gravity.
+	// > NOTE: remember that the thrust is commanded per motor, so you sohuld
+	//         consider whether the "thrustAdjustment" computed by your
+	//         controller needed to be divided by 4 or not.
+	thrustAdjustment = thrustAdjustment / 4.0;
+	// > Compute the feed-forward force
+	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
+	// > Put in the per motor commands
+	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
+	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
+	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
+	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
+
+	
+	// Specify that this controller is a rate controller
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTOR;
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_RATE;
+	// response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_ANGLE;
+
+
+	// An alternate debugging technique is to print out data directly to the
+	// command line from which this node was launched.
+	if (yaml_shouldDisplayDebugInfo)
+	{
+		// An example of "printing out" the control actions computed.
+		ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
+		ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
+		ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
+		ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
+
+		// An example of "printing out" the "thrust-to-command" conversion parameters.
+		ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
+		ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
+		ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
+
+		// An example of "printing out" the per motor 16-bit command computed.
+		ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
+		ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
+		ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
+		ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
+	}
+}
+
+
+
+//  ***********************************************************
+//  DDDD   EEEEE  BBBB   U   U   GGGG       M   M   SSSS   GGGG
+//  D   D  E      B   B  U   U  G           MM MM  S      G
+//  D   D  EEE    BBBB   U   U  G           M M M   SSS   G
+//  D   D  E      B   B  U   U  G   G       M   M      S  G   G
+//  DDDD   EEEEE  BBBB    UUU    GGGG       M   M  SSSS    GGGG
+
+void construct_and_publish_debug_message(Controller::Request &request, Controller::Response &response)
+{
+	
+    // DEBUGGING CODE:
+    // As part of the D-FaLL-System we have defined a message type names"DebugMsg".
+    // By fill this message with data and publishing it you can display the data in
+    // real time using rpt plots. Instructions for using rqt plots can be found on
+    // the wiki of the D-FaLL-System repository
+    
 	// Instantiate a local variable of type "DebugMsg", see the file "DebugMsg.msg"
 	// (located in the "msg" folder) to see the full structure of this message.
 	DebugMsg debugMsg;
 
 	// Fill the debugging message with the data provided by Vicon
-	debugMsg.vicon_x = request.ownCrazyflie.x;
-	debugMsg.vicon_y = request.ownCrazyflie.y;
-	debugMsg.vicon_z = request.ownCrazyflie.z;
-	debugMsg.vicon_roll = request.ownCrazyflie.roll;
-	debugMsg.vicon_pitch = request.ownCrazyflie.pitch;
-	debugMsg.vicon_yaw = request.ownCrazyflie.yaw;
+	debugMsg.vicon_x      = request.ownCrazyflie.x;
+	debugMsg.vicon_y      = request.ownCrazyflie.y;
+	debugMsg.vicon_z      = request.ownCrazyflie.z;
+	debugMsg.vicon_roll   = request.ownCrazyflie.roll;
+	debugMsg.vicon_pitch  = request.ownCrazyflie.pitch;
+	debugMsg.vicon_yaw    = request.ownCrazyflie.yaw;
 
 	// Fill in the debugging message with any other data you would like to display
 	// in real time. For example, it might be useful to display the thrust
@@ -354,40 +624,8 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 	// Publish the "debugMsg"
 	m_debugPublisher.publish(debugMsg);
+}
 
-	// An alternate debugging technique is to print out data directly to the
-	// command line from which this node was launched.
-
-	// An example of "printing out" the data from the "request" argument to the
-	// command line. This might be useful for debugging.
-	// ROS_INFO_STREAM("x-coordinates: " << request.ownCrazyflie.x);
-	// ROS_INFO_STREAM("y-coordinates: " << request.ownCrazyflie.y);
-	// ROS_INFO_STREAM("z-coordinates: " << request.ownCrazyflie.z);
-	// ROS_INFO_STREAM("roll: " << request.ownCrazyflie.roll);
-	// ROS_INFO_STREAM("pitch: " << request.ownCrazyflie.pitch);
-	// ROS_INFO_STREAM("yaw: " << request.ownCrazyflie.yaw);
-	// ROS_INFO_STREAM("Delta t: " << request.ownCrazyflie.acquiringTime);
-
-	// An example of "printing out" the control actions computed.
-	// ROS_INFO_STREAM("thrustAdjustment = " << thrustAdjustment);
-	// ROS_INFO_STREAM("controlOutput.roll = " << response.controlOutput.roll);
-	// ROS_INFO_STREAM("controlOutput.pitch = " << response.controlOutput.pitch);
-	// ROS_INFO_STREAM("controlOutput.yaw = " << response.controlOutput.yaw);
-
-	// An example of "printing out" the "thrust-to-command" conversion parameters.
-	// ROS_INFO_STREAM("motorPoly 0:" << yaml_motorPoly[0]);
-	// ROS_INFO_STREAM("motorPoly 1:" << yaml_motorPoly[1]);
-	// ROS_INFO_STREAM("motorPoly 2:" << yaml_motorPoly[2]);
-
-	// An example of "printing out" the per motor 16-bit command computed.
-	// ROS_INFO_STREAM("controlOutput.cmd1 = " << response.controlOutput.motorCmd1);
-	// ROS_INFO_STREAM("controlOutput.cmd3 = " << response.controlOutput.motorCmd2);
-	// ROS_INFO_STREAM("controlOutput.cmd2 = " << response.controlOutput.motorCmd3);
-	// ROS_INFO_STREAM("controlOutput.cmd4 = " << response.controlOutput.motorCmd4);
-
-	// Return "true" to indicate that the control computation was performed successfully
-	return true;
-	}
 
 
 
@@ -732,6 +970,31 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 
 	// GET THE PARAMETERS:
 
+	// ------------------------------------------------------
+	// PARAMTERS FOR THE TAKE-OFF AND LANDING MANOEUVRES
+
+	// Max setpoint change per second
+	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_horizontal");
+	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_vertical");
+	
+	// Max error for yaw angle
+	yaml_max_setpoint_error_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_yaw_degrees");
+
+	// The thrust for take off spin motors
+	yaml_takeoff_spin_motors_thrust = getParameterFloat(nodeHandle_for_paramaters , "takeoff_spin_motors_thrust");
+	// The time for the take off spin(-up) motors
+	yaml_takoff_spin_motots_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_spin_motots_time");
+
+	// Height change for the take off move-up
+	yaml_takeoff_move_up_height = getParameterFloat(nodeHandle_for_paramaters , "takeoff_move_up_height");
+	// The time for the take off spin motors
+	yaml_takoff_move_up_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_move_up_time");
+
+
+
+	// ------------------------------------------------------
+	// PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
+
 	// The mass of the crazyflie, in [grams]
 	yaml_cf_mass_in_grams = getParameterFloat(nodeHandle_for_paramaters , "mass");
 
@@ -753,6 +1016,32 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// with unit [meters,meters,meters,radians]
 	getParameterFloatVector(nodeHandle_for_paramaters, "default_setpoint", yaml_default_setpoint, 4);
 
+	// Boolean indiciating whether the "Debug Message" of this agent should be published or not
+	yaml_shouldPublishDebugMessage = getParameterBool(nodeHandle_for_paramaters, "shouldPublishDebugMessage");
+
+	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
+	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paramaters, "shouldDisplayDebugInfo");
+	
+	// The LQR Controller parameters for "LQR_MODE_RATE"
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
+	
+	// A flag for which estimator to use:
+	yaml_estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );	
+	
+	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
+	// > For the (x,y,z) position
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_positions",  yaml_PMKF_Ahat_row1_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_positions",  yaml_PMKF_Ahat_row2_for_positions,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_positions"     ,  yaml_PMKF_Kinf_for_positions     ,  2);
+	// > For the (roll,pitch,yaw) angles
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_angles",  yaml_PMKF_Ahat_row1_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_angles",  yaml_PMKF_Ahat_row2_for_angles,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_angles"     ,  yaml_PMKF_Kinf_for_angles     ,  2);
+
+
 
 
 	// > DEBUGGING: Print out one of the parameters that was loaded to
-- 
GitLab


From f63121d2278adc876ab0cd7df6f5f810bc81e01b Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 13 Feb 2019 13:00:43 +0100
Subject: [PATCH 81/87] Finished implementing the Default controller (except
 for the integrator). Needs compiling and testing. (Also changed the
 ClientConfig.yaml to be FlyingAgentClientConfig.yaml)

---
 .../GUI_Qt/flyingAgentGUI/forms/mainwindow.ui |   6 +-
 .../flyingAgentGUI/include/mainwindow.h       |   2 +-
 .../GUI_Qt/flyingAgentGUI/src/mainwindow.cpp  |   4 +-
 .../nodes/DefaultControllerConstants.h        |   4 +-
 .../include/nodes/DefaultControllerService.h  | 127 +++-
 .../include/nodes/FlyingAgentClient.h         |  22 +-
 dfall_ws/src/dfall_pkg/launch/agent.launch    |   4 +-
 .../src/dfall_pkg/launch/coordinator.launch   |   2 +-
 .../dfall_pkg/param/DefaultController.yaml    |  87 ++-
 ...nfig.yaml => FlyingAgentClientConfig.yaml} |   7 +-
 .../src/dfall_pkg/param/YamlFileNames.yaml    |   2 +-
 .../src/nodes/DefaultControllerService.cpp    | 672 ++++++++++++++++--
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp | 364 +++++-----
 13 files changed, 977 insertions(+), 326 deletions(-)
 rename dfall_ws/src/dfall_pkg/param/{ClientConfig.yaml => FlyingAgentClientConfig.yaml} (85%)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
index bd79177a..e848317a 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/forms/mainwindow.ui
@@ -204,7 +204,7 @@
      <string>LoadYAML</string>
     </property>
     <addaction name="action_LoadYAML_BatteryMonitor"/>
-    <addaction name="action_LoadYAML_ClientConfig"/>
+    <addaction name="action_LoadYAML_FlyingAgentClientConfig"/>
    </widget>
    <widget class="QMenu" name="menuControllers">
     <property name="title">
@@ -239,9 +239,9 @@
     <string>BatteryMonitor</string>
    </property>
   </action>
-  <action name="action_LoadYAML_ClientConfig">
+  <action name="action_LoadYAML_FlyingAgentClientConfig">
    <property name="text">
-    <string>ClientConfig</string>
+    <string>FlyingAgentClientConfig</string>
    </property>
   </action>
   <action name="action_showHideController_default">
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
index 2cfdc268..916869bd 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/mainwindow.h
@@ -124,7 +124,7 @@ private slots:
     // PRIVATE METHODS FOR MENU ITEM CALLBACKS
     void on_actionShowHide_Coordinator_triggered();
     void on_action_LoadYAML_BatteryMonitor_triggered();
-    void on_action_LoadYAML_ClientConfig_triggered();
+    void on_action_LoadYAML_FlyingAgentClientConfig_triggered();
 
     // FOR THE CONTROLLERS MENU
     void on_action_showHideController_default_changed();
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
index 239aa269..0a523fe3 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp
@@ -194,7 +194,7 @@ void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered()
 }
 
 
-void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
+void MainWindow::on_action_LoadYAML_FlyingAgentClientConfig_triggered()
 {
 #ifdef CATKIN_MAKE
     // Inform the user that the menu item was selected
@@ -203,7 +203,7 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered()
     // Create a local variable for the message
     StringWithHeader yaml_filename_msg;
     // Specify the data
-    yaml_filename_msg.data = "ClientConfig";
+    yaml_filename_msg.data = "FlyingAgentClientConfig";
     // Set for whom this applies to
     yaml_filename_msg.shouldCheckForAgentID = false;
     // Send the message
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
index e32c39e2..a9beaf7e 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerConstants.h
@@ -41,13 +41,15 @@
 
 // TO IDENITFY THE STATE OF THE DEFAULT CONTROLLER
 
-#define DEFAULT_CONTROLLER_STATE_UNKNOWN      -1
+#define DEFAULT_CONTROLLER_STATE_NORMAL        1
 #define DEFAULT_CONTROLLER_STATE_STANDBY      99
+#define DEFAULT_CONTROLLER_STATE_UNKNOWN      -1
 
 // > The sequence of states for a TAKE-OFF manoeuvre
 #define DEFAULT_CONTROLLER_STATE_TAKEOFF_SPIN_MOTORS      11
 #define DEFAULT_CONTROLLER_STATE_TAKEOFF_MOVE_UP          12
 #define DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT    13
+#define DEFAULT_CONTROLLER_STATE_TAKEOFF_INTEGRATOR_ON    14
 
 // > The sequence of states for a LANDING manoeuvre
 #define DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN        21
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 8900c471..1fc29bdb 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -104,10 +104,28 @@ using namespace dfall_pkg;
 
 // NOTE: many constants are already defined in the "Constant.h" header file
 
-// These constants define the method used for estimating the Inertial
-// frame state.
-// All methods are run at all times, this flag indicates which estimate
-// is passed onto the controller.
+// These constants define the method used for computing
+// the control actions from the state error estimates.
+// The following is a short description about each mode:
+//
+// CONTROLLER_METHOD_RATES
+//       Uses the poisition, linear velocity and angle
+//       error estimates to compute the rates
+//
+// CONTROLLER_METHOD_RATE_ANGLE_NESTED
+//       Uses the position and linear velocity error
+//       estimates to compute an angle, and then uses
+//       this as a reference to construct an angle error
+//       estimate and compute from that the rates
+//
+#define CONTROLLER_METHOD_RATES               1
+#define CONTROLLER_METHOD_RATE_ANGLE_NESTED   2   // (DEFAULT)
+
+
+// These constants define the method used for estimating
+// the Inertial frame state.
+// All methods are run at all times, this flag indicates
+// which estimate is passed onto the controller.
 // The following is a short description about each mode:
 //
 // ESTIMATOR_METHOD_FINITE_DIFFERENCE
@@ -160,21 +178,58 @@ float m_time_in_seconds = 0.0;
 float yaml_max_setpoint_change_per_second_horizontal = 0.1;
 float yaml_max_setpoint_change_per_second_vertical = 0.1;
 
+// Max error for z
+float yaml_max_setpoint_error_z = 0.4;
+
 // Max error for yaw angle
 float yaml_max_setpoint_error_yaw_degrees = 60.0;
 float yaml_max_setpoint_error_yaw_radians = 60.0 * DEG2RAD;
 
+// Max {roll,pitch} angle request
+float yaml_max_roll_pitch_request_degrees = 30.0;
+float yaml_max_roll_pitch_request_radians = 30.0 * DEG2RAD;
+
+// Theshold for {roll,pitch} angle beyond
+// which the motors are turned off
+float yaml_threshold_roll_pitch_for_turn_off_degrees = 70.0;
+float yaml_threshold_roll_pitch_for_turn_off_radians = 70.0 * DEG2RAD;
+
 // The thrust for take off spin motors
 float yaml_takeoff_spin_motors_thrust = 8000;
-// The time for the take off spin(-up) motors
-float takoff_spin_motots_time = 0.8;
+// The time for: take off spin(-up) motors
+float yaml_takoff_spin_motors_time = 0.8;
 
 // Height change for the take off move-up
 float yaml_takeoff_move_up_start_height = 0.1;
 float yaml_takeoff_move_up_end_height   = 0.4;
-// The time for the take off spin motors
+// The time for: take off spin motors
 float yaml_takoff_move_up_time = 1.2;
 
+// Minimum and maximum allowed time for: take off goto setpoint
+float yaml_takoff_goto_setpoint_min_time = 1.2;
+float yaml_takoff_goto_setpoint_max_time = 2.0;
+
+// Box within which to keep the integrator on
+// > Units of [meters]
+// > The box consider is plus/minus this value
+float yaml_takoff_integrator_on_box_horizontal = 0.25;
+float yaml_takoff_integrator_on_box_vertical   = 0.15;
+// The time for: take off integrator-on
+float yaml_takoff_integrator_on_time = 1.5;
+
+
+// Height change for the landing move-down
+float yaml_landing_move_down_end_height_setpoint  = 0.05;
+float yaml_landing_move_down_end_height_threshold = 0.10;
+// The time for: landing move-down
+float yaml_landing_move_down_time_max = 2.0;
+
+// The thrust for landing spin motors
+float yaml_landing_spin_motors_thrust = 10000;
+// The time for: landing spin motors
+float yaml_landing_spin_motors_time = 1.0;
+
+
 
 
 // The setpoint to be tracked, the ordering is (x,y,z,yaw),
@@ -244,12 +299,21 @@ bool yaml_shouldDisplayDebugInfo = false;
 
 // VARIABLES FOR THE CONTROLLER
 
-// The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
-std::vector<float> yaml_gainMatrixThrust_NineStateVector  =  { 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00};
-std::vector<float> yaml_gainMatrixRollRate                =  { 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00};
-std::vector<float> yaml_gainMatrixPitchRate               =  { 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00};
-std::vector<float> yaml_gainMatrixYawRate                 =  { 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30};
+// > A flag for which controller to use:
+int yaml_controller_method = CONTROLLER_METHOD_RATE_ANGLE_NESTED;
 
+// The LQR Controller parameters for z-height
+std::vector<float> yaml_gainMatrixThrust_2StateVector     =  { 0.98, 0.25};
+// The LQR Controller parameters for "CONTROLLER_METHOD_RATES"
+std::vector<float> yaml_gainMatrixRollRate_3StateVector   =  {-6.20,-3.00, 5.20};
+std::vector<float> yaml_gainMatrixPitchRate_3StateVector  =  { 6.20, 3.00, 5.20};
+// The LQR Controller parameters for "CONTROLLER_METHOD_RATE_ANGLE_NESTED"
+std::vector<float> yaml_gainMatrixRollAngle_2StateVector  =  {-0.20,-0.20};
+std::vector<float> yaml_gainMatrixPitchAngle_2StateVector =  { 0.20, 0.20};
+float yaml_gainRollRate_fromAngle   =  4.00;
+float yaml_gainPitchRate_fromAngle  =  4.00;
+// The LQR Controller parameters for yaw
+float yaml_gainYawRate_fromAngle    =  2.30;
 
 
 // VARIABLES FOR THE ESTIMATOR
@@ -259,9 +323,10 @@ float m_estimator_frequency = 200.0;
 
 // > A flag for which estimator to use:
 int yaml_estimator_method = ESTIMATOR_METHOD_FINITE_DIFFERENCE;
+
 // > The current state interial estimate,
 //   for use by the controller
-float m_current_stateInertialEstimate[12];
+float m_current_stateInertialEstimate[9];
 
 // > The measurement of the Crazyflie at the "current" time step,
 //   to avoid confusion
@@ -273,22 +338,17 @@ float m_previous_xzy_rpy_measurement[6];
 
 // > The full 12 state estimate maintained by the finite
 //   difference state estimator
-float m_stateInterialEstimate_viaFiniteDifference[12];
+float m_stateInterialEstimate_viaFiniteDifference[9];
 
 // > The full 12 state estimate maintained by the point mass
 //   kalman filter state estimator
-float m_stateInterialEstimate_viaPointMassKalmanFilter[12];
+float m_stateInterialEstimate_viaPointMassKalmanFilter[9];
 
 // THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 // > For the (x,y,z) position
 std::vector<float> yaml_PMKF_Ahat_row1_for_positions  =  {  0.6723, 0.0034};
 std::vector<float> yaml_PMKF_Ahat_row2_for_positions  =  {-12.9648, 0.9352};
 std::vector<float> yaml_PMKF_Kinf_for_positions       =  {  0.3277,12.9648};
-// > For the (roll,pitch,yaw) angles
-std::vector<float> yaml_PMKF_Ahat_row1_for_angles     =  {  0.6954, 0.0035};
-std::vector<float> yaml_PMKF_Ahat_row2_for_angles     =  {-11.0342, 0.9448};
-std::vector<float> yaml_PMKF_Kinf_for_angles          =  {  0.3046,11.0342};
-
 
 
 // VARIABLES RELATING TO PUBLISHING
@@ -301,6 +361,11 @@ ros::Publisher m_debugPublisher;
 ros::Publisher m_setpointChangedPublisher;
 
 
+// ROS Publisher for sending motors-off command
+// to the flying agent client
+ros::Publisher m_motorsOffToFlyingAgentClientPublisher;
+
+
 
 
 
@@ -335,11 +400,28 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 // CONTROLLER COMPUTATIONS
 bool calculateControlOutput(Controller::Request &request, Controller::Response &response);
 
+// > For the normal state
+void computeResponse_for_normal(Controller::Response &response);
+// > For the standby state (also used for unknown state)
+void computeResponse_for_standby(Controller::Response &response);
+// > For the take-off phases
+void computeResponse_for_takeoff_move_up(Controller::Response &response);
+void computeResponse_for_takeoff_spin_motors(Controller::Response &response);
+void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response);
+void computeResponse_for_takeoff_integrator_on(Controller::Response &response);
+// > For the landing phases
+void computeResponse_for_landing_move_down(Controller::Response &response);
+void computeResponse_for_landing_spin_motors(Controller::Response &response);
+
+
+// SMOOTHING SETPOINT CHANGES
+void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)[4] );
+
 // > This function constructs the error in the body frame
 //   before calling the appropriate control function
 void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response)
 // > The various functions that implement an LQR controller
-void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller::Response &response);
+void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controller::Response &response);
 
 // ESTIMATOR COMPUTATIONS
 void performEstimatorUpdate_forStateInterial(Controller::Request &request);
@@ -371,6 +453,9 @@ void publishCurrentSetpointAndState();
 // CUSTOM COMMAND RECEIVED CALLBACK
 void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
+// PUBLISH MOTORS-OFF MESSAGE TO FLYING AGENT CLIENT
+void publish_motors_off_to_flying_agent_client();
+
 // LOADING OF YAML PARAMETERS
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg);
 void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index f315d7de..215f13f2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -150,7 +150,7 @@ float yaml_mocap_timeout_duration = 1.0;
 bool yaml_isEnabled_strictSafety = true;
 // > The maximum allowed tilt angle, in degrees and radians
 float yaml_maxTiltAngle_for_strictSafety_degrees = 70;
-float m_maxTiltAngle_for_strictSafety_radians = 70 * DEG2RAD;
+float yaml_maxTiltAngle_for_strictSafety_radians = 70 * DEG2RAD;
 
 
 
@@ -192,15 +192,15 @@ int m_controller_nominally_selected;
 
 
 // VARIABLES FOR THE CONTROLER SERVIVCE CLIENTS
-// The default controller specified in the ClientConfig.yaml
+// The default controller specified in the FlyingAgentClientConfig.yaml
 ros::ServiceClient m_defaultController;
-// The Student controller specified in the ClientConfig.yaml
+// The Student controller specified in the FlyingAgentClientConfig.yaml
 ros::ServiceClient m_studentController;
-// The Tuning controller specified in the ClientConfig.yaml
+// The Tuning controller specified in the FlyingAgentClientConfig.yaml
 ros::ServiceClient m_tuningController;
-// The Picker controller specified in the ClientConfig.yaml
+// The Picker controller specified in the FlyingAgentClientConfig.yaml
 ros::ServiceClient m_pickerController;
-// The Template controller specified in the ClientConfig.yaml
+// The Template controller specified in the FlyingAgentClientConfig.yaml
 ros::ServiceClient m_templateController;
 
 
@@ -216,7 +216,7 @@ int m_crazyradio_status;
 CrazyflieContext m_context;
 
 // Service Client from which the "CrazyflieContext" is loaded
-ros::ServiceClient centralManager;
+ros::ServiceClient m_centralManager;
 
 // Publisher for the control actions to be sent on
 // to the Crazyflie (the CrazyRadio node listen to this
@@ -232,10 +232,10 @@ ros::Publisher m_flyingStatePublisher;
 //ros::Publisher commandPublisher;
 
 // Publisher Communication with crazyRadio node. Connect and disconnect
-ros::Publisher crazyRadioCommandPublisher;
+ros::Publisher m_crazyRadioCommandPublisher;
 
 // Publisher for which controller is currently being used
-ros::Publisher controllerUsedPublisher;
+ros::Publisher m_controllerUsedPublisher;
 
 
 
@@ -358,5 +358,5 @@ void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&)
 
 
 // FOR LOADING THE YAML PARAMETERS
-void isReadyClientConfigYamlCallback(const IntWithHeader & msg);
-void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
+void isReadyFlyingAgentClientConfigYamlCallback(const IntWithHeader & msg);
+void fetchFlyingAgentClientConfigYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/launch/agent.launch b/dfall_ws/src/dfall_pkg/launch/agent.launch
index b97eae9a..52a40b94 100755
--- a/dfall_ws/src/dfall_pkg/launch/agent.launch
+++ b/dfall_ws/src/dfall_pkg/launch/agent.launch
@@ -130,8 +130,8 @@
 			<param name="agentID"  value="$(arg agentID)" />
 			<rosparam
 				command = "load"
-				file    = "$(find dfall_pkg)/param/ClientConfig.yaml"
-				ns      = "ClientConfig"
+				file    = "$(find dfall_pkg)/param/FlyingAgentClientConfig.yaml"
+				ns      = "FlyingAgentClientConfig"
 			/>
 			<rosparam
 				command = "load"
diff --git a/dfall_ws/src/dfall_pkg/launch/coordinator.launch b/dfall_ws/src/dfall_pkg/launch/coordinator.launch
index 9d10deaf..c9e7e154 100755
--- a/dfall_ws/src/dfall_pkg/launch/coordinator.launch
+++ b/dfall_ws/src/dfall_pkg/launch/coordinator.launch
@@ -44,7 +44,7 @@
 			/>
 			<rosparam
 				command = "load"
-				file    = "$(find dfall_pkg)/param/ClientConfig.yaml"
+				file    = "$(find dfall_pkg)/param/FlyingAgentClientConfig.yaml"
 				ns      = "SafeController"
 			/>
 		</node>
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index d64bc24b..d5b432c5 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -2,23 +2,62 @@
 # PARAMTERS FOR THE TAKE-OFF AND LANDING MANOEUVRES
 
 # Max setpoint change per second
-max_setpoint_change_per_second_horizontal  :  0.20 # [meters]
-max_setpoint_change_per_second_vertical    :  0.10 # [meters]
+max_setpoint_change_per_second_horizontal  :  0.50 # [meters]
+max_setpoint_change_per_second_vertical    :  0.30 # [meters]
+
+# Max error for z
+max_setpoint_error_z: 0.4
 
 # Max error for yaw angle
 max_setpoint_error_yaw_degrees: 60
 
+# Max {roll,pitch} angle request
+max_roll_pitch_request_degrees: 30
+
+# Theshold for {roll,pitch} angle beyond
+# which the motors are turned off
+threshold_roll_pitch_for_turn_off_degrees: 70
+
 # The thrust for take off spin motors
 takeoff_spin_motors_thrust: 8000
-# The time for the take off spin motors
-takoff_spin_motots_time: 0.8
+# The time for: take off spin motors
+takoff_spin_motors_time: 0.8
 
 # Height change for the take off move-up
 takeoff_move_up_start_height: 0.1
 takeoff_move_up_end_height:   0.4
-# The time for the take off spin motors
+# The time for: take off move-up
 takoff_move_up_time: 1.2
 
+# Minimum and maximum allowed time for: take off goto setpoint
+takoff_goto_setpoint_min_time: 1.0
+takoff_goto_setpoint_max_time: 2.0
+
+# Box within which to keep the integrator on
+# > Units of [meters]
+# > The box consider is plus/minus this value
+takoff_integrator_on_box_horizontal: 0.25
+takoff_integrator_on_box_vertical:   0.15
+# The time for: take off integrator-on
+takoff_integrator_on_time: 1.5
+
+
+# Height change for the landing move-down
+landing_move_down_end_height_setpoint:  0.05
+landing_move_down_end_height_threshold: 0.10
+# The time for: landing move-down
+landing_move_down_time_max: 2.0
+
+# The thrust for landing spin motors
+landing_spin_motors_thrust: 10000
+# The time for: landing spin motors
+landing_spin_motors_time: 1.0
+
+
+# IMPORTANT NOTE: the times above should NOT be set
+# to zero because this will cause a divide by zero
+# crash.
+
 
 # ------------------------------------------------------
 # PARAMTERS THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
@@ -46,11 +85,25 @@ shouldPublishDebugMessage : false
 # Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
 shouldDisplayDebugInfo : false
 
-# The LQR Controller parameters for "mode = 3"
-gainMatrixThrust_NineStateVector    :  [ 0.00, 0.00, 0.98, 0.00, 0.00, 0.25, 0.00, 0.00, 0.00]
-gainMatrixRollRate                  :  [ 0.00,-6.20, 0.00, 0.00,-3.00, 0.00, 5.20, 0.00, 0.00]
-gainMatrixPitchRate                 :  [ 6.20, 0.00, 0.00, 3.00, 0.00, 0.00, 0.00, 5.20, 0.00]
-gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 2.30]
+# A flag for which controller to use, defined as:
+# 1  -  Rate controller
+# 2  -  Angle-Rate nested controller
+controller_method : 1
+
+# The LQR Controller parameters for z-height
+gainMatrixThrust_2StateVector     :  [ 0.98, 0.25]
+# The LQR Controller parameters for mode 1 (the Rate controller)
+gainMatrixRollRate_3StateVector   :  [-6.20,-3.00, 5.20]
+gainMatrixPitchRate_3StateVector  :  [ 6.20, 3.00, 5.20]
+# The LQR Controller parameters for mode 2 (Angle-nested)
+gainMatrixRollAngle_2StateVector  :  [-0.20,-0.20]
+gainMatrixPitchAngle_2StateVector :  [ 0.20, 0.20]
+gainRollRate_fromAngle   :  4.00
+gainPitchRate_fromAngle  :  4.00
+# The LQR Controller parameters for yaw
+gainYawRate_fromAngle    :  2.30
+
+
 
 # A flag for which estimator to use, defined as:
 # 1  -  Finite Different Method,
@@ -60,22 +113,10 @@ gainMatrixYawRate                   :  [ 0.00, 0.00, 0.00, 0.00, 0.00, 0.00, 0.0
 # 2  -  Point Mass Per Dimension Method
 #       Uses a 2nd order random walk estimator independently for
 #       each of (x,y,z,roll,pitch,yaw)
-# 3  -  Quad-rotor Model Based Method
-#       Uses the model of the quad-rotor and the previous inputs
 estimator_method : 1
 
 # THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 # > For the (x,y,z) position
 PMKF_Ahat_row1_for_positions  :  [  0.6723, 0.0034]
 PMKF_Ahat_row2_for_positions  :  [-12.9648, 0.9352]
-PMKF_Kinf_for_positions       :  [  0.3277,12.9648]
-# > For the (roll,pitch,yaw) angles
-PMKF_Ahat_row1_for_angles     :  [  0.6954, 0.0035]
-PMKF_Ahat_row2_for_angles     :  [-11.0342, 0.9448]
-PMKF_Kinf_for_angles          :  [  0.3046,11.0342]
-
-#PMKF_Ahat_row1_for_angles     :  [  0.6723, 0.0034]
-#PMKF_Ahat_row2_for_angles     :  [-12.9648, 0.9352]
-#PMKF_Kinf_for_angles          :  [  0.3277,12.9648]
-
-
+PMKF_Kinf_for_positions       :  [  0.3277,12.9648]
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
similarity index 85%
rename from dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
rename to dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
index b6d75db6..cf56b8e1 100755
--- a/dfall_ws/src/dfall_pkg/param/ClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
@@ -28,9 +28,4 @@ shouldPerfom_takeOff_with_defaultController: true
 
 # Flag for whether the landing should be performed
 # with the default controller
-shouldPerfom_landing_with_defaultController: true
-
-
-#battery_threshold_while_flying: 2.60       # in V
-#battery_threshold_while_motors_off: 3.30   # in V
-#battery_polling_period: 200                # in ms
\ No newline at end of file
+shouldPerfom_landing_with_defaultController: true
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml b/dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml
index 53fd75c2..b61a3e84 100644
--- a/dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml
+++ b/dfall_ws/src/dfall_pkg/param/YamlFileNames.yaml
@@ -1,4 +1,4 @@
 dictionary : {
-  'ClientConfig'   : 'ClientConfig' ,
+  'FlyingAgentClientConfig'   : 'FlyingAgentClientConfig' ,
   'SafeController' : 'SafeController'
 }
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 96711b81..c5e0188e 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -92,7 +92,13 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 			m_current_state = DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS;
 			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
-			response.data = 3000;
+			response.data = 1000 *
+				int(
+					+ yaml_takoff_spin_motors_time
+					+ yaml_takoff_move_up_time
+					+ yaml_takoff_goto_setpoint_max_time
+					+ yaml_takoff_integrator_on_time
+				);
 			break;
 		}
 
@@ -106,7 +112,11 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 			m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN;
 			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
-			response.data = 2000;
+			response.data = 1000 *
+				int(
+					+ yaml_landing_move_down_time_max
+					+ yaml_landing_spin_motors_time
+				);
 			break;
 		}
 
@@ -175,6 +185,10 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Switch between the possible states
 	switch (m_current_state)
 	{
+		case DEFAULT_CONTROLLER_STATE_NORMAL:
+			computeResponse_for_normal(response);
+			break;
+
 		case DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS:
 			computeResponse_for_takeoff_spin_motors(response);
 			break;
@@ -183,13 +197,57 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 			computeResponse_for_takeoff_move_up(response);
 			break;
 
+		case DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT:
+			computeResponse_for_takeoff_goto_setpoint(response);
+			break;
+
+		case DEFAULT_CONTROLLER_STATE_TAKEOFF_INTEGRATOR_ON:
+			computeResponse_for_takeoff_integrator_on(response);
+			break;
+
+		case DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN:
+			computeResponse_for_landing_move_down(response);
+			break;
+
+		case DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS:
+			computeResponse_for_landing_spin_motors(response);
+			break;
+
+		case DEFAULT_CONTROLLER_STATE_STANDBY:
+		case DEFAULT_CONTROLLER_STATE_UNKNOWN:
+		default:
+			computeResponse_for_standby(response);
+			break;
 	}
 
-	
 
-	// CARRY OUT THE CONTROLLER COMPUTATIONS
-	// Call the function that performs the control computations for this mode
-	calculateControlOutput_viaLQRforRates(current_bodyFrameError,request,response);
+	// Change to standby state if the {roll,pitch}
+	// angles exceed the threshold
+	if (
+		(abs(m_current_stateInertialEstimate[6]) > yaml_threshold_roll_pitch_for_turn_off_radians)
+		or
+		(abs(m_current_stateInertialEstimate[7]) > yaml_threshold_roll_pitch_for_turn_off_radians)
+	)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Angle thereshold exceeded. Switch to state: standby");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
+		m_current_state_changed = true;
+		// Publish a command to the "Flying Agent Client"
+		// requesting the "MOTORS-OFF" state
+		publish_motors_off_to_flying_agent_client();
+	}
+
+
+	// If the state changed,
+	// then publish the setpoint so that the GUI is updated
+	if (m_current_state_changed)
+	{
+		publishCurrentSetpointAndState();
+	}
 
 
 	// PUBLISH THE DEBUG MESSAGE (if required)
@@ -198,11 +256,62 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 		construct_and_publish_debug_message(request,response);
 	}
 
+
 	// Return "true" to indicate that the control computation was performed successfully
 	return true;
 }
 
 
+void computeResponse_for_standby(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Nothing to perform for this state
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
+
+	// Fill in zero for the angle parts
+	response.controlOutput.roll  = 0.0;
+	response.controlOutput.pitch = 0.0;
+	response.controlOutput.yaw   = 0.0;
+
+	// Fill in all motor thrusts as zero
+	response.controlOutput.motorCmd1 = 0.0;
+	response.controlOutput.motorCmd2 = 0.0;
+	response.controlOutput.motorCmd3 = 0.0;
+	response.controlOutput.motorCmd4 = 0.0;
+
+	// Specify that using a "motor type" of command
+	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+}
+
+
+void computeResponse_for_normal(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Set the "m_setpoint_for_controller" variable
+		// to the current inertial estimate
+		m_setpoint_for_controller[0] = m_current_stateInertialEstimate[0];
+		m_setpoint_for_controller[1] = m_current_stateInertialEstimate[1];
+		m_setpoint_for_controller[2] = m_current_stateInertialEstimate[2];
+		m_setpoint_for_controller[3] = m_current_stateInertialEstimate[8];
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
+
+	// Smooth out any setpoint changes
+	smoothSetpointChanges( m_setpoint , m_setpoint_for_controller );
+
+	// Call the LQR control function
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+
+}
 
 
 void computeResponse_for_takeoff_spin_motors(Controller::Response &response)
@@ -216,12 +325,15 @@ void computeResponse_for_takeoff_spin_motors(Controller::Response &response)
 		m_current_state_changed = false;
 	}
 
+	// Compute the time elapsed as a proportion
+	float time_elapsed_proportion = m_time_in_seconds / yaml_takoff_spin_motors_time;
+	if (time_elapsed_proportion > 1.0)
+		time_elapsed_proportion = 1.0;
+
 	// Compute the "spinning" thrust
-	float thrust_for_spinning = 1000.0;
-	if (m_time_in_seconds < takoff_spin_motots_time)
-		thrust_for_spinning += yaml_takeoff_spin_motors_thrust * (m_time_in_seconds/takoff_spin_motots_time);
-	else
-		thrust_for_spinning += yaml_takeoff_spin_motors_thrust;
+	float thrust_for_spinning =
+		+ 1000.0
+		+ time_elapsed_proportion * yaml_takeoff_spin_motors_thrust;
 
 	// Fill in zero for the angle parts
 	response.controlOutput.roll  = 0.0;
@@ -238,7 +350,7 @@ void computeResponse_for_takeoff_spin_motors(Controller::Response &response)
 	response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 
 	// Change to next state after specified time
-	if (m_time_in_seconds > takoff_spin_motots_time)
+	if (m_time_in_seconds > yaml_takoff_spin_motors_time)
 	{
 		// Inform the user
 		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: take-off move up");
@@ -290,14 +402,292 @@ void computeResponse_for_takeoff_move_up(Controller::Response &response)
 	m_setpoint_for_controller[3] = initial_yaw + time_elapsed_proportion * yaw_start_to_end_diff;
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response)
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
 
+	// Change to next state after specified time
+	if (m_time_in_seconds > yaml_takoff_move_up_time)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: take-off goto setpoint");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT;
+		m_current_state_changed = true;
+	}
 }
 
 
 
+void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Nothing to perform for this state
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
+
+	// Smooth out any setpoint changes
+	smoothSetpointChanges( m_setpoint , m_setpoint_for_controller );
+
+	// Call the LQR control function
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+
+	// If minimum time is passed,
+	// then check if near to the setpoint
+	if (m_time_in_seconds > yaml_takoff_goto_setpoint_min_time)
+	{
+		// Compute the current errors
+		float error_x = m_setpoint[0] - m_current_stateInertialEstimate[0];
+		float error_y = m_setpoint[1] - m_current_stateInertialEstimate[1];
+		float error_z = m_setpoint[2] - m_current_stateInertialEstimate[2];
+		// Check if within the "integrator on" box
+		// of the setpoint
+		if (
+			(abs(error_x) < yaml_takoff_integrator_on_box_horizontal)
+			and
+			(abs(error_y) < yaml_takoff_integrator_on_box_horizontal)
+			and
+			(abs(error_z) < yaml_takoff_integrator_on_box_vertical)
+		)
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: take-off integrator on");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_TAKEOFF_INTEGRATOR_ON;
+		m_current_state_changed = true;
+	}
+
+	// Change to normal if the timeout is reched
+	if (m_time_in_seconds > yaml_takoff_goto_setpoint_max_time)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Did not reached the setpoint within the \"take-off goto setpoint\" allowed time. Switch to state: normal");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_NORMAL;
+		m_current_state_changed = true;
+	}
+}
+
+
 
+void computeResponse_for_integrator_on(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Set the "m_setpoint_for_controller" variable
+		// to the current setpoint
+		m_setpoint_for_controller[0] = m_setpoint[0];
+		m_setpoint_for_controller[1] = m_setpoint[1];
+		m_setpoint_for_controller[2] = m_setpoint[2];
+		m_setpoint_for_controller[3] = m_setpoint[3];
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
 
+	// Call the LQR control function
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+
+	// Change to next state after specified time
+	if (m_time_in_seconds > yaml_takoff_integrator_on_time)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: normal");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_NORMAL;
+		m_current_state_changed = true;
+	}
+}
+
+
+
+
+
+void computeResponse_for_landing_move_down(Controller::Response &response)
+{
+	// Initialise a static variable for the starting height and yaw
+	static float initial_height = 0.4;
+
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Set the current (x,y,yaw) location as the setpoint
+		m_setpoint_for_controller[0] = m_current_stateInertialEstimate[0];
+		m_setpoint_for_controller[1] = m_current_stateInertialEstimate[1];
+		m_setpoint_for_controller[3] = m_current_stateInertialEstimate[8];
+		// Store the current z
+		initial_height = m_current_stateInertialEstimate[2];
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
+
+	// Compute the time elapsed as a proportion
+	float time_elapsed_proportion = m_time_in_seconds / (0.8*yaml_landing_move_down_time_max);
+	if (time_elapsed_proportion > 1.0)
+		time_elapsed_proportion = 1.0;
+
+	// Compute the z-height setpoint
+	m_setpoint_for_controller[2] = initial_height + time_elapsed_proportion * (yaml_landing_move_down_end_height_setpoint-initial_height);
+
+	// Call the LQR control function
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+
+	// Check if within the threshold of zero
+	if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: landing spin motors");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
+		m_current_state_changed = true;
+	}
+
+	// Change to landing spin motors if the timeout is reached
+	if (m_time_in_seconds > yaml_landing_move_down_time_max)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Did not reached the setpoint within the \"landing move down\" allowed time. Switch to state: landing spin motors");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
+		m_current_state_changed = true;
+	}
+}
+
+
+void computeResponse_for_landing_spin_motors(Controller::Response &response)
+{
+	// Check if the state "just recently" changed
+	if (m_current_state_changed)
+	{
+		// PERFORM "ONE-OFF" OPERATIONS HERE
+		// Set the z setpoint
+		m_setpoint_for_controller[2] = yaml_landing_move_down_end_height_setpoint;
+		// Set the change flag back to false
+		m_current_state_changed = false;
+	}
+
+	// Compute the time elapsed as a proportion
+	float time_elapsed_proportion = m_time_in_seconds / yaml_landing_spin_motors_time;
+	if (time_elapsed_proportion > 1.0)
+		time_elapsed_proportion = 1.0;
+
+
+	// Start by using the controller and reducing the thrust
+	if (time_elapsed_proportion<0.5)
+	{
+		// Call the LQR control function
+		calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+		// Compute the desired "spinning" thrust
+		float thrust_for_spinning =
+			(1.0-time_elapsed_proportion)
+			*
+			computeMotorPolyBackward(m_cf_weight_in_newtons/4.0);
+		// Adjust the motor commands
+		response.controlOutput.motorCmd1 = thrust_for_spinning;
+		response.controlOutput.motorCmd2 = thrust_for_spinning;
+		response.controlOutput.motorCmd3 = thrust_for_spinning;
+		response.controlOutput.motorCmd4 = thrust_for_spinning;
+	}
+	// Next stop using the controller and just spin the motors
+	else
+	{
+		// Fill in zero for the angle parts
+		response.controlOutput.roll  = 0.0;
+		response.controlOutput.pitch = 0.0;
+		response.controlOutput.yaw   = 0.0;
+		// Fill in all motor thrusts as the same
+		response.controlOutput.motorCmd1 = yaml_landing_spin_motors_thrust;
+		response.controlOutput.motorCmd2 = yaml_landing_spin_motors_thrust;
+		response.controlOutput.motorCmd3 = yaml_landing_spin_motors_thrust;
+		response.controlOutput.motorCmd4 = yaml_landing_spin_motors_thrust;
+		// Specify that using a "motor type" of command
+		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
+
+		// Change to next state after specified time
+		if (m_time_in_seconds > yaml_landing_spin_motors_time)
+		{
+			// Inform the user
+			ROS_INFO("[DEFAULT CONTROLLER] Switch to state: standby");
+			// Reset the time variable
+			m_time_in_seconds = 0.0;
+			// Update the state accordingly
+			m_current_state = DEFAULT_CONTROLLER_STATE_STANDBY;
+			m_current_state_changed = true;
+		}
+	}	
+}
+
+
+//    ------------------------------------------------------------------------------
+//     SSSS  M   M   OOO    OOO   TTTTT  H   H
+//    S      MM MM  O   O  O   O    T    H   H
+//     SSS   M M M  O   O  O   O    T    HHHHH
+//        S  M   M  O   O  O   O    T    H   H
+//    SSSS   M   M   OOO    OOO     T    H   H
+//
+//     SSSS  EEEEE  TTTTT  PPPP    OOO   III  N   N  TTTTT
+//    S      E        T    P   P  O   O   I   NN  N    T
+//     SSS   EEE      T    PPPP   O   O   I   N N N    T
+//        S  E        T    P      O   O   I   N  NN    T
+//    SSSS   EEEEE    T    P       OOO   III  N   N    T
+//    ------------------------------------------------------------------------------
+
+
+void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)[4] )
+{
+	// SMOOTH THE Z-COORIDINATE
+	// > Compute the max allowed change
+	float max_for_z = yaml_max_setpoint_change_per_second_vertical  yaml_control_frequency;
+	// > Compute the current difference
+	float diff_for_z = target_setpoint[2] - current_setpoint[2];
+	// > Clip the difference to the maximum
+	if (diff_for_z > max_for_z)
+		diff_for_z = max_for_z;
+	else if (diff_for_z < -max_for_z)
+		diff_for_z = -max_for_z;
+	// > Update the current setpoint
+	current_setpoint[2] += diff_for_z;
+
+	// SMOOTH THE X-Y-COORIDINATES
+	// > Compute the max allowed change
+	float max_for_xy = yaml_max_setpoint_change_per_second_horizontal  yaml_control_frequency;
+	// > Compute the current difference
+	float diff_for_x  = target_setpoint[0] - current_setpoint[0];
+	float diff_for_y  = target_setpoint[1] - current_setpoint[1];
+	float diff_for_xy = sqrt( diff_for_x^2 + diff_for_y^2 );
+	// > Clip the difference to the maximum
+	if (diff_for_xy > max_for_xy)
+	{
+		// > Convert the difference to a proportion
+		float proportion_xy = max_for_xy / diff_for_xy;
+		// > Update the current setpoint
+		current_setpoint[0] += proportion_xy * diff_for_x;
+		current_setpoint[1] += proportion_xy * diff_for_y;
+	}
+	else
+	{
+		// > Update the current setpoint to be the
+		//   the target setpoint because it is within
+		//   reach
+		current_setpoint[0] = target_setpoint[0];
+		current_setpoint[1] = target_setpoint[1];
+	}	
+}
 
 
 
@@ -341,7 +731,7 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 		case ESTIMATOR_METHOD_FINITE_DIFFERENCE:
 		{
 			// Transfer the estimate
-			for(int i = 0; i < 12; ++i)
+			for(int i = 0; i < 9; ++i)
 			{
 				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
 			}
@@ -351,7 +741,7 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 		case ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION:
 		{
 			// Transfer the estimate
-			for(int i = 0; i < 12; ++i)
+			for(int i = 0; i < 9; ++i)
 			{
 				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
 			}
@@ -361,9 +751,9 @@ void performEstimatorUpdate_forStateInterial(Controller::Request &request)
 		default:
 		{
 			// Display that the "yaml_estimator_method" was not recognised
-			ROS_INFO_STREAM("[PICKER CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'PickerControllerService': the 'yaml_estimator_method' is not recognised.");
+			ROS_INFO_STREAM("[DEFAULT CONTROLLER] ERROR: in the 'calculateControlOutput' function of the 'DefaultControllerService': the 'yaml_estimator_method' is not recognised.");
 			// Transfer the finite difference estimate by default
-			for(int i = 0; i < 12; ++i)
+			for(int i = 0; i < 9; ++i)
 			{
 				m_current_stateInertialEstimate[i]  = m_stateInterialEstimate_viaFiniteDifference[i];
 			}
@@ -403,10 +793,6 @@ void performEstimatorUpdate_forStateInterial_viaFiniteDifference()
 	m_stateInterialEstimate_viaFiniteDifference[3]  = (m_current_xzy_rpy_measurement[0] - m_previous_xzy_rpy_measurement[0]) * m_estimator_frequency;
 	m_stateInterialEstimate_viaFiniteDifference[4]  = (m_current_xzy_rpy_measurement[1] - m_previous_xzy_rpy_measurement[1]) * m_estimator_frequency;
 	m_stateInterialEstimate_viaFiniteDifference[5]  = (m_current_xzy_rpy_measurement[2] - m_previous_xzy_rpy_measurement[2]) * m_estimator_frequency;
-	// > for (roll,pitch,yaw) velocities
-	m_stateInterialEstimate_viaFiniteDifference[9]  = (m_current_xzy_rpy_measurement[3] - m_previous_xzy_rpy_measurement[3]) * m_estimator_frequency;
-	m_stateInterialEstimate_viaFiniteDifference[10] = (m_current_xzy_rpy_measurement[4] - m_previous_xzy_rpy_measurement[4]) * m_estimator_frequency;
-	m_stateInterialEstimate_viaFiniteDifference[11] = (m_current_xzy_rpy_measurement[5] - m_previous_xzy_rpy_measurement[5]) * m_estimator_frequency;
 }
 
 
@@ -415,8 +801,8 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter()
 {
 	// PERFORM THE KALMAN FILTER UPDATE STEP
 	// > First take a copy of the estimator state
-	float temp_PMKFstate[12];
-	for(int i = 0; i < 12; ++i)
+	float temp_PMKFstate[9];
+	for(int i = 0; i < 9; ++i)
 	{
 		temp_PMKFstate[i]  = m_stateInterialEstimate_viaPointMassKalmanFilter[i];
 	}
@@ -431,16 +817,12 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter()
 	m_stateInterialEstimate_viaPointMassKalmanFilter[2] = yaml_PMKF_Ahat_row1_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row1_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[0]*m_current_xzy_rpy_measurement[2];
 	m_stateInterialEstimate_viaPointMassKalmanFilter[5] = yaml_PMKF_Ahat_row2_for_positions[0]*temp_PMKFstate[2] + yaml_PMKF_Ahat_row2_for_positions[1]*temp_PMKFstate[5] + yaml_PMKF_Kinf_for_positions[1]*m_current_xzy_rpy_measurement[2];
 
-	// > roll  position and velocity:
-	m_stateInterialEstimate_viaPointMassKalmanFilter[6]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[3];
-	m_stateInterialEstimate_viaPointMassKalmanFilter[9]  = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[6] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[9]  + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[3];
-	// > pitch position and velocity:
-	m_stateInterialEstimate_viaPointMassKalmanFilter[7]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[4];
-	m_stateInterialEstimate_viaPointMassKalmanFilter[10] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[7] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[10] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[4];
-	// > yaw   position and velocity:
-	m_stateInterialEstimate_viaPointMassKalmanFilter[8]  = yaml_PMKF_Ahat_row1_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row1_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[0]*m_current_xzy_rpy_measurement[5];
-	m_stateInterialEstimate_viaPointMassKalmanFilter[11] = yaml_PMKF_Ahat_row2_for_angles[0]*temp_PMKFstate[8] + yaml_PMKF_Ahat_row2_for_angles[1]*temp_PMKFstate[11] + yaml_PMKF_Kinf_for_angles[1]*m_current_xzy_rpy_measurement[5];
-}
+	// > for (roll,pitch,yaw) angles
+	//   (taken directly from the measurement):
+	m_stateInterialEstimate_viaPointMassKalmanFilter[6]  = m_current_xzy_rpy_measurement[3];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[7]  = m_current_xzy_rpy_measurement[4];
+	m_stateInterialEstimate_viaPointMassKalmanFilter[8]  = m_current_xzy_rpy_measurement[5];
+}	
 
 
 
@@ -467,14 +849,10 @@ void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateI
 	stateInertial[2] = stateInertial[2] - setpoint[2];
 
 	// Clip the z-coordination to within the specified bounds
-	if (stateInertial[2] > 0.40f)
-	{
-		stateInertial[2] = 0.40f;
-	}
-	else if (stateInertial[2] < -0.40f)
-	{
-		stateInertial[2] = -0.40f;
-	}
+	if (stateInertial[2] > yaml_max_setpoint_error_z)
+		stateInertial[2] = yaml_max_setpoint_error_z;
+	else if (stateInertial[2] < -yaml_max_setpoint_error_z)
+		stateInertial[2] = -yaml_max_setpoint_error_z;
 
 	// Fill in the yaw angle error
 	// > This error should be "unwrapped" to be in the range
@@ -485,53 +863,110 @@ void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateI
 	while(yawError > PI) {yawError -= 2 * PI;}
 	while(yawError < -PI) {yawError += 2 * PI;}
 	// Clip the error to within the specified bounds
-		if (yawError>(PI/3))
-	{
-		yawError = (PI/3);
-	}
-	else if (yawError<(-PI/3))
-	{
-		yawError = (-PI/3);
-	}
+	if (yawError > yaml_max_setpoint_error_yaw_radians)
+		yawError = yaml_max_setpoint_error_yaw_radians;
+	else if (yawError < -yaml_max_setpoint_error_yaw_radians)
+		yawError = -yaml_max_setpoint_error_yaw_radians;
+
 	// > Finally, put the "yawError" into the "stateError" variable
 	stateInertial[8] = yawError;
 
 	// CONVERSION INTO BODY FRAME
-	// Convert the state erorr from the Inertial frame into the Body frame
+	// Initialise a variable for the body frame error
+	float bodyFrameError[9];
+	// Call the function to convert the state erorr from
+	// the Inertial frame into the Body frame
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 
-	calculateControlOutput_viaLQRforRates(bodyFrameError, response);
+	calculateControlOutput_viaLQR_givenError(bodyFrameError, response);
 }
 
-void calculateControlOutput_viaLQRforRates(float stateErrorBody[12], Controller::Response &response)
+void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controller::Response &response)
 {
 	// PERFORM THE "u=Kx" LQR CONTROLLER COMPUTATION
 
+	// Compute the Z-CONTROLLER
+	// > provides the total thrust adjustment
+	float thrustAdjustment =
+		- yaml_gainMatrixThrust_2StateVector[0] * stateErrorBody[2]
+		- yaml_gainMatrixThrust_2StateVector[1] * stateErrorBody[5];
+
+	// Compute the YAW-CONTROLLER
+	// > provides the body frame yaw rate
+	float yawRate_forResponse =
+		- yaml_gainYawRate_fromAngle * stateErrorBody[8];
+
 	// Instantiate the local variables for the following:
 	// > body frame roll rate,
 	// > body frame pitch rate,
-	// > body frame yaw rate,
-	// > total thrust adjustment.
-	// These will be requested from the Crazyflie's on-baord "inner-loop" controller
-	float rollRate_forResponse = 0;
-	float pitchRate_forResponse = 0;
-	float yawRate_forResponse = 0;
-	float thrustAdjustment = 0;
-	
-	// Perform the "-Kx" LQR computation for the rates and thrust:
-	for(int i = 0; i < 9; ++i)
+	float rollRate_forResponse = 0.0;
+	float pitchRate_forResponse = 0.0;
+
+	// Switch between the differnt control method for
+	// the X-Y-CONTROLLER
+	switch (yaml_controller_method)
 	{
-		// BODY FRAME Y CONTROLLER
-		rollRate_forResponse  -= yaml_gainMatrixRollRate[i] * stateErrorBody[i];
-		// BODY FRAME X CONTROLLER
-		pitchRate_forResponse -= yaml_gainMatrixPitchRate[i] * stateErrorBody[i];
-		// BODY FRAME YAW CONTROLLER
-		yawRate_forResponse   -= yaml_gainMatrixYawRate[i] * stateErrorBody[i];
-		// > ALITUDE CONTROLLER (i.e., z-controller):
-		thrustAdjustment      -= yaml_gainMatrixThrust_NineStateVector[i] * stateErrorBody[i];
+		case CONTROLLER_METHOD_RATES:
+		{
+			// Compute the X-CONTROLLER
+			// > provides the body frame pitch rate
+			pitchRate_forResponse = 
+				- yaml_gainMatrixPitchRate_3StateVector[0] * stateErrorBody[0]
+				- yaml_gainMatrixPitchRate_3StateVector[1] * stateErrorBody[3]
+				- yaml_gainMatrixPitchRate_3StateVector[2] * stateErrorBody[7];
+
+			// Compute the Y-CONTROLLER
+			// > provides the body frame roll rate
+			rollRate_forResponse = 
+				- yaml_gainMatrixRollRate_3StateVector[0] * stateErrorBody[1]
+				- yaml_gainMatrixRollRate_3StateVector[1] * stateErrorBody[4]
+				- yaml_gainMatrixRollRate_3StateVector[2] * stateErrorBody[6];
+			break;
+		}
+
+		case CONTROLLER_METHOD_RATE_ANGLE_NESTED:
+		{
+			// Compute the X-CONTROLLER
+			// > Compute the desired pitch angle
+			float pitchAngle_desired = 
+				- yaml_gainMatrixPitchAngle_2StateVector[0] * stateErrorBody[0]
+				- yaml_gainMatrixPitchAngle_2StateVector[1] * stateErrorBody[3];
+			// Clip the request to within the specified limits
+			if (pitchAngle_desired > yaml_max_roll_pitch_request_radians)
+				pitchAngle_desired = yaml_max_roll_pitch_request_radians;
+			else if (pitchAngle_desired < -yaml_max_roll_pitch_request_radians)
+				pitchAngle_desired = -yaml_max_roll_pitch_request_radians;				
+			// > Compute the pitch rate
+			pitchRate_forResponse =
+				- yaml_gainPitchRate_fromAngle * (stateErrorBody[7] - pitchAngle_desired);
+
+			// Compute the Y-CONTROLLER
+			// > Compute the desired roll angle
+			float rollAngle_desired = 
+				- yaml_gainMatrixRollAngle_2StateVector[0] * stateErrorBody[1]
+				- yaml_gainMatrixRollAngle_2StateVector[1] * stateErrorBody[4];
+			// Clip the request to within the specified limits
+			if (rollAngle_desired > yaml_max_roll_pitch_request_radians)
+				rollAngle_desired = yaml_max_roll_pitch_request_radians;
+			else if (rollAngle_desired < -yaml_max_roll_pitch_request_radians)
+				rollAngle_desired = -yaml_max_roll_pitch_request_radians;
+			// > Compute the roll rate
+			rollRate_forResponse =
+				- yaml_gainRollRate_fromAngle * (stateErrorBody[6] - rollAngle_desired);
+
+			break;
+		}
+
+		default:
+		{
+			// Inform the user of the error
+			ROS_ERROR("[DEFAULT CONTROLLER] The variable \"yaml_controller_method\" is not recognised.");
+			break;
+		}
 	}
 
 
+
 	// UPDATE THE "RETURN" THE VARIABLE NAMED "response"
 
 	// Put the computed rates and thrust into the "response" variable
@@ -895,6 +1330,22 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 
 
 
+// PUBLISH MOTORS-OFF MESSAGE TO FLYING AGENT CLIENT
+void publish_motors_off_to_flying_agent_client()
+{
+	// Instantiate a local variable of type "IntWithHeader"
+	IntWithHeader msg;
+	// Fill in the MOTORS-OFF command
+	msg.data = CMD_CRAZYFLY_MOTORS_OFF;
+	// Fill in the header that this applies
+	msg.shouldCheckForAgentID = false;
+	// Publish the message
+	m_motorsOffToFlyingAgentClientPublisher.publish(msg);
+}
+
+
+
+
 
 //    ----------------------------------------------------------------------------------
 //    L       OOO     A    DDDD
@@ -977,19 +1428,53 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	yaml_max_setpoint_change_per_second_horizontal = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_horizontal");
 	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_vertical");
 	
+	// Max error for z
+	yaml_max_setpoint_error_z = = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_z");
+
 	// Max error for yaw angle
 	yaml_max_setpoint_error_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_yaw_degrees");
 
+	// Max {roll,pitch} angle request
+	yaml_max_roll_pitch_request_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_roll_pitch_request_degrees");
+
+	// Theshold for {roll,pitch} angle beyond
+	// which the motors are turned off
+	yaml_threshold_roll_pitch_for_turn_off_degrees = getParameterFloat(nodeHandle_for_paramaters , "threshold_roll_pitch_for_turn_off_degrees");
+
 	// The thrust for take off spin motors
 	yaml_takeoff_spin_motors_thrust = getParameterFloat(nodeHandle_for_paramaters , "takeoff_spin_motors_thrust");
 	// The time for the take off spin(-up) motors
-	yaml_takoff_spin_motots_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_spin_motots_time");
+	yaml_takoff_spin_motors_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_spin_motors_time");
 
 	// Height change for the take off move-up
 	yaml_takeoff_move_up_height = getParameterFloat(nodeHandle_for_paramaters , "takeoff_move_up_height");
 	// The time for the take off spin motors
 	yaml_takoff_move_up_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_move_up_time");
 
+	// Minimum and maximum allowed time for: take off goto setpoint
+	yaml_takoff_goto_setpoint_min_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_min_time");
+	yaml_takoff_goto_setpoint_max_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_max_time");
+
+	// Box within which to keep the integrator on
+	// > Units of [meters]
+	// > The box consider is plus/minus this value
+	yaml_takoff_integrator_on_box_horizontal = getParameterFloat(nodeHandle_for_paramaters , "takoff_integrator_on_box_horizontal");
+	yaml_takoff_integrator_on_box_vertical   = getParameterFloat(nodeHandle_for_paramaters , "takoff_integrator_on_box_vertical");
+	// The time for: take off integrator-on
+	yaml_takoff_integrator_on_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_integrator_on_time");
+
+	// Height change for the landing move-down
+	yaml_landing_move_down_end_height_setpoint  = getParameterFloat(nodeHandle_for_paramaters , "landing_move_down_end_height_setpoint");
+	yaml_landing_move_down_end_height_threshold = getParameterFloat(nodeHandle_for_paramaters , "landing_move_down_end_height_threshold");
+	// The time for: landing move-down
+	yaml_landing_move_down_time_max = getParameterFloat(nodeHandle_for_paramaters , "landing_move_down_time_max");
+
+	// The thrust for landing spin motors
+	yaml_landing_spin_motors_thrust = getParameterFloat(nodeHandle_for_paramaters , "landing_spin_motors_thrust");
+	// The time for: landing spin motors
+	yaml_landing_spin_motors_time = getParameterFloat(nodeHandle_for_paramaters , "landing_spin_motors_time");
+
+
 
 
 	// ------------------------------------------------------
@@ -1022,14 +1507,24 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// Boolean indiciating whether the debugging ROS_INFO_STREAM should be displayed or not
 	yaml_shouldDisplayDebugInfo = getParameterBool(nodeHandle_for_paramaters, "shouldDisplayDebugInfo");
 	
-	// The LQR Controller parameters for "LQR_MODE_RATE"
-	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_NineStateVector", yaml_gainMatrixThrust_NineStateVector, 9);
-	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate",               yaml_gainMatrixRollRate,               9);
-	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate",              yaml_gainMatrixPitchRate,              9);
-	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixYawRate",                yaml_gainMatrixYawRate,                9);
+	// > A flag for which controller to use:
+	yaml_controller_method = getParameterInt( nodeHandle_for_paramaters , "controller_method" );	
+
+	// The LQR Controller parameters for z-height
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixThrust_2StateVector", yaml_gainMatrixThrust_2StateVector, 2);
+	// The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollRate_3StateVector",   yaml_gainMatrixRollRate_3StateVector,  3);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchRate_3StateVector",  yaml_gainMatrixPitchRate_3StateVector, 3);
+	// The LQR Controller parameters for "CONTROLLER_MODE_LQR_RATE"
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixRollAngle_2StateVector",   yaml_gainMatrixRollAngle_2StateVector,  2);
+	getParameterFloatVector(nodeHandle_for_paramaters, "gainMatrixPitchAngle_2StateVector",  yaml_gainMatrixPitchAngle_2StateVector, 2);
+	yaml_gainRollRate_fromAngle  = getParameterFloat(nodeHandle_for_paramaters, "gainRollRate_fromAngle");
+	yaml_gainPitchRate_fromAngle = getParameterFloat(nodeHandle_for_paramaters, "gainPitchRate_fromAngle");
+	// The LQR Controller parameters for yaw
+	yaml_gainYawRate_fromAngle = getParameterFloat(nodeHandle_for_paramaters, "gainYawRate_fromAngle");
 	
 	// A flag for which estimator to use:
-	yaml_estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );	
+	yaml_estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );
 	
 	// THE POINT MASS KALMAN FILTER (PMKF) GAINS AND ERROR EVOLUATION
 	// > For the (x,y,z) position
@@ -1059,6 +1554,16 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// > Conver the control frequency to a delta T
 	m_control_deltaT = 1.0 / yaml_control_frequency;
 
+	// Max error for yaw angle
+	yaml_max_setpoint_error_yaw_radians = DEG2RAD * yaml_max_setpoint_error_yaw_degrees;
+
+	// Max {roll,pitch} angle request
+	yaml_max_roll_pitch_request_radians = DEG2RAD * yaml_max_roll_pitch_request_degrees;
+
+	// Theshold for {roll,pitch} angle beyond
+	// which the motors are turned off
+	yaml_threshold_roll_pitch_for_turn_off_radians = DEG2RAD * yaml_threshold_roll_pitch_for_turn_off_degrees;
+
 	// DEBUGGING: Print out one of the computed quantities
 	ROS_INFO_STREAM("[DEFAULT CONTROLLER] DEBUGGING: thus the weight of this agent in [Newtons] = " << m_cf_weight_in_newtons);
 }
@@ -1281,7 +1786,18 @@ int main(int argc, char* argv[])
 	// will take to perform (in milliseconds)
 	ros::ServiceServer requestManoeuvreService = nodeHandle.advertiseService("RequestManoeuvre", requestManoeuvreCallback);
 
-
+	// Instantiate the class variable "m_motorsOffToFlyingAgentClientPublisher"
+	// to be a "ros::Publisher". This variable advertises under the
+	// name space:
+	// "FlyingAgentClient/Command"
+	// meaning that it is mimicing messages send by the "Fying
+	// Agent Client" node. The message sent has the structure
+	// defined in the file "IntWithHeader.msg".
+	// > First create a node handle to the base namespace
+	//   i.e., the namespace: "/dfall/agentXXX/"
+    ros::NodeHandle base_nodeHandle(m_namespace);
+    // > Now instantiate the publisher
+	m_motorsOffToFlyingAgentClientPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/Command", 1);
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 288af49a..d55fd3dc 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -377,9 +377,9 @@ bool safetyCheck_on_positionAndTilt(CrazyflieData data)
     {
         // Check on the ROLL angle
         if(
-            (data.roll > m_maxTiltAngle_for_strictSafety_radians)
+            (data.roll > yaml_maxTiltAngle_for_strictSafety_radians)
             or
-            (data.roll < -m_maxTiltAngle_for_strictSafety_radians)
+            (data.roll < -yaml_maxTiltAngle_for_strictSafety_radians)
         )
         {
             ROS_INFO_STREAM("[FLYING AGENT CLIENT] roll too big.");
@@ -387,9 +387,9 @@ bool safetyCheck_on_positionAndTilt(CrazyflieData data)
         }
         // Check on the PITCH angle
         if(
-            (data.pitch > m_maxTiltAngle_for_strictSafety_radians)
+            (data.pitch > yaml_maxTiltAngle_for_strictSafety_radians)
             or
-            (data.pitch < -m_maxTiltAngle_for_strictSafety_radians)
+            (data.pitch < -yaml_maxTiltAngle_for_strictSafety_radians)
         )
         {
             ROS_INFO_STREAM("[FLYING AGENT CLIENT] pitch too big.");
@@ -721,7 +721,7 @@ void setInstantController(int controller)
     // GUI" about this update to the instant controller
     std_msgs::Int32 controller_used_msg;
     controller_used_msg.data = controller;
-    controllerUsedPublisher.publish(controller_used_msg);
+    m_controllerUsedPublisher.publish(controller_used_msg);
 }
 
 
@@ -1006,9 +1006,9 @@ void loadCrazyflieContext()
 
     CrazyflieContext new_context;
 
-    centralManager.waitForExistence(ros::Duration(-1));
+    m_centralManager.waitForExistence(ros::Duration(-1));
 
-    if(centralManager.call(contextCall)) {
+    if(m_centralManager.call(contextCall)) {
         new_context = contextCall.response.crazyflieContext;
         ROS_INFO_STREAM("[FLYING AGENT CLIENT] CrazyflieContext:\n" << new_context);
 
@@ -1027,7 +1027,7 @@ void loadCrazyflieContext()
             IntWithHeader msg;
             msg.shouldCheckForAgentID = false;
             msg.data = CMD_DISCONNECT;
-            crazyRadioCommandPublisher.publish(msg);
+            m_crazyRadioCommandPublisher.publish(msg);
         }
 
         m_context = new_context;
@@ -1079,7 +1079,7 @@ void loadCrazyflieContext()
 void createControllerServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient )
 {
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "FlyingAgentClientConfig");
 
     std::string controllerName;
     if(!nodeHandle.getParam(paramter_name, controllerName))
@@ -1096,7 +1096,7 @@ void createControllerServiceClientFromParameterName( std::string paramter_name ,
 void createIntIntServiceClientFromParameterName( std::string paramter_name , ros::ServiceClient& serviceClient )
 {
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
-    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "ClientConfig");
+    ros::NodeHandle nodeHandle(nodeHandle_to_own_agent_parameter_service, "FlyingAgentClientConfig");
 
     std::string controllerName;
     if(!nodeHandle.getParam(paramter_name, controllerName))
@@ -1157,7 +1157,7 @@ void timerCallback_for_createAllcontrollerServiceClients(const ros::TimerEvent&)
 //    ----------------------------------------------------------------------------------
 
 
-void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
+void isReadyFlyingAgentClientConfigYamlCallback(const IntWithHeader & msg)
 {
     // Check whether the message is relevant
     bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs );
@@ -1175,14 +1175,14 @@ void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
             // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
             case LOAD_YAML_FROM_AGENT:
             {
-                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the ClientConfig YAML parameter values from this agent.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the FlyingAgentClientConfig 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("[FLYING AGENT CLIENT] Now fetching the ClientConfig YAML parameter values from this agent's coordinator.");
+                ROS_INFO("[FLYING AGENT CLIENT] Now fetching the FlyingAgentClientConfig YAML parameter values from this agent's coordinator.");
                 namespace_to_use = m_namespace_to_coordinator_parameter_service;
                 break;
             }
@@ -1197,20 +1197,20 @@ void isReadyClientConfigYamlCallback(const IntWithHeader & msg)
         // Create a node handle to the selected parameter service
         ros::NodeHandle nodeHandle_to_use(namespace_to_use);
         // Call the function that fetches the parameters
-        fetchClientConfigYamlParameters(nodeHandle_to_use);
+        fetchFlyingAgentClientConfigYamlParameters(nodeHandle_to_use);
     }
 }
 
 
 
 // > Load the paramters from the Client Config YAML file
-void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
+void fetchFlyingAgentClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 {
     // Here we load the parameters that are specified in the file:
-    // ClientConfig.yaml
+    // FlyingAgentClientConfig.yaml
 
-    // Add the "ClientConfig" namespace to the "nodeHandle"
-    ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "ClientConfig");
+    // Add the "FlyingAgentClientConfig" namespace to the "nodeHandle"
+    ros::NodeHandle nodeHandle_for_paramaters(nodeHandle, "FlyingAgentClientConfig");
 
     // Flag for whether to use angle for switching to the Safe Controller
     yaml_isEnabled_strictSafety = getParameterBool(nodeHandle_for_paramaters,"isEnabled_strictSafety");
@@ -1232,16 +1232,16 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 	yaml_shouldPerfom_landing_with_defaultController = getParameterBool(nodeHandle_for_paramaters,"shouldPerfom_landing_with_defaultController");
     
     // DEBUGGING: Print out one of the parameters that was loaded
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched ClientConfig/isEnabled_strictSafety = " << yaml_isEnabled_strictSafety);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT] DEBUGGING: the fetched FlyingAgentClientConfig/isEnabled_strictSafety = " << yaml_isEnabled_strictSafety);
 
 
 
     // PROCESS THE PARAMTERS
     // Convert from degrees to radians
-    m_maxTiltAngle_for_strictSafety_radians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
+    yaml_maxTiltAngle_for_strictSafety_radians = DEG2RAD * yaml_maxTiltAngle_for_strictSafety_degrees;
 
     // DEBUGGING: Print out one of the processed values
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT CONTROLLER] DEBUGGING: after processing m_maxTiltAngle_for_strictSafety_radians = " << m_maxTiltAngle_for_strictSafety_radians);
+    ROS_INFO_STREAM("[FLYING AGENT CLIENT CONTROLLER] DEBUGGING: after processing yaml_maxTiltAngle_for_strictSafety_radians = " << yaml_maxTiltAngle_for_strictSafety_radians);
 }
 
 
@@ -1259,70 +1259,91 @@ void fetchClientConfigYamlParameters(ros::NodeHandle& nodeHandle)
 
 int main(int argc, char* argv[])
 {
-    // Starting the ROS-node
+	// Starting the ROS-node
 	ros::init(argc, argv, "FlyingAgentClient");
 
-    // 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
-    std::string m_namespace = ros::this_node::getNamespace();
-    ROS_INFO_STREAM("[FLYING AGENT CLIENT] ros::this_node::getNamespace() =  " << m_namespace);
+	// Get the namespace of this node
+	std::string m_namespace = ros::this_node::getNamespace();
+	ROS_INFO_STREAM("[FLYING AGENT CLIENT] ros::this_node::getNamespace() =  " << m_namespace);
 
 
 
-    // AGENT ID AND COORDINATOR ID
+	// AGENT ID AND COORDINATOR ID
 
-    // Get the ID of the agent and its coordinator
-    bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
+	// 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.
 
-    // Stall the node IDs are not valid
-    if ( !isValid_IDs )
-    {
-        ROS_ERROR("[FLYING AGENT CLIENT] Node NOT FUNCTIONING :-)");
-        ros::spin();
-    }
-    else
-    {
-        ROS_INFO_STREAM("[FLYING AGENT CLIENT] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
-    }
 
+	// Get the ID of the agent and its coordinator
+	bool isValid_IDs = getAgentIDandCoordIDfromClientNode( m_namespace + "/FlyingAgentClient" , &m_agentID , &m_coordID);
 
+	// Stall the node IDs are not valid
+	if ( !isValid_IDs )
+	{
+		ROS_ERROR("[FLYING AGENT CLIENT] Node NOT FUNCTIONING :-)");
+		ros::spin();
+	}
+	else
+	{
+		ROS_INFO_STREAM("[FLYING AGENT CLIENT] loaded agentID = " << m_agentID << ", and coordID = " << m_coordID);
+	}
 
-    // PARAMETER SERVICE NAMESPACE AND NODEHANDLES:
 
-    // 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";
 
-    // Set the class variable "m_namespace_to_coordinator_parameter_service",
-    // i.e., the namespace of parameter service for this agent's coordinator
-    constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
+	// PARAMETER SERVICE NAMESPACE AND NODEHANDLES:
 
-    // Inform the user of what namespaces are being used
-    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);
+	// 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.
 
-    // 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);
-    ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
+	// 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";
+
+	// Set the class variable "m_namespace_to_coordinator_parameter_service",
+	// i.e., the namespace of parameter service for this agent's coordinator
+	constructNamespaceForCoordinatorParameterService( m_coordID, m_namespace_to_coordinator_parameter_service );
 
+	// Inform the user of what namespaces are being used
+	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);
+	ros::NodeHandle nodeHandle_to_coordinator_parameter_service(m_namespace_to_coordinator_parameter_service);
 
-    // SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
 
-    // The parameter service publishes messages with names of the form:
-    // /dfall/.../ParameterService/<filename with .yaml extension>
-    ros::Subscriber clientConfig_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "ClientConfig", 1, isReadyClientConfigYamlCallback);
-    ros::Subscriber clientConfig_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("ClientConfig", 1, isReadyClientConfigYamlCallback);
 
-    //ros::Subscriber safeController_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "SafeController", 1, isReadySafeControllerYamlCallback);
-    //ros::Subscriber safeController_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("SafeController", 1, isReadySafeControllerYamlCallback);
+	// SUBSCRIBE TO "YAML PARAMTERS READY" MESSAGES
 
+	// The parameter service publishes messages with names of the form:
+	// /dfall/.../ParameterService/<filename with .yaml extension>
+	ros::Subscriber flyingAgentClientConfig_yamlReady_fromAgent = nodeHandle_to_own_agent_parameter_service.subscribe(  "FlyingAgentClientConfig", 1, isReadyFlyingAgentClientConfigYamlCallback);
+	ros::Subscriber flyingAgentClientConfig_yamlReady_fromCoord = nodeHandle_to_coordinator_parameter_service.subscribe("FlyingAgentClientConfig", 1, isReadyFlyingAgentClientConfigYamlCallback);
 
 
-    // GIVE YAML VARIABLES AN INITIAL VALUE
+	// GIVE YAML VARIABLES AN INITIAL VALUE
 
 	// This can be done either here or as part of declaring the
 	// variables in the header file
@@ -1331,183 +1352,174 @@ int main(int argc, char* argv[])
 
 	// FETCH ANY PARAMETERS REQUIRED FROM THE "PARAMETER SERVICES"
 
-    // Call the class function that loads the parameters for this class.
-    fetchClientConfigYamlParameters(nodeHandle_to_own_agent_parameter_service);
-    //fetchSafeControllerYamlParameters(nodeHandle_to_own_agent_parameter_service);
-
-
-
-
-
-    // INITIALISE ALL THE CONTROLLER SERVICE CLIENTS
-    // > This cannot be done directly here because the other nodes may
-    //   be currently unavailable. Hence, we start a timer for a few
-    //   seconds and in the call back all the controller service
-    //   clients are created.
-    m_controllers_avialble = false;
-    m_timer_for_createAllControllerServiceClients = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_createAllcontrollerServiceClients, true);
-
+	// Call the class function that loads the parameters
+	// from the "FlyingAgentClientConfig.yaml" file.
+	// > This is possible because that YAML file is added
+	//   to the parameter service when launched via the
+	//   "agent.launch" file.
+	fetchFlyingAgentClientConfigYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
 
 
 
-    // INITIALISE THE MOTION CAPTURE TIME-OUT TIMER
-    // > And stop it immediately
-    m_isAvailable_mocap_data = false;
-    m_timer_mocap_timeout_check = nodeHandle.createTimer(ros::Duration(yaml_mocap_timeout_duration), timerCallback_mocap_timeout_check, true);
-    m_timer_mocap_timeout_check.stop();
-    
 
-    // INITIALISE THE TAKE-OFF AND LANDING COMPLETE TIMERS
-    // > And stop it immediately
-    m_timer_takeoff_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
-    m_timer_takeoff_complete.stop();
-    m_timer_land_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
-    m_timer_land_complete.stop();
+	// INITIALISE ALL THE CONTROLLER SERVICE CLIENTS    
+	// > This cannot be done directly here because the other nodes may
+	//   be currently unavailable. Hence, we start a timer for a few
+	//   seconds and in the call back all the controller service
+	//   clients are created.
+	m_controllers_avialble = false;
+	m_timer_for_createAllControllerServiceClients = nodeHandle.createTimer(ros::Duration(3), timerCallback_for_createAllcontrollerServiceClients, true);
 
 
 
+	// INITIALISE THE MOTION CAPTURE TIME-OUT TIMER
+	// > And stop it immediately
+	m_isAvailable_mocap_data = false;
+	m_timer_mocap_timeout_check = nodeHandle.createTimer(ros::Duration(yaml_mocap_timeout_duration), timerCallback_mocap_timeout_check, true);
+	m_timer_mocap_timeout_check.stop();
 
 
-    // PUBLISHERS, SUBSCRIBERS, AND SERVICE CLIENTS
 
-	
+	// INITIALISE THE TAKE-OFF AND LANDING COMPLETE TIMERS
+	// > And stop it immediately
+	m_timer_takeoff_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
+	m_timer_takeoff_complete.stop();
+	m_timer_land_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
+	m_timer_land_complete.stop();
 
-    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
-    ros::NodeHandle nodeHandle_dfall_root("/dfall");
 
-    // CREATE A NODE HANDLE TO THE COORDINATOR
-    std::string namespace_to_coordinator;
-    constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
-    ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
 
+	// INITIALISE THE CRAZY RADIO STATUS
+	m_crazyradio_status = CRAZY_RADIO_STATE_DISCONNECTED;
 
 
 
-    // SERVICE CLIENT FOR LOADING THE ALLOCATED FLYING ZONE
-    // AND OTHER CONTEXT DETAILS
+	// INITIALISE THE FLYING STATE AND PUBLISH
+	m_flying_state = STATE_MOTORS_OFF;
 
-    //ros::service::waitForService("/CentralManagerService/CentralManager");
-	centralManager = nodeHandle_dfall_root.serviceClient<CMQuery>("CentralManagerService/Query", false);
-	loadCrazyflieContext();
 
-    // Subscriber for when the Flying Zone Database changed
-    ros::Subscriber databaseChangedSubscriber = nodeHandle_dfall_root.subscribe("CentralManagerService/DBChanged", 1, crazyflieContextDatabaseChangedCallback);
 
-    // EMERGENCY STOP OF THE WHOLE "D-FaLL-System"
-    ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopReceivedCallback);
 
-    // LOCALISATION DATA FROM MOTION CAPTURE SYSTEM
-	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
-	ros::Subscriber viconSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, viconCallback);
 
+	// PUBLISHERS, SUBSCRIBERS, AND SERVICE CLIENTS
 
 
-    // PUBLISHER FOR COMMANDING THE CRAZYFLIE
-    // i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
-	//ros::Publishers to advertise the control output
-	m_commandForSendingToCrazyfliePublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
+	// CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
+	ros::NodeHandle nodeHandle_dfall_root("/dfall");
 
-	//this topic lets the FlyingAgentClient listen to the terminal commands
-    //commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
 
+	// CREATE A NODE HANDLE TO THE COORDINATOR
+	std::string namespace_to_coordinator;
+	constructNamespaceForCoordinator( m_coordID, namespace_to_coordinator );
+	ros::NodeHandle nodeHandle_to_coordinator(namespace_to_coordinator);
 
 
-    // SUBSCRIBER FOR THE CHANGE STATE COMMANDS
-    // i.e., {TAKE-OFF,LAND,MOTORS-OFF,CONTROLLER SELECTION}
-    // > for the agent GUI
-    ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, flyingStateRequestCallback);
-    // > for the coord GUI
-    ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("FlyingAgentClient/Command", 1, flyingStateRequestCallback);
+	// LOADING OF THIS AGENT'S CONTEXT
+	// Service cleint for loading the allocated flying
+	// zone and other context details
+	//ros::service::waitForService("/CentralManagerService/CentralManager");
+	m_centralManager = nodeHandle_dfall_root.serviceClient<CMQuery>("CentralManagerService/Query", false);
+	// Call the class function that uses this service
+	// client to load the context
+	loadCrazyflieContext();
+	// Subscriber for when the Flying Zone Database changed
+	ros::Subscriber databaseChangedSubscriber = nodeHandle_dfall_root.subscribe("CentralManagerService/DBChanged", 1, crazyflieContextDatabaseChangedCallback);
 
 
+	// EMERGENCY STOP OF THE WHOLE "D-FaLL-System"
+	ros::Subscriber emergencyStopSubscriber = nodeHandle_dfall_root.subscribe("emergencyStop", 1, emergencyStopReceivedCallback);
 
 
-    // PUBLISHER FOR THE CRAZYRADIO COMMANDS
-    // i.e., {CONNECT,DISCONNECT}
-    // This topic lets us use the terminal to communicate with
-    // the crazyRadio node even when the GUI is not launched
-    crazyRadioCommandPublisher = nodeHandle.advertise<IntWithHeader>("crazyRadioCommand", 1);
+	// LOCALISATION DATA FROM MOTION CAPTURE SYSTEM
+	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
+	ros::Subscriber viconSubscriber = nodeHandle_dfall_root.subscribe("ViconDataPublisher/ViconData", 100, viconCallback);
 
 
 
-    // PUBLISHER FOR THE FLYING STATE
-    // Possible states: {MOTORS-OFF,TAKE-OFF,FLYING,LAND}
-    // This topic will publish flying state whenever it changes.
-    m_flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
+	// PUBLISHER FOR COMMANDING THE CRAZYFLIE
+	// i.e., motorCmd{1,2,3,4}, roll, pitch, yaw, and onboardControllerType
+	//ros::Publishers to advertise the control output
+	m_commandForSendingToCrazyfliePublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
 
-    
 
-    // PUBLISHER FOR THE 
-    controllerUsedPublisher = nodeHandle.advertise<std_msgs::Int32>("controllerUsed", 1);
+	// SUBSCRIBER FOR THE CHANGE STATE COMMANDS
+	// i.e., {TAKE-OFF,LAND,MOTORS-OFF,CONTROLLER SELECTION}
+	// > for the agent GUI
+	ros::Subscriber commandSubscriber_to_agent = nodeHandle.subscribe("Command", 1, flyingStateRequestCallback);
+	// > for the coord GUI
+	ros::Subscriber commandSubscriber_to_coord = nodeHandle_to_coordinator.subscribe("FlyingAgentClient/Command", 1, flyingStateRequestCallback);
 
 
+	// PUBLISHER FOR THE CRAZYRADIO COMMANDS
+	// i.e., {CONNECT,DISCONNECT}
+	// This topic lets us use the terminal to communicate with
+	// the crazyRadio node even when the GUI is not launched
+	m_crazyRadioCommandPublisher = nodeHandle.advertise<IntWithHeader>("crazyRadioCommand", 1);
 
 
-    // crazy radio status
-    m_crazyradio_status = CRAZY_RADIO_STATE_DISCONNECTED;
+	// PUBLISHER FOR THE FLYING STATE
+	// Possible states: {MOTORS-OFF,TAKE-OFF,FLYING,LAND}
+	// This topic will publish flying state whenever it changes.
+	m_flyingStatePublisher = nodeHandle.advertise<std_msgs::Int32>("flyingState", 1);
 
-    // publish first flying state data
-    std_msgs::Int32 flying_state_msg;
-    flying_state_msg.data = m_flying_state;
-    m_flyingStatePublisher.publish(flying_state_msg);
 
-    // SafeControllerServicePublisher:
-    ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
-    //safeControllerServiceSetpointPublisher = namespaceNodeHandle.advertise<dfall_pkg::Setpoint>("SafeControllerService/Setpoint", 1);
-    //ros::Subscriber controllerSetpointSubscriber = namespaceNodeHandle.subscribe("student_GUI/ControllerSetpoint", 1, controllerSetPointCallback);
-    //ros::Subscriber safeSetpointSubscriber = namespaceNodeHandle.subscribe("SafeControllerService/Setpoint", 1, safeSetPointCallback);
+	// PUBLISHER FOR THE CONTROLLER CURRENTLY IN USE
+	// This publishes the "m_instant_controller" variable
+	// to reflect the controller that is actually called
+	// when motion capture data is received.
+	m_controllerUsedPublisher = nodeHandle.advertise<std_msgs::Int32>("controllerUsed", 1);
 
-    
 
-    
-    // crazyradio status. Connected, connecting or disconnected
-    ros::Subscriber crazyRadioStatusSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
+	// SUBSCRIBER FOR CRAZY RADIO STATUS CHANGES
+	// crazyradio status. Connected, connecting or disconnected
+	std::string namespace_to_crazy_radio = m_namespace + "/CrazyRadio";
+	ros::NodeHandle nodeHandle_to_crazy_radio(namespace_to_crazy_radio);
+	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle_to_crazy_radio.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
 
+	// SUBSCRIBER FOR BATTERY STATE CHANGES
+	// The battery state change message from the Battery
+	// Monitor node
+	std::string namespace_to_battery_monitor = m_namespace + "/BatteryMonitor";
+	ros::NodeHandle nodeHandle_to_battery_monitor(namespace_to_battery_monitor);
+	ros::Subscriber CFBatterySubscriber = nodeHandle_to_battery_monitor.subscribe("ChangedStateTo", 1, batteryMonitorStateChangedCallback);
 
 
+	// SERVICE SERVER FOR OTHERS TO GET THE CURRENT FLYING STATE
+	// Advertise the service that return the "m_flying_state"
+	// variable when called upon
+	ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("getCurrentFlyingState", getCurrentFlyingStateServiceCallback);
 
-    // will publish battery state when it changes
-    //batteryStatePublisher = nodeHandle.advertise<std_msgs::Int32>("batteryState", 1);
 
-    // INITIALISE THE BATTERY VOLTAGE TO SOMETHING CLOSE TO FULL
-    // > This is used to prevent the "Low Battery" being trigged when the 
-    //   first battery voltage data is received
-    //m_battery_voltage = 4.2f;
-    // know the battery level of the CF
-    //ros::Subscriber CFBatterySubscriber = namespaceNodeHandle.subscribe("CrazyRadio/CFBattery", 1, CFBatteryCallback);
 
-    //setBatteryStateTo(BATTERY_STATE_NORMAL); //initialize battery state
 
-    // Subscribe to the battery state change message from the Battery Monitor node
-    std::string namespace_to_battery_monitor = m_namespace + "/BatteryMonitor";
-    ros::NodeHandle nodeHandle_to_battery_monitor(namespace_to_battery_monitor);
-    ros::Subscriber CFBatterySubscriber = nodeHandle_to_battery_monitor.subscribe("ChangedStateTo", 1, batteryMonitorStateChangedCallback);
 
+	// PUBLISH THE FLYING STATE
+	// Ideally the GUI receives this message
+	std_msgs::Int32 flying_state_msg;
+	flying_state_msg.data = m_flying_state;
+	m_flyingStatePublisher.publish(flying_state_msg);
 
-	//start with safe controller
-    m_flying_state = STATE_MOTORS_OFF;
-    setControllerNominallySelected(DEFAULT_CONTROLLER);
-    setInstantController(DEFAULT_CONTROLLER); //initialize this also, so we notify GUI
 
+	// SET THE INITIAL CONTROLLER
+	// This cannot be done before the publishers because
+	// the function also sets the "m_instant_controller"
+	// (as the "m_flying_state" is "STATE_MOTORS_OFF")
+	// and the function that sets the instant controller
+	// publishes a message with the information.
+	setControllerNominallySelected(DEFAULT_CONTROLLER);
 
-    // Advertise the service for the current flying state
-    ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("getCurrentFlyingState", getCurrentFlyingStateServiceCallback);
 
 
 
-    // Open a ROS "bag" to store data for post-analysis
-	// std::string package_path;
-	// package_path = ros::package::getPath("dfall_pkg") + "/";
-	// ROS_INFO_STREAM(package_path);
-	// std::string record_file = package_path + "LoggingFlyingAgentClient.bag";
-	// bag.open(record_file, rosbag::bagmode::Write);
 
-	ros::spin();
+	// Print out some information to the user.
+    ROS_INFO("[FLYING AGENT CLIENT] Ready :-)");
 
-	// Close the ROS "bag" that was opened to store data for post-analysis
-	//bag.close();
+    // Enter an endless while loop to keep the node alive.
+    ros::spin();
 
+    // Return zero if the "ross::spin" is cancelled.
     return 0;
 }
-- 
GitLab


From 134b80b34a4954f1fa1711cee685f44e3c49f805 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 13 Feb 2019 13:10:57 +0100
Subject: [PATCH 82/87] Added 3D printable designs of the marker mount, battery
 connector, and point mass load

---
 hardware_designs/Connector_3point_v03.STL | Bin 0 -> 74484 bytes
 hardware_designs/Load_PM_20mmBox_v01.STL  | Bin 0 -> 64484 bytes
 hardware_designs/MarkerMount_v17.STL      | Bin 0 -> 293284 bytes
 3 files changed, 0 insertions(+), 0 deletions(-)
 create mode 100644 hardware_designs/Connector_3point_v03.STL
 create mode 100644 hardware_designs/Load_PM_20mmBox_v01.STL
 create mode 100644 hardware_designs/MarkerMount_v17.STL

diff --git a/hardware_designs/Connector_3point_v03.STL b/hardware_designs/Connector_3point_v03.STL
new file mode 100644
index 0000000000000000000000000000000000000000..61cdf08dd774b85efdcd39d6676689a17f29cada
GIT binary patch
literal 74484
zcmbWA3A~rn_Wz%ROrg*q4T>Vo6AkBlzu(fNt_T?_bTyhP(``V<SSrepq>@x3A>u0P
ze6Pg4QXyj*$~6;Ll$+@G-=DS5^X<LA&pG#ZU;ppxb#L2Q>;0^?pJDH{*YoVXuO5E+
zuz__h8GhxJgD$yd_*ECR95H;@mDgN!UCTQEf4{f(i|{MTUU^j8Oq(B$N$Zch8=sOH
zcwz%9KR6?k88UdVl_iURMOjKnH2SDb=E`}^(y?azZ%9z<rTVQi<Bw`v3Zdg(zU7OQ
zjv)_UKkqjy%l7)(RjnK!U;la=v4q5j6WeCayQo5%+DU?1tRJbc9wb!m)UI+FHsZ5L
zEuQtz2G7YUHCtwG%%ttO|C?7N=B;a%Df+qd|KU}j)xAk({(ricLX4?UJG0?~4kno~
zqf+k9IIzvJnM}`4r4W>m81P8FOrNIRN+D=tb^V%|Ddk!x>_zw$WqDi@FU_ryX;HpW
zDK<z@>)u<A&iuPp-BJijZhg0U=7rf+O^Zj0@C&^PiRzj4YY!>K29Gsk#$GM`J-(-5
z!rkqZkdVDEe=k>tjrds9QvJH___35HD#G3H$=s7N)w}hy<Nj}VB8gSspO87I*wbM>
zcr0r1jD!RwBpz#5KU1lHk1}c=KZDdN`%dIJ(OvR(qmS(T@T@1jiq9?y-IZ0Fy<W=M
z<*}&s!0(kZRi{-dg`k9lo|}7bS^j?z)EYdgN~YmiOAA>Cm5Z{JkkHfo?1PI-u|a}b
zZD-fWOueRUDK;n}q3dzSyN{G&g9Nq49C~b~X!-30$$C&iLf8L@(X&diL4sQQzgR!>
z;k2LHCv8wdLU-k{FU%;#1_^349^I%68<ddH)3wjM2TQR*f?CUuYf;9zqJ)H={~ue=
zDa8f}YW+6t<T9>#Ai;6f`?NlNVJS99P;1@74rScCl#o!L*mlXYrPv@rt(hlh%6JAT
zA)#Ko!2vIqVuJ*=)bhnG2Jfvfk|CkU>HMv4mtup*q86j5DB8B_r0gy46l7(sMa$3A
z56-BbUif|A)ar`wrCYUZnLed;rPLWq_RYMz-{YzOjQFQ}sz^|B>rn@1x?Ov1s^hrN
zJH)M0?TNM0AwdZVwtQt1)QXSf&lA03J?LTl_lnE*&-02B60wbBJxEY1{`*BEi=2(U
zKlRSTGV9j%Os`wJIIXhIw8{_87?At>UVR_E?v>;dF&z^{b_HpJ$8FVVgxN?}_i>6S
zPf$W4F8g!kt$5;rBS+h@-v4oKdhM)ht$g>iN7Fn~=oPhQts7}X&2o$W3&CTNSh?y7
zqi0lGoDOY}pcc<aNbG5NlO5}oN5`f|{<Fx+W2@i(KYB%CXU5Yn9e!7ySC2jAC0|Xy
zAU*Z<znF~+dL5shxoMo0SMIkrHt}bd5)u{nj4`6Yo~C&=NKotd=Wj6L@FhM%SM9wG
z`rB>Rji%LP+_e9(<|J0vxZdbjn#{`cir0f$ynE!4e#tv=Q=@C_xPyK?Ce7>Q^<#n(
z5<G8Z6V$q=y1y4X?YJ}@5|ohOmCX^>3U8~{+a04Q-R|3^>3346T6xStFQf+!u5aa5
zE#Gnf`d^U|YN<uMw{~rzTDZ9U;M$2+F5hWn9&y>}x^IfoZMJt!Z@%X|E8o|@S9-_B
zJB&D};Qs$YQ0t^!x;u)}^}gtsNAS3B4jO1$i@rVYzu4e$Nt`(1N~4eOt)uv#uQ>^7
z{Wjz}r&*Lv*8J{Q?z9^IwD9TlzK;(xtzQN$N{{U`#s03d?kzap&MqY+GD|KrT1N^A
zTAy0^dehp`Z`}V_a}sU3j5GSMW5(y%V9lx3Z>YcK``t7<kD!Fa+24B`cP>TiV>Ks1
ztsb2w*}2-)eSV$|N=P)^eS_5_d0&yB*0wuF8<DIB&pV$LUZ<$!m%M@`%6_7FENVSe
z>29mJp2yGzB_!6Zz0Zi`Q%izc1>f9b#3S36<=Nn~#_K<SPh+Q9lzybQ&+5oCUvo-G
zG@a$2^W-%rL9Go-JdwN;*~+l>=~mU>iMsRUk$&E*g7J4*4b|c_UDMObuYSC{aPuMl
z*;FfG>N$cE68F8~@5E%wz~_AQz{zGq&pDsq&;}(Wc!!ovP;2<JSEY45lFtVvB+9<q
z*#mq!QMoI3o!y<mdo1*dlG2C=XDoL|@jrh(NW^7n&B`9?G>g(TTW)aw`kyB#A+a^1
z_|SV;HbJew-|;Wk))b{{w|mo({^xB_LSpCS1Ds}2I{6Hepw=htR-28F`>%1N|9Kmf
zkXSlohY`u%fCRN}S*P)TQTnNuU&*sU35g@xer!at{~$rFb}wJ!ZA^P9&juwV?(F)S
z5xVnzy`7KlFHuB-TE~6T-iXtWdNz-sgv9bz&l!=t+euJs>Ey$WSaRFKJR6h*#BGln
zk?ajfEQMCnD&G|9dOY3|k)=CE6j4H=<DA)MBiTohpjNY9>&?b}Bd6xogAx+otx^W3
zD4lF~Nl>eP(Yt12_kFkK*`S2P@fBy9jbuwrf?8jX-DNf|{w6<8q=dw^*UU8=$+n#Y
zwT_-%+la}3@0(W-N=VFqU75ksVmK1inttXPMvNKSHO~emBswi$VMMb3AVIC`_8V`+
z#TWVa2$B2wCyEjhzpQ)9h-9xuf?5aM^n?-DHdVy$f8GWqBtE?Q8za=CmQ7IWfP3CG
zqIK7!^9e{uTzsS60QfOOo(&Mx`ttV3h)%mJ<=LRtLmLh=EsY?`CMY4%V4X5VrNurZ
zs1^5DQIsDoF`8hM!3ZZR`T6TX35m|Bt`>0&uf5SdS^k$KsKqf{NW`(B{N0|NX2(^e
zw{pS^D<{t`B_uk}nQlaKtVV)bqtBRSMDi}7gv9z`-YbnP!+MaQ)*YWcWHyp_J0&Fg
zR-S1@@@^+Vt;~sYjYvMVl#qC7vafmasU<<JidE;Cjb!UX35osI&o(02`jDX3mRa+S
zNVcMskl3@<pWWn0m;|*JJ-xu6t3+==35nh}&oLs|8<3#ZjINIwk?hqdA@SNb-bS)l
zBSEeH7keAY-kA~-m+kg8lD#ttYNdbk=PDUxP(ors*4s!%86>FH@+fa387)ylqOiHQ
zk&Ko|P;1GH{@zVSeUy;+Qy+g{C8ItP)SB{(e+HjQM6Z;PsMFd%AIa#I1hrmX>ua8j
z!YLtf!27-}Nk-u$sP+9h-mBzjf)Wz7J3VN3dvY{Ef?B&D_C#`2L<xyq;~y{^$x#sr
zYCZb0?+ucpJ4#6Od**(#k<3hxpjO;>C9@xtltv^+sU+gEw93wxu%~BUgONelM^Qqe
z?Cb{#YVA90e>+#oYlJo^AyIa|gaoyI_~l@;k&H4ZA;J7i=oND^Ynx8B<Ejs5R1*@E
zkT`pn&ygjg3=-60^by*igv5f4_xd|Ak?|ryt@w@!qQ0!G>F(3pux;Hl?tR*QR+g5I
zq`wF8l@akfI=y|1%X(kecWZSc`0mcXn^3M#$Ld(Cvt^o9e)-}a_U=w)y)n(z+-%S~
zz0!NN(g{jP==l(#`h_+~P>bG%M0{L5&&ts2xUU`eWLmj*l_!kAh~Da<Y^@~ce12A1
zxmT4{^Z2|aYp$4DTGe+xoK{30A6IYXR8GFTql5(Cd4}~+{#(bIbi+OA_ZmNLWxc^t
z?p=RB_WK!m=ZX>%o0~jkMDh(532L=2c+LpD{|voSdnN0-`_!(eth-NHJe8AIkP;GQ
zpIs8vQl3#ZbccpsQ9^=OGbEHf*Rgb+m4{VX*Pr)WNKisTd05fChUi_3|M@411hte^
z6_K8k|0Ygttt7hUdV{I5-nc5ut#ZY$Cg$0ogoNJRiqPBM5~oVuL6V@Ba_=Ih_PZsI
zpoE0pO^VRl<<JHRYUyo_h(^sv<q>har1t8=E^SRqWj@WJ4N6F;mynIOzI!Im1_^4Z
zXAn^|=lMM1*+Yu$j?+6@-dDRfziNL^errGpiMX8n)<EyDWnJ&E^=?~by#X)#E@A7#
zc169Y=w!=42?>37AVOa%glCrowRney1SKT&WrS?#`-!p%YU%yCh-B+SiQc$NORXAh
zmu-WD-tdc7i&{28Ek0c#!TU!MfQ~z{!LtAH-X)=EKy>#Jc>iI26z^SXDXJ9_M94-^
zLPFV=(ru8SmZEbJL8NasC?TP2iwK>C@LZ9gmPQ#Of)R_^poE07Eh3UnEeUFAv?L-J
zd6^ALNGRJPBH5OZpq55`W`iS0vq1?7Wm`ljMhVXq32JHdDk2yOn+-}xDBB_;8T*i+
zmPX+sf)TyhpoE07Eg}>Xh4mmoEoBo#1epo5K?w<ETSO#VI1<!SRzyUQVKEz&kWjWo
zg!<sH9wexx?2d>aQ)D(MA)#!Gh-80Gf?CQ_i3r|*m<>uuDBB_;*`Jf3ma=Ukg3O)S
zpoE07Eh3WrISFbhYbYYfK$;CoNGRJPA{i}_pq8?qB7#h+*`S1kvMnN#F&qhMDT^y2
z$OxMaN=PW%B0^DScwdpAma@?zg3PwrpoE07Eg}@vhBio0i(|NupoE07EwYh}!bwnz
zqu0;|#~JGyy<{<!;slOMLV^+!P2N~#bTX15L9Oq%tT7@vR@0Xbs-f=cW1>f_tgq(u
z?T`MRe4;2JG3>>;MkFI-64cTcNwSe_87Lv~@W<Z6WTa1mS{zx1XO|KZw_dowyh?uk
zNrGA&e}*=$*tN)xrFgg5GmlzX--z<8hXf@gRy{G#XnlEFHbE_3n~>lrMc+f}8t9sr
zJz}ARgua>-o%D(XwaSk4DIuZnVPzxvZ7m6Eag-6(oMR4s{i);X`&}L>Bq$-F?^8u<
zv{W`hEsl^wf)Wz?=2kY6BQFxvivOM*dBvkf<-%eumE*r_{26*h35mG;zY)^n_%pOY
z36EQLricW!^hKJ^RWh=qgak8Fp;yfN=u0OZSGgW$bV7m>68eTobh7^-K`ng;AR^fh
zQbI!CFo{U^gCwY>uNFik`*TW2=o=;x$^M)Kwe&58h-6$s2?>3}BqAA?kf4^n2@#Qu
zuP7m*Z<s_R<0}%>(zh)ll5rv>B=ilFh-92df?E1UM?^B-rG$jOVG@z-ok>tj-x`TX
z#_g1l&^JsXlD#ttYU!IP5y|lfB_#9>lZfQ_g9Nqo?U#t;IEoSy`i4nFavVj1TKa}f
zL~=Yx2?>3}BqBK;Btb2GizgyEuBC*8zF`uP9M_VdmcA(z5xn8Gn3@t2`i4nFvK1vk
zEqxnlHu#;T*`S1kzF`uP%rlUnmcH>6k<6D+LPFm&iAd&4NKi}Ps)|VFeJCNJubxCC
z^FAb~rLS~FB=c94kkEHhB9b{W64Z+OuHX%?T@Ok~=)G#`HsU-r-=(QPkMq092!N89
zmKHO5Vb4i|S}oigEqPU%jlB{QWxw;{v8Yw{sE860nn@zBlFvB_YH>ss)|}^EGYNED
z-AlYqAwdZV%^nh+yxU1oi{~x0K?w=X9+HjZQ%izcd><Lw;5*3p`s=-;zWA4oWCTD7
z3BI!kZIGarzWA4oWCTD7i7xN_)d-CfLK`Hg#W7q+P(q^n&?ROgIUA4!wK%ejqV+8o
z6wA`<r(cz=-R+l@RzeuK=;xHmn)R#lSI-w)d3&Am=_tA&^*1A)JoSozpq9!yk|!SR
zxZQ|uyD!dCLgLECcbSbVTIvhamb3S_mS<1){D7dA%Cg~!w#{l8v9(M0EF~l+)$U?8
z3hUQ%HZJUXq7la)oDK+TsVp0w$o$REjz0Orld_bMxaNXgg*tC<Uw4YLvHRGrW~16?
zbpnD~D$9l^)_#Ak5k1Ern5Bfo`Hjb$jiV->;cR?*)<s4XcHdP@f?6ueh9|Dsewh*T
zXTDZU35mMDeo&x#e6~byUw>;f(uhGzp9lzQsVp0wxW3zHBPLWBR!j+r^Jd@OK{m!#
z(Yw@9CtYvE>QT)Cf?6ueh9|zceVh@`e>Q3*B_!&cGqAmEG_G;Cv(a~tC$9Kt>PsZ3
zrLt^zqSwtgnvG}w`f&jzB!1gnWany9G{@OkH`&+Y_el*3Nl;5=+3-Y_j@OxuI$upH
zq=dwpbXU9P*ALKWd&^dTJ$|}kVL(tzW!dmV=Y58ljaTP?Tu2Ft0p-@1jVC_V`=~9K
zUu?vhvwjT-YN;$6o><@fOe3mJIU+>~iPt-vV9#KWs;ixiI+ME@@!B!91A<yA%Z4Wg
z4R38k#|K-bC?U~f=4i9=SazMWaqiBBMpT|y7!cG_SvEZJpIeVK;-*{9NKr!K_`y$@
zjhm*t=WIMT;Q%A*-g#a?P)lXm@I?L9pIV#vw{e40l#uxHzE90Yboxim#@OMjjaV`C
z@_?Y0%Cg~!xhLLb#9{xsHbn`E6;~Z(t2<oq_NUIqXCnq0F?jOmfS{Jjvf+uoM|`z1
za=*F*ZcI@^La~INL3dBN|Mfj$un`j;7#9%KQrYTZM2qGXkCzS2&!B{aVu{iTO7e-o
zs{&b&S0q%9wL12Az{<Ir8=;z$pq9#e&y_p7g|eZuO9_b{OJ;g|cFi9?@h&5D1xZj#
zWvh97ml&bDgc1@bfBul!@ONT^)t?%nJCOvnRF(}-ES+#bO7*Dc?siH@WY^9$8@VUS
z2t83GsHL)O<epk1^wd&9V(Gc_%|@<eFhVT@32Lb<8=j~=xtkGceJCMu-^fSJhHv5C
zY<{K@Ra^^4f?6ueMy?e#LaitzB&r?!nAym+)ZQ!CQj?&T%CeE`4UAB4KnaPN)gCt+
zxgN&|^*AJ`rLt_~dNm`|t5HJYx_i8hT+eBQdQKA5Qdu@~y|WSOohc#F;#zMb7XcWd
z2!I5&RF;iglwpLT3`$7Md)Z%)TqI+JA{i3YQdu@~(UK90mM9_d#q|sAdgLN9BNUO5
zpq9$Ak&F6_P}D~WiKa^yn2lUyX@nw664X*zHgeIc5!GDuN(qTsL+6=|T!d_dB4iTO
zQdu@~QMeI`!YLu~%3mKg8@Wi|2u1oNsHL)O<VF)lXf#0yiS|#;HXDA#vasWJYZEnM
zAweybWg|B#GD4#wN=Q^2^q|?$n94?8Mrh<kf?6ueh9?FuyTgb_re2q&gv94JpKgR-
zp@{?~B+gts)V$LAPOfi)4HDGS-}kNpwP1N$>jxiLF)quMrc{>i>M5SC+0DvY5h{x2
zFJErNuiI`62x_SuuOSsh(?2=IYTo#bu~|w;(Ay~b*YLqcR2V)wAgC4A!x6>uRRmXl
zQd#xT8Pz&fD*Jle|H&yv$SV@m;>uQ5^Odrpno~kTU-rl6EsEUPH9}{X1hrJ&yH=RH
zg65U(5{}|Iy62i+cFl7HB_wzj$|k7AGZIBFKJ}#4<C`PKSq!I`YUYgd)4fh^Zn0sP
z+b&3d^v+2Z^*#LV`ROR?T>d8W>im^|NljVS-n5D`{nP7jZ(~}W7xfM3D7s@}cO&Zj
zXH1I6C2>yU=0;zY)!Xo+haYal+aqoW2x^61E&F1F5uLjXORbsJ*}OXL#R2I*R;BH@
z2X?zCO>d*9`3cL6*yqzLgL;toa(;WG8;tJnyt?{>Sw{4I=IVf;7V8v6w_I>o*4<W7
z>*{Bx8q7T1ygGILkaUHD)9ko^x_4lj-bT@g+U1RS;nTiBJxG)*>TL8AKMZhQb=<zy
zylVQdKL-T0Sf?oZrfzeyQFFs7si7nLm{-S~IXqqa>E3qSBL-cTrnl~T461L$36nbp
z^&oM?b*CHM?2jSNtN+xlVZ`zUJpzJStWy-dyx~tqeAc#FYSWkf%&Q9y9+j^0(fM}V
zx|6O>)7vQO{n@ETy!&vypdKV@bnatxjZwp$SC{r`Z^WpgCILY$)+vhC+&|EW8aI7a
z_`^R2m{<KjElO9Ne32b@)a%!$>8)!Mm-aW}$|wrzL1OySen$VP;V9=--x__4sNCm}
zfS?xZ6h-I#{Td@a**dLo(XRu|tM3oJJ>C9+OYFFNuDB&lZ=<Nj@gt0Q>d(&v^&rvk
zo&iQ*_-&E%YHabPMszuKZ9q_qb&8^9Kipu%j>GpUoOkYE^Q!j9N$F=k8)V1rvSLD-
z-bT@ZPmMLA)7kBVdXV^a#XzI$9;LYeYabqEMBSZN2L!cPrzrYmwa+cR`+nn<I<8u{
zb3U1xmWOK3$DVMPmGyUd>sGG*%@d1u4(Y&pka+wUPhWhMh(r2$;>TB~7LcG8>l8(Y
zXU14PdaXFOSpLfTgD2f@=SN;GnRu_Ax7gb#TJ*KgU+u`&DrP-&Mq}dmh5k%W+o<(2
zo+$P?vRQYn32II)*2!fHCSGA)9sG51v97JGZ*Dcy?j_kMeCYwZ$6{|?7H7&;Mx5}%
zyr3Ss`(omai~L==v#!=WYqHK~)i#x%5D?U2oucTi-RGN)a&7m|>N$}0gWjEE&z)@i
zaPMq;9%FA^f8Jq$5p&P`C8&p<)R-7}u785>Z!pt&Rdtom!}S@nF(9bLI=L&@C~Y=&
z9eZL{ZHBB@`g)$VQL<5S+gxkAVsE49gyG$d`0bCHK|R!}#l#~|_}1>mRdbwIjSlH;
z!~^G64hU+oPEoY~J9UgWzj4>B+E-cM-fN+?=dv;S*#*|l$KJZ@@%~9hR9jUL)I&W$
zOmw^5_YAAvp69$er$-wj(kog91hrVFC~C0uH|wJ|-EdJ>eUYr+zvFT1`($InipQ)^
zjJ=Jbr+OS{HkMU7FQ|ul%b3_%!}p>$ovb-=J9->tM7tfm0)kqsQxx^Qdy#o{>BS?n
z>bGTm)aoZJPLPdFI~Q5}5PR$Hl3A}BQMuveK|K^%#Khu7KH_+0)8o#oI{R!f;_()P
z1A<ztQxx5KXk#OKpLu;&F^;UC_Vi+lsbu5deHL4+6?+>+`+Ppghz5Td9n?dyR!sc(
z7ayH{yYLC;)dRbH26FXV*9HW&Sf>cTqU=vQ>*TzO^L~1(OK;uX{>l)GEXz$F7u18q
z#`Qk3{O8@uo_9a*Ya_<@yD=cB#X8x!DwJzFSATS_lDmS}PpgruIlVO-1tMgF5)wb}
zu4A<K%GJXN)q@1JSf?oJarYwgO83>92OeTx>27a#WTo6)LT~MQ7@_My35ie6u41&m
zg6^6dp=(ZpTC9^jgGT5XTs>tU^GYp4)U1LXSI;25wR_hH-MfJVM9sQ~813(N_k0+k
z=Ys^bSSL5Cd#6rH*F){q`R%t`UR|x|sh9j=8FRH)fwy|jjnH#W35mCt>|<W}mcg|p
zMyM?z5on=K*0vj=wtd*=Uz%6yabEuGR`W`2JH53w(FnDPl#nQY=XRrgE9%-^Bh>Da
zpcd<7{h$%*2Z!CX$-GkU{Lgip?YQa(>8<r2MyUUwghcO-Um5Lt9M?w~vD5WYB&fwY
zxoq>qD~veE#SArvZ7{DC$t<hzz8zOF1HHAr)(G{rl#qD)yG=&>-r4o%MyNk0K`qwF
z;wvK*Up0Myoq46GFSYnhJFem@dTVis5gT1xLJ5gI8#fs3BN-R_7;&PDeMnG?b+TC0
z2*sjje7DxTQp~BcT583j^wwfHBNW3?LZVxb^+x-s&&7#GC{83nE!N56c2BstT@v*y
z8cm3nSBl%|t;M@WDBh)nM5l{A?IUCtQyZa}ngq32CmZ7!p)romqP)_`OJ`bMX^cZ}
zZERqK#s-v-SXBEhqy1>YjX#Xg_=5zsSSK3~8lmx^?l^g+QL64rd8P3ny|r<a5gJEP
zLLzmoe^&g+%Z=5H&{&NGwOA(`I~$>~vz|_Qr4hZJV0opnGrhGjrx6-+QbJ-_i!Da`
zQK}o)8liD*KtPLivOI$k$}^}XlUK@qsI`+<$}`Yg8=o7Y@i`?V1|0T-(SAhlasWms
z2S9>atdr$rj8INSeV@Eirbs=5yi!hv-dZlh2<0*;A#uf%zQ6L>50@`7LirLB)MA~Y
zX!#c#tmjnzN<E~!QdUj9sJv4Cir!k@#|Y(pC?WBWp1yDQnWEvf%bQorTyBX3wOA+1
z^_dOj`V>vbD`f-~amXv>`sl6Y$c#{qj1m%GHSlqe&#JjRoDs^yk)Rgq6h$Y#^7RVE
z46lAUF2yWh9EB-=sj|FP*$9{4_5>v)6x*pzKFjIyq89b#=S8W-Gh#VQtA}!yl#sY?
zj*m-ymeb`$jZj{c1hshH!fb8)23$4#w*LM0u0Ypj?3ihmr%q;TEB|G>Y3aV&_}2ZV
zr7K7}%+^vu;)&xuoy^vfpjPM=v$Zpp`nUIb1~01S-^=T6r?+9YmJ$-PubFOjN@i<G
zP>Xd6v$ccXnPKNj?bY0_Gwir(8R%`8t)+xSw8YmbnXM&3E!HW_);3=6-&Cn>|NI>P
z4oa;ky$!Rql#p1p-q$IattCONpiV)y_N7_=+X(f8m$dg^J*dZ_w_&!H5)$+N;p>#l
z){>wW>l9{dYqgzaS5Ps-&D*?J>YeFrn60IR#MSqEI+?8{K`quP%+|j5koQXQRfVf(
z*?px*hTewRT1rTCZsF-<ww467Sf?;syM2xKO0nq4EBtX4_0iifTT2OvInzCz%+`{i
z7V8vdYjs?;;fmYkp;~7}$n-YM)>1;^{#QJm%+`{i7V8vdYvr%J(ilf|l2;l{(AzLu
zO9_cDpYwDwTT6mktW%h+)wPvZ8V~CF%PWn%=xvy-rG&(;%RHUT){>wW>l9{d^&H46
zjh*$Z$SaLf>1~*;rG&%}-+4NjttCM%)+x-^s?CsB$}^~4kyjeg)7vmxO9_c<T6?dO
z*;*3RVx7Wlt=d<4rJRh~V0oqN2fYomwUm%}{S05HWVV(BwOFSxTdTfEUMYX2{z_gc
zQ$%mWY%L`u#&z;_N@i<GP>Xd6v$g8C<(0Cv>f7a&vbFR!%+^vuqR&yjPRVR732L!U
zVYXH=j=WN~R&kKLQnr@fhS^$5Nc?BLr<2)Q64YXy6zRslqHL|&{!2-D6@L$@Y%RSF
zv$d3v_-M3`ER)$<64YXy!fb8!ANS<0;L}&#n>$zZHq6#iLZaB!PiH!rttCM%)+x-^
zw!7)>+}%E*?mfBtir$9VT1rUFT;u6vww467Sf?;syYtMc=9Oh@znW@Z=^3QAVYW7q
zfH?KmyNym}Ye`Uxbqce!&v%+)Ua1vr{n`{euG*`>+aOy@35gnge4UcnS`vX4>J(;c
z+gx~;d8Hob@;B}>uhh2F+b~;835mD5`8p-DwIry;I)&NVDv#Z1Ua5E9{KuW<mHI(?
z8)j=MA#wabU#DcYmISp}r!ZT4Pkrx|BAKxld#@BT(AzLuO9_c5pYn7vTT6mktW%h+
zz2uY0cCHllt==`+&XwXTdK+eIDIxK2WA9ZmTT6mktW%h+U9jGJr3hJNwK$4J>1~*;
zrG&)uUwAs1ttCM%)+x-^N}?V|qY2USN^v{A4YReBkl6QqPbagrB&fwYh1pu2MR}!>
zm(H}j(in%{hS^$5NbD-->14K+1hrVFFk7oTPF~qJMecc&R~iq}+b~;8iSFZ=ID3dM
zC$qIAsKq*k*;+lF@=7CmJ;Ab}u`|65v$d3vs9)aG$!skNYOzjXwpJ~fyi)c<t)0A5
zo`K$m*;-0S?0Cz2mCV+Xpcd<tm#uZJzPwVVNIiqRQci~6hS^$5NPMuy*D0B;B|$CL
zDa_WYhm=>!s;L*1SC*}Xw|UuGNJz~1*4L?&Y%K_Cu})#OR?&pKQbte_hrCj*kKTsa
zT1rUlKF-t0Y%K|Du})#OR&k;{QEoDh!j!*MS>7hIwUm%hY!@HN@}jwHEeUGzjD*=*
zN=W?cY9E&-v$Z6s#q$<?vz^k)s@hvtEC1xLvZ}xP^?mS_cS^IOV@W=t`Ocnjv$m|}
zZhll&v*P3ZYdJ$+GuicbzgC!=8D@l=AC;vfpO6htV186UaE83rCX)@nf*IyVWhu!g
zWWy6~7M<n7-TbJ4;F@PzF-<o7TCA8Km8B$~kPS~@epEnkB{r?;CL4bBRyX6&-k7-g
zQCUjz3EA+3o7HH9n;#VrTq{m%Rm+B7(b~<NG{Vh~%2JX~$c85{KPn)&2DVl(lMTN@
zEapdLDaj{f!xL_nsd?q*M-`Lc%4k|KO*Z_xYHlX05wFevxR{cBLN+|%X3HAk=0^nt
zS7OsTZnELmhjTM>jd1g$iYdt_WWy6~)~^w6epEnkeK@U0XV=44f_5{Djd1g$R#K8r
z*!3{N&0aRb&5vqNg6rIA?Kau)``5Y|(nh%XQ3aIb6SCn6Hw)VcH$SS71lNSqT5+=B
z*KTt&y^V15qY5d>CuGADZZ^3QZhllia1A=GU?&@X?KU@K-3T{7s*sX=LN+|%X2l!f
z=0^ntSH{yy2(sb#MRqgqjd1g$Qk3Kqvf&9gyWfavpVbKnuCSn$7i7b)&)`-NFv87`
zN>P$e$c87}Dg{Qk`B4GE6&<u5glzbACfrI0M!5M=DN6DQ+3<v0ZNUgPKPn)&&V<&r
zkPW|T9p*=+D9I;e!xL`R2y1uU{HTE7dKv7yg85NFua-~92G_Y$MykmAC`puo3i~U+
zvprXbiHW_Ed_pz%1lG$)ac66;rN<qpgY_~}l;jh8&lT3o2neq5#~rAH^)gbF<P)-y
zyGydFx9$=WT&a+IhzILsq$tTJWFvRCn+@IVB)FDhxHmc0%Scg@Psm2@sWlsVYDsV<
zNA8Ortd~(pNj@PPxz@*QsP!Sil_SGlz_DINAtm{QY~)%|v!Pa$1lP0V4&=dl8HJSO
z6S9%(4a|mm0}@=9Q!9MxZue`kV!e#^l;jh#;R&plv66(!v6gm6kd0i=X<n)4q$HmZ
zo$H;AQ148FyDo5N`(V9{VoLG}*~mp1X2Y$Q5fEJ8UhCeg9=S-y2t_iK<P);t39Ofq
zCBgOdwHm)&k0!Iy!Fm~4O7aOi(?(#ujDX-O|JpA=Hgb`r)kBdbCHaJG<f2z26upw*
zJ_OpiKsJ1YjP)|Il;jh#;R&pl5fI!FLHjAlMlRAXRtu*{pOSn+Havm#G6I78G-zK4
z*~pDp%!XUhAxlX<Ase|-(MoxxQ4tC5H=(sgWyAM4ST7?>Nj@PPp1=%H>!T!556S*2
zUNbc}9<+M6IiqeZy8-s3N|H~=D^I8n>Sy);96`oqc@p;L(u@g8NU-1a`lS&Zg>keL
z5<C{ipR^qkl#t-avTTA{^e`moFGpdt9TJp~;Ap9Af?6Ccg#;xW@6dKgP(p&^lClYE
zag-4fjF1`0mQ7GXf-!1ng9No$zmT9;q&a2?2}($Cv{W`hEslNM8<Ro(i+|ka*V*d3
zxnAaj#y@qabZ@!zm_v`v6fM8KV8Dd(xw1cg_a?_?Cw$(;p4ta~uav1eO>_QT25C~2
zOvAI57OEWoz4pXf=_q=;N|kJMNw0vAghX7f`etQEOh0;h@y`$Vd84r>I&NH+S8Zq4
z$V|Pat=WsBuLjL8etqOsW`kPId)CUVzxT(2+cW#;5f4o%E`EBZpF_xFl}2n@exUQJ
z*OD)aFFAOS*&q>@r4`ph-a4<2-d4QieLugC5)$?Iubz4R`CALG{Jvs3irO#UH{0Z=
z3(N)yYQ=x|=c>;`^^51;@8?^Vb_M0f{x8<gd^qi=_S*(V&c^e<A5=VLuAl!(NqpW&
zs2oLwl`dMDeaO!nB@vgUGh@by8U0(%ZCIv%_492zB_tY;Ze(70U1y^pwn2hgaoN}7
z*JnO07&6w+8>J*J>$o4D)iifcN0B>Mh4Hzfgv9dWTG*ZMy>ib-Vf=iMpjKSgUFovt
z**gjsPx13cDT&KEZn>{p<?c$mcMIctml6`cO*<KPySsM_<9n9`wc@hBcN^6Iuy97D
zp>|(U5|`yw#m4P$C%SvLFur#wA+c^@hukx7_iie_cS%qyF8h1ewG63pB`pIbaamr?
zJUNqVW87C3O^!{)txv3_V^J$E`_^aMs*_T;yi;H`XIv7OwZ3fG1lRZA`Xw>#cPyk0
z9xE=Z9$eQXib(KSaaj=(ZHELUBw~BXnv<XwS3(JGP(mWChkM3Ts-1rHMCCZri~p`O
zExjZmNj|YRdi}o$#fh;EAHBvckF3S9q0Xqvie%$*V8iYZ5;|5sAv#x&|4K+JroC61
z7v<);+xZ&NwPEJi7iOehxgnkYWbR3sedaxwTE1m(S$;&(!&^pYv$HO=xH{euLC1~D
zI_{N6wav8o;h1#y?=^?F{Km1_3QwQxiHU79o!V7SAGvf)ju0IaW+J+3<PF(N`};La
zDEY92mR4NWk)mkcm*cV(dw*l|8Yqd&F>&5S6`ZzyC4|juh_%csXCv0q-&O8DePlX{
zy|Uh&lDMp+%G=k^`>o{uOYI($J#?0zr4VcBSk#Kk2hJYqY%G8F>g-SJXPFI3;<9Y)
zZhT7S@-1JK*ckHhmDvf+{2Y*2OUI&CTpqdq#m+{0+n=-NY~5-$D2dCm(deT#ne(^4
zU1H;kkNal3)bq1nVl5quT5<X1%I7&7S3cGwJK~rc##0iPW#gs#tuqY{c)7$z$2&S^
z#|`!Keqt>hi&}Ac;vZTecI7QivKRJjZ#*S&SvF3o*)r31$+IOk2F|XRZSsYm@f2(6
zSk#KkfBgG2XQS3{dy3zA-p|~cx2{>H_2~=kSaEr1^DY7H`cXH#)UCK+TJf>u35kZg
zn`fSVaB=GPOS?H6nqBHvDo7C2ijU;IdbVTx;!P!U@8Ty_HsZ3LTGuUQer!Fbq~@B(
z>DJ7!|Dx8!osBX_jGmSHX@T2&Hy|{R)2%h(c}PklcE8cl)uY!1&lEpa-_N}Zj#WZS
zD?SVIHj1=PhFdekYy=Vz8>TkR-0|)ssq7i2rd_n8^(9vMH)SNK75`n=CW<sy)U9D+
zHcD&Z<j1P-Psp`=Zq4XTgIC;GGT)Mt_`H!&If^uo)2(4*Hb}%}>GZj~L9Ru0t1Y;>
zqHetxBPb#9SiAamZA3?r=2*t_ElE%-F5A_NG>_A*_hL3EiOV`_i|>xJyTo5X%@uWP
z;}}5+i2;w)v+E(+eYx!BSjO`$Nl+^;`zxq<oNjF#vq4E*)={Sps%uZ0zk-@8>edl5
zf)Wx3wmH_GDABI<adRx=`IaQ86_@=psCk@j9U-$pNnF-Ze?O{@wI%);w7H@i{$vCt
zB*s*zow@gx<)-8AL^sDWo^MHlT5-9`dw)tt(GkmArbeCK#&}BNvb<Vdzh<Utv)4;(
z9Q|rR>XQwAW_+xrV^J$E-!b%TXJgLKy;Ar0@@oQ65|?G;rMWdSZ#Vj=#73<n&r5yV
z^+5ZtSWCyER$RVndtYbc`DTMtCmgiJdK^mPvTWRY%h8#xJAN#&vG%0PQ=9Jft0BZ%
zIu^C!azSRGvvJ#-*QOekpJFyBiOaHa>$}x6U;bXsY3p~wsL`nzZ~Jv1Vl5quT5<V}
zN>`-an6=-HsWoH2w(mbEiOV|bj2YE4>(?IQwDs#aeVilw3K+4Ljzz7w-1PYC(mBGi
zsg%TJ9aTqqVRlugt>4_fH>PGy_iKN|S~?cBhHiE>f1qmmj#lH+ZZ27?QK>`zKBic-
zYX0w9b<;~OTaeoyUNKy}TZNA-pZ;)cD)m<%!|_<Okw<JCm1=tC2(v*6iP*OMh@xW-
zxi<Cb3HK!kYQ<%F>%M{XcS)iiv6haiyQf9@MowG5k~=X$P%AD!ziC$5MF9S8&x)ob
zF6-}l3Z|56omSaDQPX-Il_01Um)9Sz9f(VwS|ccl%Q~u_<_#ZoaN7Env<wM?T5<WD
zu6L!Q==!KuYVhUVji4kh>!@nGGCeyvZT)^Yt8(haLwhF(YQ^QQOD3eFsKf8$3olyl
z^9*X8`!rR26GiGjD)sLXl#hPyCimYZJ&xIkwIoqrGXFo_)6+h`In5*GdK@DtDUEpR
znp>TX^i>-R|9Hi(PemdwODnF2bJqQi_C1c-poE0_m7<?Jr@tPkb=69GoCHCw_(=X-
zmBb}RD6**Dt*1MVn-l9sVFwlWOkZ|$QCiV}%KE#T6X(``h}Tx5q%=ab`*QiRH3i3H
zeKv|jT$WaR*3CrptB*^}D@sTx`jEF%zLAZRxFkVPD?XCH<|VPH5sDLaon>8-rS1}G
z@r<}=$*si^uir*VX@vKxWL%p#yD=>-p0`{qYJ?(4U0Zpj$Wr&Q-AnM+^&f8Cl6d_#
z)}u5+_i+?y&9->`HWG1JTC9`naW;<1R`2Iq(RhT-@v=tP8ue+k?VNSLk`bh}aFoPl
z5gNk{Jh4IgxI^crqo`yAnINbYm(4^xf;57XxUA!940q+cX6bqxA8<BGMv!)PV=Wzv
zT5;LiC>cQ-K}lTJaW#e;e^lG_(h1rHqhth`AgC3Wy^WF)q!E<FWgS-|uNyPz^j~{V
zayCjvkO_iXaoO7_8QmE{NnF-(HPTbN>syAB5oCg(7Vl6O0l0O2;x+pyDUI;$RmnKY
zY><e{(hBb5s7dqkE0?rtow{>DEBC&(lFO?XrQch-wva3Ka=l+S$E5i!MqFAYB&hYn
zF9+L^hS%O$==#@b`xHOzY~22F^DHGKxE5~|O?$0wvAkN{yjeg{Yu{n}n~hgL-tBB0
zvASdNFZ;GmRXD#%u+NY7pH!VX?XHw29TJp~2yN)fZ+AA_|7<1b_*`-AXr4oVr^Ey$
z`GmgN_S)}t99G=@^wz0Q4nHYNPq?}<cO`Obge@O$#NjtL2ncFvhfI0vciUVwa<LJc
z->;RWgamgba>K65#l@#Nug1JsJs_y19WrIZ@3uL<?`9*qRX;RK2?_2><f7Mo|7FD3
z`zizkwX{Q~Z1~+a8~nOoR_E%qc|R9ZLV|k?MNxLzAx5+~;q!o?mUhUL4ZqvwPs6Ka
zRr6&{R~1u2g1ZvAl|mNPG~&%?mjnd0v_qzB_}w;_-dEqe`m)XBVoFGGS0dLtpW4uD
zygvM@fS{Ik$h33yjk27Rb~iN}|Gwq8VoFGGkD(~aRA^x~&T91AN)pu44w<syciSvC
zxRu%X{kf(qDIvi<hFtIbk|$P7==l-}YH5c|+3>q<R(PtVc~x`6%mPYCa95%z`gads
zkFNJ@4G3y!hfLY<yKTO+sj=CZG@)}LB_y~jk;_@W(a>uC(U8jnf?C=kQ#Sl=n`^4n
zGaJ{vI<t@x65N%@#qA?%nT@l*elj4ar5!S5!|%4)VaX9jTzLLlg_Mxsu0&BZY+6P0
z>W;^^1O&CTL#Ax_-8NfSjm*ZFa(fCXA;DdV+-$%h+pP7Od+Yuw64cTTnP$Uw+r0O=
zw~c7h`iK-IB)BV)dq4P(zZvntXVn6NTG}B~HvDdzl{?QiV!?}bQ<RY4u0$>_d1|7y
zS8Kki9}v{i4w<syciVjZ#cpP!&BKjTl#t-AL{YS)%duwThQ`eTf?C=kQ#Sl=n>DX|
zWTo1~S@*Y0Q9>eK-^uTARP)NZMqG7OtAL=E%Cg~i+jPBip?c?6T<_d;P0w5}tT%t^
z$+Y(X_d2i$pfHXANKmVDsw-j!7iAR4hN28gNU#@GTvFbMyIdqgf?6u89*S^W6#nGj
zk1Oe&gFTTnS1PV8&q7F0l2636MHz*0T(WY)3_Gr35$=e=GZGS%kl>k)B6kG~bj@`I
z>50ldve=U5eoP`BF+z6<32Ht1@^tgo-&gKVEL1<JJCPC++>a@W{{CXOLV2aTodmUZ
zKm4HC@Xv>PqRfV#C`w3hKPGpsI?py@zI$p(Q0x11W}6NFoV%96yi&_R2?_4U<T7c`
zy={bA9}?7hdF>pt@szb!i-&A8uhha(LW27-xt$QIMk$>uwW1`bHRYGN-o~_-+_UIf
z>XfdBT53v2a6cxO#aVKM*-&plf?7*noM$$C|FLyMEwgcs>v1R{!Tp%r%;GBbj8Lye
zf?6$)T3|MOKj?Z+^GZD@B_y~XQxv)0*=(qHCPA(AZ{CLQ&v*7{VK%zB2!Ik2+>gnv
z=<rlav!N)11hx8K{HWE#$0aV3F&m0xC?Uc9nA{u1!L7`Oq9qd4n$gwU@bQ(4$c#`#
zMhOY-$7E5Td9~9;eI%&0=xKkh{I2XSvNRitEGZ$u{g|T2MXzQ<(JKjRZJ9OS&XtdM
zU4(2l6d_YWg8MN=k&D8OP!vvrS{1AMd)LS9#nTQkqNR)UDIvlAnB3YTzwT%C&}f1L
zwK6CAXV8y7+=#_mhB0o$LJ0}($K=-6?z`Dq291hHQ0tD*9<p=g$5C$NWrRjvl#t+l
zOzy4c$i?QBMt3BrHTsNMX2XvM-3Zc%N^S&62?_Q-QRGIcMrf2uf?DkDa=lts<8x_g
zUbFUzl9s-7QJ=`Ko<f2W67jb<{@bV$ud?!rTC}G+$+q7ItEA>xjh#tQOZAh7xv{fq
zp4Hi<goLh*Z20}WO0Hm5SC9m?be&`)H+I%F&+0CrgoN%f+3@?4=}r`(u`>y3>3)-q
z+}K%ndscTlB_#B$$cEov&5fOn(Ab#-we;M`MsDn^XE3X$mJ$+r=4He06IaqQWYsc|
zpq8G0*~pEZ%`3G&l#o!{B^!RfyOI_zs}_y~wbYK;xr)cmW<z6VN=T>;mJPpeUr9@y
zRZC5RT56AFBR6(78|n=xA)&rRHvImBB|T17Jq`(Ksb7(e+}PQ!hk7+iNT^Sg4Zn|~
z8#^1Ju`>y3sehD>+}PQONv?OMgoOHb+3@>8mP7zqMF1qIrG8#Ea${$+p(ukA5{gk|
z!|!Y9#?E$jHFhRJEyXLcksCW3p=gN`5{k8C!|%^o5|L#Uk&&R5;x5_9jh)SgqCQGU
zC}xxmzt5-}J6r3c$dUxL6hE2`i$zPK*Q}yfN=PX7l?}gNYDt8gRfJ4}T8e{ZBR6(7
zuQYb1goI*v+3<V)mPGnlMfxPDrFdR8a${$+q0s~-Bs3P04Zq`U$%rMZ5eo@wX<Q;3
zxv{fGMOlrCC?TQIlGVfZ`YjoGWi|35K`oVK!;hUy#++G=J2irgkEL>~MLIX;G=h?R
zBBpITs1dz+MJ?Lnj>k40G(t5eK`mty_MWSf%!Hj?N=R_$W*ZL{%PU<$64X*wL^g8c
z!D96vx=Sb_!5ye=JZOZ*gCwY>?2c^Y#)IaS?siH@a3^gW4;rB-iUhTkrIL-@c+kAk
zQ%ea6?g(z<!K}`eS_Tr-Qtr%b#N)xN&XrmpN=PX0r~A#fi6z;=tXen{)Kb<^Hge-Z
zv!U@IB_y~*yNw5pP)kjMTFQRPMs7T4HCJyy2?_2rZ{tC;p&o|>wUot`jof(9Y-l`4
z2?^zsb*_A0TatCos^=s@EoGx+BR3v28|s}YA)&muZ1|W#*>hb%MF1qIr5w3z<i>+W
zD9WIOg!22c;bWhYw*Xm<2T4#%xqjKmjR(z!q9sa5=sksO_!zF_ZAMlR83}6XEr)F6
z#)D=<Q6D8F^u9$ld@Ne>R>mSr64cV$8rjH=2hE1YgOrfadn4KKF?Gq?C5w<rP)l!}
z>|9->uY~jl%br>ng;PR8@4sZjj}1!Rl3Aorf?9feCL6i&ptU9TCJqu3dXFa?evDJ{
zw$DZ^JQlU|7Em^F<3X#3#)FiQ;9jjZ9yCHDFA~(!+f3QeNY6%hdS7efK}tx(a~k~U
zuH+4`5tNYNey}dPU0Aocd9T*lGio(UaRvT<&)jc4^0w}oy!G_|wY9quN8Zsm#ntgi
z>>B@o(H(2)OOjv5PBP-h7wZQEwSpDxqY(`sGGhOm>!v6nQM;3meO|s;Usn~p_p%Z5
zCRGavYH@vf*GIj*!H5&qS58qv;(+&OT0PGB{48f<&x1c3@%7IA0)kpxZQgx_^jwtH
z*-fq5T}TOuI<0-2*lWmz&PIinhZ?a@)y)AxEv_9OMc4K?(ulKXt}mp7#Gm^3v2%LP
zrOrmLa<z@<@b(h{K`pKX?^a2BsGbq;+&rU@5)y^YeN5e`xppSKr^87`G-@>@AgIN4
z-QDVY9hw+1eov~95)uot-p15^w>TRsCblr5OW~FR64c@<?QTxphb@g*|J7Xul#sY=
zx3^L8tBKCWp66Q`QGHk46(p#|HP_uYkX<~nY-Z1ul#qDs8*gLM4fi-3mps+nZ2Y<9
zzQrV{#TC?Dj_kIkMojM3sF)HGy>Iq5j{SayvvJDA6O9-@Y)n8<i|e7g9Zz03-iXER
zrWR8|V$WKCUsd1vu(L7pwquM~@%(cEK`pLs?!I<EzN!)bZ1`F+B_#G+@1KteBeYlJ
zFMAF$;)C*E2L!daR(TY)X}7Ntj}G~@m=Y2%P4@Y#*N%JA*|>ejclMn3>~mn21hu&G
zcobFN=OZINeeJL;B_#S*_HD^q-#z1OtUh765d|mL2ncF%9q}mosN+H-4nDa~mJ$-{
zhxtrl(VXX<jf)Ss*@#MWPY4KVaaC|PA7@B^BThTGQI--Co#*)R;KT;YoQ)^WKGcYE
z&6@`VwYbK&TLtR9H&&`m9JjSamJ$-%v(v2I?LK0;v$0?K`74?^;`fEE0)kpveNp|n
z)+#rmLrhRYV!_6HVZ(V<5PL;}T3mlSiWZ-JXrTzzoDvde@4DM;_;cmXt`R!BB&fyJ
zwCxHSp({uUiM36qnhk%=Kkm5Dh=bf+LV{Xc8{6(gBXlQHLZV>&U1r1IyY6l`LU%g}
zYH_7&H$!2^cSiilJyDd9*nG&HX2U;&?x{`b?CPl{K`pLZ9YsIyImigL43v<#?~O@j
z!?z`_^)W)N4+&~<6>2vR^0s4)c*(VJl#qCE?L@QT+eFuj8lhH{1hurrukKx~rfn^?
z5o)O^A<?a>x8d7%*Bcly(e(x-sKphct;aFq64&EULSn;`JFFhQk8-`55$e@QP>bt5
zThD2PdQM76G@a#b_`cTl&PJ$rCP6K(-fR(o5sCmPA+cklx8Y+37iAcsD1!vGxE6C1
z-QD3NBO1F%h7uC}hWhK_V;>hS8KG#21hu%bvPEP@C?cbTM2}AX-t{q@i~5XE)JK9^
zTqoHgOCuCnQbJ<%z{z&aeJon>xyXn@7rm087FRuv-0}cF+jFi6nGzCrzv7>BA5*(1
z+z3VCBmyn0VeGzJdhcZ;6zNBhkQm!%iq*r94cutL2#qF4P>U-PyYJz~PBKCx7D`Aw
zRLQsPevIQrMMfOqMnxp3#kGHJ<Yk0LUX+k1_~ss~helyh^vY%PtdFX8Ps@OyR-FCx
z>mk2#Sv?~bjPPH*sFjf<pU{}o%@#2m^{jW!C*lmPv^Y*QuZ)mal#t-q(7i=I``Us>
zI<!t*SHD$Op6E-UN476>YhC$oiXNP?JY5{@&9Soa+JalEwoY}c*D_0q&YQm8(OxM$
zQWUkj=FmbBXANy0*dW0@G@|J8_H7E~)eHY_5)jnVwUM`D4tl|ztKVMeZ#IUf8fB@a
z>o2dguS`hHX?U{{o!&noO9=_?q2bmx+;*RNHRx~01q8KpSIVn)-!64tRl9zn**JJe
zoh-F<=gTYY{}B>5^;>SlYeQ>f0||&=4~?km4QtG+m2Vss5Y*E1D6f86__XutrPDq#
z8|Q92EK4mt^YTjje}qJ*w%;3(z4^c_B_z0qMid>^dY5_i`S^VTf?8^c<kc^O7CEn)
z4%#=RyX5Gne=Vk#T042A{XatD{Syv0VxKd<E~bP8_t0?jJo;Bk&2{(H@cljr2x_Sf
zmRGyF&v#yJKc}kMc<s-x6;n&?yu8x>A0g57xnqp@&(F^lQ$m7!Xt*zzM;@Ef-9G7!
zM*@Oc>V4$ZemBi_UNzr(yxAB!U}`b7)WgXu?f(%H*R4F!h^JSLDW-%3_t1!<i?%ef
zb2Z}CvjT!z>UZVUK?RDIu3OPGb+fyI*N$vdOfB{8@=E)Egv8@tG&ipv8oF;WB_z0q
zMiiadr=@w-Z`lhgNl;4>hrGITsb(A&-Pp=(-0)b>mDJ+S7a>vnLo2Jts9)=?po9eX
z&~P^9wX!R?X7Y{>B&elWOI{sz%y{Qj$HTl=hc%i~KrQZk5fbOFYGL)5eCd_~N=R@I
z4Y!*|aWnJkoc`4cNl;5sro7tGPcw42jcj5zc6Lb@QcIDnuAuh+2#Jwbxiy5`HNS88
zkU~mGa1V_rn(#^k^J?@vw+95Z6kp4$@|`pn;Hx+5nT;P`m{CYA?tBpvU$(4m#PVoy
zAtfZZhlX3@cSm)*ulh`184%Rc$U<Hn-&-@ihyUeBv(aPA`a)`P=Zlc|?BYX>__ojH
zLP|(*4-GeVUS7ex`r)e|1A<x_Q^~7E-)hB^yEjH=qsmeLDWn#6z6gnF-~DWD`*C&l
zPf<dGduT+_eGNaiwtdnQhXe$*G@6uG_x11Pyt=*OJ7%Nz?#d}@ap#MW7+Pgjq1uvz
zmRCzrLV|l}xEazHEGbmmKJSB?0YNQ|qvchb?OmN$)6RLwyt?;!m)XXy9o+dMBsMLc
zWJJ>+>Zd3n!96sh=(Qh4*tzO5x?w<2OBn=tRqu<A&a2~UpJq13XWf?r*tLVZQiMe3
z8|oUd>#SxeN=R^jizxbH<n{vV2V1rX2x=*JBCj6ltyr|?ZSx9rJ-&RsWr`9K%GIcq
z@Ou_7e5;<tiH#m>6%f>lqf8&~E_`cV2el<1Y~K4_xFq?6Z1|Yk5i3d~blg}=d8WPf
za9*txA+M;V>{sl2NVu9C@rA27B_y~<vYp+P@!2IoEoIpDUUPQ^i*<H&1*xUHpS;qZ
zFCpRXl48|EcL^mVxJR<xiN%UCbSILamU4^o%0D0OZZ{jc+o`3Dr@YesI3eMlC?oVl
zQ9^=yBu7#03znEydTL2fOIcNU<=Yb1GT6CN%RnvVdgYb&5(){|`j}U0eJCNpJ(8`3
zGq2Rbk)W3H$@0p#yZ3(gv)NE9N-gEA<(2kb3JKRzXLSYDQd2^Ldn8+Lkku9Z(e(x-
zsHIH0yz+gN>v7D6dK_vgzb~(}M^#9S_{)(-s8^$e1oudGYxnG^ZeE@1dQKA5(mMos
z<@<BjJDZJVu6L%E-fYM#?dKH|E&?#(UoHZmgar3UwkX5AQj|f0T6%jTuYBy|A{n!x
zNQPQ^rz5Wv`-FsxmW=q#MN5>B;2y~qk(pPD$VgC2?~UY@j}u+gXEqe|QA_Wp<dyb`
z3kerl8llLN5)#}a+1Z-c%DhtaN`hK?V<xYBOzk4%tlBF@$kgJ_#v$RNaPvx0I3*;w
zM{*RM(Wj+()!#+>B&el#h4RXeKNfw_+`O9YMibQH&c-3(Ml42X#6k%P?vZSxqO96>
zjfzN6OK(Z#l^?6Qk(b$c%8k6J#hr~q!j10iTxoPi2?_3zY$HfJR~kW*pqAbb%PT*w
zZT8$TW@EP-rBaJK8;67&2^*o2FeN0oM{*RM)W4E>HNuUyNl;5~#^sgI0k{#p+1S^O
z=&8k>jYGm^4UDMnvIdlp;2z1AnXtB9nF$iq(l-I}%I8a5_QTqCWk0CJosC0c#c3ZI
z(Z^+2C?UZ;lHF?4H>@$Ql*J)IEqx6kuY7K4T)*Yk4=PhcE$(a_5-uBMUMU+z2?_3z
zY#A@}N*ON_)Y5k#^2+Do9&UKE*-%!ETHM(<B>w$Ee<PH+ql5(aNOr4uv~OcxDLY7l
zTFP?DE9EjR18Fvtfut69HVz4w<+P|zSx!nwaF1lmq^?x&tV}8iYQ^!cvZ_&p=rv18
zKB0Eruak-hIUwRlR$9!-hWXu}ch^blSlVNGYewsK`SYVMXjS%JF~3XV`e`+cR(_Xs
znBS#@#3yH0G1~8>%=|71YVDkSfO(b7?^3JXk(KPY%I}5*^ShLgs9E<Aqy0|G%<qz*
z*3uz6Y=(3)ze}yCSp_?;^1C6y{B9rt@%EB^jP^SzGrvoMT1T|~*t|;Scd2#iC4Z!J
z{gvMh3FdbxAyNL$?MC~Zl$qZpL9IKxzGhw}^Sjh~`LA2;xXSN_1oOL;km%j<E2I5R
z%FOSQpw{wM&zV=r{4TZrxo)!^SNYwLV1Abp5^sOE$!NcmGV{A6sI~OAN6o8bewSLy
zD!gyURem=lnBS#@#GZ{CjP^SzGrvoMS{>)iHm{QTU23HkziG!+em5kT-=%~^w;t<_
z_B$yvze|Ez->sTqUM2Ip)H>t4wRT+X?;H}$?@~gd)5YtI_B$yvze|Ez$5)(bUM2Ip
z)N1;^Kd$2TkYIk75)zAQzhz$eos^m1B|)ugubFFJCG)$~syWQx85-k+1oOL;kVswY
z?@GUuGV{A6s5Srf#pYEqze}xQH~FVX<H3+%ewPvw!&+>ybLDqZW_~vypw(&l3iB$N
z-{rA}eg37t25#&e63p*XLSn#SKN#(IQf7Xa1hsxy_m+8;%<od`{Pw<eR-PdwnBS#@
z#1&8ap26>=%=|71YJGV1H|A9`ze}yvQ+!XRoJ>eCze@>;fAsXdsNYGM`CSs!y7)$|
zsv767nBS$=n+N({U-_$$V1Abp5??j&5r^MNnfYB3)Ou*cVdhmbze}w@I{OGoxxSEK
zewPvw*Uj<KncwA@`CSs!YOqc_(3F<nrG&&!JAM3^%<qz*RvcL-^ShMf6N*ui`CSq!
z$6E9EG)6s`-=)?^@0?_Wd=ClccPSxpPUGfA=gw{}ze|EzC++HhYtH;GwbtL>#*V9N
z9umy&QbOX(`R$F)-HA3TQht{NwJtkd-{;5A2lKns`eRkvj;rS*B$(f&ghaWb&PMyE
zmib*0)Y^QH-dvTI-=$WCg467{YD+?b`CUp#9C6+0M(0{MJ6HAw3)ZRi<{-W0D=oiE
zt=dobw&SYZ4GHFVDIrm#b04E~y@BORl;0&mtrJIFX<jAsyVR=k(fM{<<#$7Z`CUp#
zOkdj1Xy0=(ze|EzzYWov(WT{gsa19IMRr{E=OMxTE+r%y-ZQ}HT$EwwO8H$9)S6oP
zdh;ro-=$Xj2QIPWD)tEp=65L}@#~6#M&}|j^Gf+$64YwbMQ_?m%kNU_na>8<aTO<q
z1oOL;ka+x<!A9qzSMy5wT@utf`+M(IGQUf$dFT4$Dy9wz=65L}ar{DGCm-oEze|Ez
z4R_yQ=PH@srPiWf{WZ||BP5vLrG&&A7y0X-8x`g9yCkT!?T*prRWiRztsnm3?^li0
zLW22SN=OVm*FP({5u{x~<#$O?YxuKQnODjDF10p&>7Q+lYeRzhT}nti@`P_!{Aio`
zT@uvV_wixoRWiRzt)U}*JE$B$NHD)k35jmE`!+b2nXtB9`CSs!$}G|RuF~?m)M_x(
z_ZiBUgaq@ul#tk2!}nLYERK1l{4NP<ZL8MXyh`SGskLU7?_ZT$3JK<SDIu|Vk?-4c
z887on`CSs!dM9<Nd6mrXQftaGAB!jt7ZS|xQbOX#zxX)FX9t<zB|)uECu#<3Y584h
z^*Y(dZOU1O1oOL;kl481$BfFChWT9*)QV%&WPX>Dd_s|IGQUeAj%209oNPE}RKDx0
z;x4ycV71kk#QIuUXIg(R%Jg^j;G9uPRHvBGSywqZXOslBbdSl#aW4*VHaKUL5)!)K
zWFt9elmxZ(bjil4>xVcSoHI%Z2|a1Dk(@J1f?8@<WaF4KhdUdbGfD{wwK1}hoHI&-
zT53^c<AQ@nIUAfaN(l+IuCkGwGfIM5>Puv!|EERH2Iq`YLPGtDY$WH5lAxA)QQ7$Z
zQ0+ayIir-2P>(7b$vLAWsHONpHfoR5y62oTN(l+Y60(t;GfIM5ikxKQoKL1Y8=Nyr
z2?<3}vXPuKN`hL78D+!IE8?6{N=PVvl#S$^Q4-Wrv@9E&Tg`O!;G9uPNGNiajpUqB
z64cT-K{gJ0caF2cIir-2(3n9sl5<8$P)j2u*{JmOJZFP*Mkyho(UNQ==Zun|md1v%
zvAvgOvU1KSB_uSml#S$^Q4-YBs8}}c-=X~nIcJm-5*i`PMsm(532G@HARD7rKjCa}
z&L|}$lpBzZ<eX6w)KVryHvD`}&KaeIgt8*Ck(@J1f?CP}?X}@%ndat<QbIyGr@b~f
zXOslBlrP(Rt~h6u5)#Ut?LAkVGfIM5$`s0mzvgb%ugxpcoKZ?hC~GJi$vLAWsHGgK
zZ1{WE&0aPenlnlX3FS*=BROZ31hteMmJR<5a?U6vB$O$ZjpUqB64X*&TsC}L!a1Xq
zkWh|XHj;BjNl;5~1Z2aviJUV^2?@O&kd5S=Q4-YByAat(&KaeIgx-tDMsm(532Nyr
zkZkxq%B@mhvjH_{loAqpBP1KiIin<~rT1U5;rm**+Jf28oKZ?h=v|m>B<GBhpqAeJ
z$%c;^+^P{~LvuzcA)&W`vXPuKN`hK?=P4UL_TijSN=WGar)(tWjFO<1-uB9dkKx=Z
z9##*{8Ks1T-u%i&a?U6TYUw?<Z1`Bztwv%tG-s3&5_;z?8_7ANB&ek~{IcO=YR(y@
zgoNJq%SLj}D2YJJecK=#eryoT8HI#|zH^X`Qs#_;pq9SskPSb^;ha%QNaza>*+|YA
zB|$BH&mtQdUxjl<DIuY6TVx|SXOslBG}4oe<eX7T@(J1S?^xU{)7+d<5-P`994Cfz
zMkyh|v0-Gtm+m|+dqa&=Q{07*`|HIk9{GLygv5k)PST#f+*Mb*-*PAI&;|)=X$L3m
zK<xJurVUC+#Ov=Sy&^#^?qwW$RodQ}+T-$p-z(X!?0%<ldPRx$yVIVW+!fRBgjp7$
zUHG)arnJgFyOfa7K7rah)9-{y8ziWu-3zr7rr+0+1a|<_e$w$y+B|R4-+Rp|A;I0K
z|2q-ye_i(V(4K1XUg6wfxAEvknGdJ^)PCE*C>`2h4YePn_T<#Am^>pPK?w=&cUd+;
zEj~9PL4R3~88c3FUo^UP*xiF35|oh8Zh7%e>SYtu+W*D+Wt=NYNc7!YFY`g;pE^{!
zS8v|+i=T5!NO0HSvI%O9IrP{}(em31223cQ4hc#~Xs5s2e$s}-UXh?y^PaUb>+k)s
z;P%Y^c{V5^(ROx?%+zbz7H(R8U>-pU3GPfB)`JAK>hE7Y^ZN6*7GC*%#XK97kkH<c
zd-ti9mAK|4s5N*}l}y94mKIihvvQsdN=R@oV_Dd1g9NqM@`VH?B(zKA-o43bg9NqM
z9)~vgM16Qx)7<^a79%7mA+h|p7G>OtB&ZeaQ*K7$>p=;La$mP9<4z<IXknl7upZjc
zQM<2eUu_b<O*^@adzS>YxU+d^gAx)I8@DUt-X%dT?fR#k?frh+vJ#&wN=U3**rAMj
zmjt!An|)XhN=Pt%D4U>`_Ec=U<k^(pp_}!fgoJi_Y;eHKDaAqF#s^FLXI&{9_qEFW
z$MKcQ+($DcC?OH=M(p=278BdxK9k(nvTTA967imzen(H*AVDp98`gunM#j4wYcJ$@
zH)6kMF>R3Gj<?)RGPFSn3GT34HbJd$mr8m?-{~RGNN9r+65Ok^Y=T<6vLV5<81KET
z9hzw`Bq$*f?k6lJzOP77i)T8t5$rl!vdgV@qg5{&@5vhyJny_7+{-p3C?Ua}o69Ds
rRkl}(cjDcXxxcS^iM@Lk%SwE%SaTk?Y=ROJ-0?W92MKD?+bH^f#@NH;

literal 0
HcmV?d00001

diff --git a/hardware_designs/Load_PM_20mmBox_v01.STL b/hardware_designs/Load_PM_20mmBox_v01.STL
new file mode 100644
index 0000000000000000000000000000000000000000..373d1557e6b125a1d25692f0210d8151240e745e
GIT binary patch
literal 64484
zcmbuI2e=j0_4c<|02>55N)ZIF1x2yTJ#)w2jlCeYC@6mw6k9|EHP#RX6%|`<Vk|M1
z*rF!fGqGVbCb7kuC`Jt`*rP&>`mJ}Zv+jQP%(?3GeD`^DhO^dh*4{IF_FikZnK=HK
zqmLN4%lN~NIOK=pk3R0iT@RZ$ap3>QUysE@So4%0XWiaBvL58`h*M`~um5R!{?yhJ
z+ul0k+HCz_Uz#uZ(D9w;A++Zq+_>C3Bky^8aslF-ZB}SI<;Pd&U;lpXwh#uk9dyan
zqA{>-!o`EzMxJwZj$;UIA0M9WGk?C?nBViJ>?a3YE?VumpD*#{F>QZe^xo|0cW3DD
zA-r<NA=#SuEL4IeOuTgFZP~b?GxAISc(mAf@a~D(M}NIm2~Rt0_&M_7wB=*mp~q)C
zPrtR2Dki@EZF_drPcF;Pym`FX=(F}Q*-F<wRv}o+Z6Hq}?77G3+0T|8rbM&5i<B&L
z)0NrQZ%@m=SocIBPB{LIY~1MHO0dLJ#f0T!kt-)>Esu=t2=d2-pF?ZQC9ljvn3m5u
z4K_lUBLA{KmN0?yj=q;Po=3w*E0{9jT25F#&OhkPY{&iQD!~#zN2+i~R^RkuEpMIo
zss<Y@VFGvI>3x6JNL8ckRtVPeb3FeL9)0?x?5h7>tOQH^9I3+796M=h<C&wB>@xjU
zC0N1)p82Gke%eS?qm)z#*79>JCFgV>JM#2}ll7V4jk@r>bM;!U%^2La+(bJ+|FXet
zADwb;j$;VF-f&Ddu-hE9!PoM0<OA==6)#`Zct09%loBjq0&m*-D_+#d#{)muKf7b+
zo|-BqSj*3s`}#;p)p57%oK0A5RV7&B=SbCW7n_|;xa)$3jjb-+Dw}-N&<ep?etz>;
z2Z@c2bJoia-epTASmNif@sIOg&CWji{DzGqt{a@K_trKQg0=j7*^zsSjlUeQboTDb
z`zpZ_KZlL4Kln83d+B)%8~qo4Q+w{d(G`NV{Cskc?Zn2ZyF699XVy3+SmNifvF6s@
z+Xm0I=O4oE2i{e?W$1(o!CHR);;hZY#^jzS*8cGGQ<Y$epTh>1w-D~$YRlRycTB1f
ztmWrc=MVaDTI-#o(y|MQYr#fZcHg>T?#QR!t`e!%z_wpaK+XqBK7L-@P=EJlCupkn
zeQJZYAKq^F<blaq+vOwd8T{t(tnK=d=jAwt@Xz@(>ia)_q7p2@eZd{Yk*^fOpam1_
zPqo{<VhI!T{;)yY3%@%z$1#L!p6Op-@bA+rsbVdDgG2bdcencR_s>v*B~0Mn;r+L}
zJL-?qI#xNz?iCZPmEO10L;qsTF*~Y_fjjTg)~%bp2YWxgU)!yH?7e&S+Wp!Vu5v++
zV+e0-zH;%<v%4z661)p|i*V#CNjtdj(#5D%?fqa06Wb5krES+G&(CoT;fzB+t)IKa
zVU<*|7C+4p`kwXg`jb~2p#)2qz?+13(B7!+wt1>Pscvr+6RgE$A%y<R?_a#Tz1481
z|NgMHyGLKB?=w6K)SM{0er{gI#;fdIoO56=O%+Q}|Doo@k*_3v$&EV~Uk|W4ktIyL
zcE(|CPygt`97oCdW39zMpIt|7Fu_{<G(+h3>}JI~gEmltB}}09M7?XZ=&4iIE5_|^
zwI~y;#bqIcmQ#OR%zWlZZ9m`*p@qc#fv<=*oX_!F2nTeWQf#~ESxUGTj%bO|hU3Ur
z3Srb;6N`y2UR$xzj4+SvsdbJiUb*bC3gOqq(Vr7i7{a#O9bG*5*0V~mgbB3DXwR*6
zUjM_xi>>}Mze2E<UkS$$-dS#P@%uY&SC0%ihEEOa@QmEkGf!-q{vN_(;!m&j$lO^$
z{#eqCF!@$jPA;CDG*<m9Cj1;nzw4IsMyixx2@|jff6jckXC|Cc^c~+@bIt^7`R_P(
zKJz;AfjbJ{8P@RxJ(_@~-w~<bzdo(F@S+`+U`aE=Y&23;A)LmM@0&gI2i|&C2|OW0
z4M-K9AYu_5Ikh2ld+oSlgO&#>`DjLf>@2$#!mo=X=P86nT~gp);XU8&mse=2P%|JB
z!jV%O!u_v}DkcnAR0)<eBdjDg%5Ej+PUFaV>a0uD25N?V-@j5*HTJQC+MeD1${a^d
zt<(%tw<`J`Ikb|GW(3I2I<Z3db#df8b+%DTpvC#>tE)6szh7q0wp&lSD#wvi8^ZJL
zgNr@i*rt+?W&}v_$gEDR5Pn@8IZq+1YHgGfXmS4UshOIpW8U7jZKES+<~VX{#X}CE
zxbmLSm3%ZKKz6pZ6~eEJBj>5p_fZ0#%$<88CU4KX-?UlV)LvKXky9JO9f#jlUv<cY
zN<NwqAVX-hwH3mzizDYLghn)>1V`?O4ZO7bxz$&VXhI2=_&G`ly#7meyRy-$HKK_M
z!CHQ9HX6}{5-jm^w1@Ee&phKQ^@AibwP>P3u$G^jjYc$~1WWuJUK70jxyR0IcruM>
zqC&8ipPP+FG@%4b{2V?Iy#9Zze6{+%ozX;vU@bp48;xi}36}UdJY{(Ou|KF0O;iZh
z@^iB>Z^`Mc6Glx|f+c<qzc=k$nlN|l$O#Lp1Z%-_o<G&zf)F;lZ(7HO2N}T<CN{le
z?Y2+HU7h0?!Vg#JR-ZTj3{4diti^9y2tPS!%lgf?Pf~&<%?QXl<BtmAG>-f}2KkG<
zIJkSGUpiFYbMwmVZo=P@UY0Rq<ofu%Ohk!kMhd$4?b`|0G8<Pt@zb^{f%apsL!QoX
zJ+yG$e>zLg{rXh`o;PX;Xuu<n1a$2$%{gM6KO8+*3B-fjP6=(GM~pZ}@_-1koR27J
z&zV4EdFzN}zk`Tc?K%2q28>&+3E`d|QsTak<=XFdIaMBQK`Z*|mX8sup4Q}fpl-MH
zw&!SlJm+Qy`7Yatl9WJ;YWMKlh^W<`$0u7R;yr24V=Vi9p9d2jt5@^EPcUkI+r0u|
zcd<QZB1Vwqd@vEU+Vl9F$^@5ic$r>~<6SQkQPQ3>0nZuzjn$kp5w+TL_|)h(trAg!
zk~gi<8yrhvm0%l8Aku4YgNdkRbqKDHzx1uO-|+wToC!phUFF=F_B?8}=ds2p+u%~N
z_3rgHs}0)oSYwolC~41`aLYKR`CuYywdd$<v6`<;L<!#?uI<VMmqd@9ao=LBRwklX
z)SgH0#h<y^P4i(-&@`Bceo5H|*HPa4fvd#SmWe2lI<e7T0wPA+-$q2O_B`H&GQoAN
zM|YgJ>Jwxs6YiIOI}x?o^LW?Gsfu?|`lma+u<!dkn27#W*#_q$YPk(7o6Vj%B<(p9
z@RpjlYG%WTsMVgwmZ+L4(~hM58{S8ApCL-DoI)RTd>_j;n21{J6O{?}mY9eo^xKH2
z<#*Ro+U)L{1`}PswRVq;h+2~K&hbIJ7x+JHnN=LovY9{Uzd?u3%lS!(fo)Z~OrZ8m
zwJfEu<bQq#T*Ab_HoNQ9RJk^eQyYGp|As3!CtSkB)J7@!F2bI9SN9D$Pwx+3x9faF
zEtG6Lb4z>IM3gXr-XiZ|^*f6r?rtPl3q3jBXPpx0AwV02lprqm5fi>rO0a|p#2`NQ
zk`inky*J*I&R0qamN0={79XeRnqV!?UrKO#dGv&BrvyuwK>X>WvRxCbg{T-_W>;m`
zO1JlyK+Ah{ssu~CH_Ej99cf<LP0ED#uvKmF^;pY$3af<o!$9KwB~i;$7Vp-SjJ3S?
z<J$?N?OIHDzec1@Gp&7C%X=xR1WUZ1A!;?t2d9b&?i+~tj<u*=E7kJr;~4+EZm$yF
z9}rV$R7$WGm$7J}oGPAWfpfGtRU2Fyyl30AzE3`w@ZS2W4ZdEg#r1s53347KO!&w~
zGaHd$Ev|#31>7r^Fadi${?#?XT3l<V1mAbeFM%f;)9!aTGHGdN0<$`NmQ~a*KXcaN
zw>c%aCc_&QXFbH0C?&WSWdd(-oR<+9<Re~-wNPWk*&<A^1Zj`+R^pYSzU4ehnBW;O
zT@zKU?|L3g@NA*74gA}##ajG6LSssS|A+9WHSqr!358%jmGyGL<3LG;PD-$Z3G;&*
zy@QF3)aQ(I$IPo~MzDlun?+ByS*pBmlC?OsUFU;|Bpyui!PjCfzK5v|+&zEq;O|<m
zk^SobZ$_Am3G<d4J&;MN{5m+YmfOYeWg93Z_QwQ2&6MCA#%Mb&F)6{<Vj@QR<y0}j
zT1g*SlJnS483IR*UFV#y75m}7Z$6la{eIt;57vskk!6A<vB&fKrizK!pIo-VcbBzd
zpLLmtJ&+-A4{g_XmnBTZzTUD8CRmG~Y}e(A-;ZypeYCgEY8fW1{M(z5+Td%k7S~EC
z!4f7cf6Z*9gw@(0xvorY@RN!?h2OW7FcEtV%g=*L32VjClQI!|qhy{&=h!B467!Vi
zgC$HPJzmLs&ID`4{<3naVo!4jvCrC5g=3lE`Xly6LC>CEm0$@IvG=QNg9+B+{B?b=
zn25c2&23nkS&N@jYJ=}$?6dTo+m%v+)5}EcFa5Suu~yfmol6||%5w=#Q^gV{V*h?Q
zRZOrJKd00NOPGkG4rLomuojol)CQN=I4a}M1IKT(!9*Md`Zj{KxXw3AMow*v35Nim
z(0m5S2ew&V>AH5DQbbSRR(4pAhY?oum5JEn5kl-Q`8ER9{aQ@KzM8TPCRhtznO}*S
zDFsWIh<#bCk9)-gYsJ2$G7;l`Swqv9SrK(&?c={qDPlYjLX1CLUOjsGG6@qg_DQLf
zV67Nal?hIJ>@RVxX8ACgNtlTJGfvylQ)L8eA%$oeQhhuRzE>=b5fc9jqAQ8%HOohp
zFs&GQm2L2w!zBh0jMYk2B1%#Mwwk3Xy%uXtZS?Oqvk~8ICaTv5i|4`Didtzc5$#MV
zQb{DDPI^`*SlU(X!*`eUyDqy-q*}3#;VU8MQNl#*rC@!#SCL>Xt}B_DQpDcV5Mtje
zbokjs2C0e?CSt#D)W+GAg5Mm}4Dbe`PWAbu?;sO+)2yc`@@B*SZP#Kgyf@Y}RVG*x
z`?6f?yHdr3uQ7Ahk7+(wtLwLx>u}s%8(jz?eIMNd?k-E1h~pGd8)qrOT5(*YOz^Xf
zJ+#n@Wr3NrlrRzddRgDfZoF1i>${!@6S2>_Y6HL6wOEVWM`orJv4@uDi2GHVrz++n
z_92H5d!yMxIp?g!?<O--3Vu?thxYrH5+-6_FIy;=l2j|^kD2tDGZA~BS-+ff*5bSF
zjJ-_@2X3x)$BF|oYLjGT*jXd=_gm*})mgU~kxKlDwdV)yHB2>o-@k2%DCVu8zdV2W
zCvB^r*Gtcr>ib2Tr-YAYgMVS-)tNn&?*G77opd!HZ!S?&t=*5^LXI(oepR;-B~0AX
z%X0kAf{pYlpsECG&FE)2Ugo{^N(85O>Yj_Kbe#c<c4~Qw*hc(~i8b!{rVWzMHtEqx
zd#WPAT5n8Spu~G$EmI<T-M+p4vhTdUa`d|p!tBrO_nCLEULsOSBqAMuvs5)F+Vi#h
znvGG%wv=q762D%1-u2z(d<@C9)9X#%arq=qesBC<`E^5JV%q&%D_y-;F^3ZUk=6$-
zZAw(12jBO5&-zrKfu+jR5|5s$_zM$rZv04TdrqcPC7Nk*s>?)s&cwt%W~2JdW18A?
z*1Gl2A8V?rPmu4)iMMa5_s2?myz72dPgRsKvBsE9l&-$#oHN#X?Z?BF;CjVuuq0o8
zZPh|e#8>J%RZJXx#9*Z#-_h<FsA@i%Y5Db;h`%v$#WkySX(JM>#kH$zSgQC*{r%C;
z+92gRitm8u!>`buGjZpfFO_aqCq{y``Yl{U^I>(c>6i_cbboyb)w0$nUdhj@sbXT0
zGnZDn+D18#9J1C;xAjq?+D5VDxYkuv>)vCmuClAel3GnwN(@x`n{OgrB_tLhEx)!O
ztK|xkNKAitXeEVi!>`evvsTmAIYZ7?`|{B?+@~4u9+EHd?%jGmboM@aeJde;MM;$s
zpj^VlMMHkohToSubf*U0j9{(So->uW{ma%8aqfqgtK_d|_Q;>;cfFoJe60HnF-1ZC
z%Bc#0iDOs#jnW5Ce_f9DS0z~M@{9i<n(g^DUpyg4`!j+i69@iHr0w}igYK6j{=O?!
zOkBO++if6TIO}FP+FvzQtX01QK2Ljo^@-QW(f*9MaOC20_hbg~^b_-?c0ldip7%X-
z{P%o<OdRy#%S!*`XGfKuhuK38+jG|9(qlUQJUG4YJh7CL_ilBWTpxemb+4FsaAUlW
z?fD-4E@@L({#U(Msg|YGwQ+PJN|@OGNxV_bZA5~#R@wyqVS66)<ThCHi<Vrq?5V{o
zdCID(Vq(PJyDHtRl*DVX*5l*%S0a{5PZhswPrfj{4QW5}O=~rAZvR=jJXQFYNtihN
z!HboC{77pLp;aZSTDVgDD-$6wao;0&*6sOY&sppMu1c^L*BEZa2)-xxZFack)ZXnh
z*K8w7nAq{eaY{F<OCrHqtA0E|iCA}eK3LLv!AYux+RpE|=b?G3m>AOkRHd5TtC*@(
z%YVnw{`~Gn2@|{BU^bdP^GLAP)ytovsfuOHbIy{(CQVc=YXRbwx=s}nTfTp+(#=|&
zcrDgC{ikD;h%KC_D&F_@{J*2nc3Ula@*@^SqIOMF#n(FF?9ob~73C|X1WTCMv&UXa
zHLG`HK3I!WnA+g<9(WOA^7j12U)!^Y_Km4N^OP8<^n!cv?7Je&FKN%CmZvx+@GqCd
z>)v=0JTgyVR|IQuYZt=&;|63e?X*L~FYy`JSLr+`8y~t#uJ6CYesiKdA<*M(G>As3
z3LK-vuIo19?_Cp+Ol^!>F>QqVZ?KYT*?8UeBg_U9b{<oO>*KlmJ>lz?@0;AKLhi2S
zT%L1d2LDyG-T<`!4jau0o@vi?OqG>H^u5|>hF#as<L_M)kobB7rj3}AeYsCI1bHuO
z+1SnZBg_U9b{<oO>mx6IPx!i=bNqhtovYo9vWpVAh*0*Vrsg<Dxk8!3_5AmgU`d%^
z8hTc?Sj*2*4xrJTU`aE==##FPv?erRhqZ7X({47Z1UP$(Eayz{x#dA@-OSf5+l%>-
zySpaJE=nY{>`4u5!#T<o$`ow-?|OGT36_)zrlDtLm$m#H<p3JZ36?Y?j7E;F>`u{A
zV(*0IBc`3_5i;R6a4pzig3r^t>k>|tpWA(FyysHV@n@rY(0~-r0O$U@=`<rCVZzUi
zu>V`iT;kVt8~%IOgh^~1k7+0D={3_r>HB_!(@a>|bt`s6UgEvNc{v|u4>dxpcWo3I
z64VHI{-za2mpfZExjz1)gb6=49s9rK-X(rrx8c8cO_;<+l$my7N)hYbR10P7`w?z~
z2`iy)#g4eU@m}G)oDZ|NLHBuh&r$CRaTTpBlp0#fF3J>q5_^JpgHwVfDG}+IBAl_7
zo#WZVMppz&s)W%m|90dp4Lh0JFbU_$uGEZRNlL_=d+jE+TAJM}w-@sv_X@2V>RnBh
zJt?#@SLyRWnL^Iv?<v8Ol)%$8I_4T@tYzoc%A`9}K-1rKmQ)F&k>f_atEB|iO>z~b
zop;zs36`Wp%(<t??{1WEsyKhV|CR4^h0$*x;luiTKSz#3cy+n+9uPZ{2mHlddM`eH
zHQl8bM;^Nk;Ww8JYhC@Z@*XK6Fp-Y%zO&ohS+6&C1!fz3UEg5^R|(-4J3iTQesQLz
ziX}|&7_{uS^ico$^>a_J5Ul0rwkyWSFVC+Z^4F7<V2PjOe(+d&=U$T)g0=j7Tis`*
z?Sz->|9fPt5-jm^*x=Fr&fO3z1Z(-Z?aA@}UVVz+FT1A_Eb(*L;F%+`qnPajSs_@<
z&uy22<sKYSoVwd4O0dMwVIv(sZ|qc9Ay~`LZ5Nluj*Ck0xV)cZzYHf}ud7|s;@Ce3
z-zyCBTDsa@ECkka8<wiZ-iEqM8oxPyjyH<u9i;o*v6k=fhM6!a(b(HiZLp*nVY^>6
z_BN~#PD9J@o87C%-iAuBgbCm64KsQ|XudyO2(0B-vb{`rZ^LG_4^rau4s3o-W2eH7
zvc&Hj|Bmy{-4I9OoUi5Q_}%v)M9tT^<6>)B!UXKuN<C=t-iCZF*79@P@uaa+VGT4(
z{2agIX=05Lo_}X4QGz8*;Mv$pZ}7YWCKIgX=T=G@I~A%8miRfYil>RSK=#ae2TYbQ
zfoE>3$-(mum`t#ipIa$;Kz1q|KVVV02ll4=%x>4h?|2`v#>n1U-dU9;OyI4xmF3`h
zXH_Ox%g^mSZ?>~4B(8<4qPFuHVv<Iy6Ez>M1%kEw+-gzYf0reG4jZVoZACu*)u`Lm
zhHK$ktmWs{8Z_HY7ZTUPRnhv`N`L&T(MG8a*8;&>er~NA@43tpKgU(kirRhv_*bK?
zRU58_Yq6G}TkG6x2W3cH3s;3VfVEOM58(#$8PtYrfnY885|5sKZf;%%?}5#;)p`D=
zpW_(9x#t|RnR{jMWPBfLzV0c<tfsrM<0$(&uRM0vq{ja3EMbCE7{X0|9@hHhqqeUz
z6RhQ_#W92#?@nu-RoZ78l4gY5DEa%W=wG{auI*3F*Yb1dEVs?Fx}!CYvM1oI{c64Q
z)Aa7Lgo*TC@lNSHJC^6x`Z<mvEVB6$+0$Pgpf*@?>>uW4*e@DKzLNNf`+r*d)kxbr
znkCH$$eZu2j@&wpqvr#^hp^P#dTr1}$7-rr!o*(J1>IpBN7?oC{u^rhU1EEZGr?N^
zJC5n@_&hfs^`EU?j_U%fPCQ`P_Sq884b)V*7LM6s9U1nE#*wcS!paY~X6wCRdq=aR
z83B3o{q%81oW{|g6MhfjzpJm6^<KA4Q^gV{cAEWkh8@On3}NB_`eiNSZBKG0Sj&IM
zQR;U4nuoS(XtmIK!8Y1ew6A<_Z7qMN!L@KiE9q-~_)48$^QhQpMp(<)_>M`1@ay8}
z&j~5){EmqdEMWpIrnirs`=sjKWrDT*cN{yvn^A{7<k;tC!)x(XNj$eYgvPfy)FWd_
zGs66<X5ScrJ*RQx+1TpCWxk^|OPUcTmp!mSsMp7YpW_G`tG;1d>Jt0%iF$o3X+}Wa
z`E?b29!&T-j$V4qM&k=EO0a|p+_$(&jK5041Z(;4IEK*tOEgknN!j(4VbJs^+xZ=n
z$}?|9m<|5U4`0jAapdRUS$5S1N}8`RKuPq~XDG*U^+4mRBucQP83B3cJ6Iu{#*y<R
zKDE?|-Jcs+;OU^o@%2OS%6uIhr#6HwKHEL}Z08k}U`aE=-YDLym<d0}k@M79C#nt9
zU|1oG6vB`5HPxJ2@yKS4$oARUqHUHiG3=z-8TQ=9v9oTk<earQPn~V85@^Y=niQ#m
z=jZFTIknP{wqKuY-KDLcfhA1*^sQGj?759&2n(!kR~t;Q7UxM~Bx!30Uv#VzXc@8I
z6{*@*d_`YD&Z!kY^R$<1D?MyIEG%JS&5i$)Vb5(GJADSV!31k@p5$Jg`DE)Gb?c4d
zUalwhSV4CJ#u0uH*7G8@A#C-h{<VD@y-_S-0={WnqulVXG*wKn7T=K&US9Nq+IoMn
z{wtO+@x=k%bzg5BLs-lFlFHp>ExvD>m4IFTB_ht6MZ%~R&|4d8IAf+{v!`viDSOE2
zmq^-^y>UZ;zbk&Pv^r5zCU{Q;SpzODg7hm&ix9nVrrE!?G)aGACjE-7sU+G1&HE^X
zApMD%^efiNglln>VK$^cF_T!QmP+`#yr(c2e7i>CsS4qH18}rtHl#l>lbEfRO8C0z
z9;Ont$k$aQF02r~g8)Z;W<&ZDGl@Mrqei?BxIa$doOcrl0pFF8__jj07DumUL;4dl
ziJ?2=Wz+=eb<<r>W%qjd@`=Rh6~b4Ra};hi@C6s?SJdmeALYFUsHI`gX(R9j7wK<E
zBusE`f)V(Fi}W`n1Z!1Og>R)uzoHWU=6Ju4zfta&nhks_MZTG$efLgq9}x1968Kh%
z^cblPmoVWyI%q-72ELUd{fY^ZYNfmBiYG4LN|7ETCH(F(!TmvI1K&!K9;1X{Exyx6
z$hT5jrC%|reUMwf3*L)oejONm`9%5^vs4lZ(7aY(>P7jw3Ovj*;ac36*_o;iPZf4N
zfXA0!w>{Z&S-#vezIWYgQ6}6A$Mg4dvw<(4NWWs|c#W3~*TU0;*JnN)7%3%nl#*1!
zDUo?hw0Cp}QcCJ5C1t|3@HGA0QiU&{NWWrd54M$`cwIbAczx!>fss;DM=41qk-&X(
zpV4ecDXF8BlnK{DDe-e7q(8Bce#Oo{Z-2L43-2R*RP*7$$a`MkJx?W^65f*@guLek
z-t#iyo+aLMKZm~7R|V>;RKnLycS@Ju2^nKSomeK^Ped*1=Vn9d-2(M)D&gz4=kCuL
zfw3ag?PbEX&>Hx;5z>AXXg^X3Uzhib2ZJ#$v{7ZkeK@pTer`6T9W2lerV_qxx{q)O
z7`sDTTPED6LL2PoW<$QnR!G01wzW~h*Ol*%((c9*4a*p$^eeWe*NR&34Dc;e>raFg
z`KDeW{fZK`q`M~j&MoEdG=Qm&zVdbb97kw}FkZfCaliukwnf7_j(%<_i77N<Ng1!*
z_`YEsu7x8~=(*)@PZ)89d}-s5|4!>jC6P$;2L}GG_`UTq;k(@UJ;c#$NPl7>es4XM
z#QRpgSMue>Li!a8SdaVP#9hqOuie0k^d}b5uUN3eOC^r!l|V>;Vj=yC`UKqu6X~~W
zK*+Zm3;D`QLZn)}uQv$kPb{QgQ3)>@On8~b5&9uWe_|p1iV4A5)q5ph+brZeIeM?+
z9!s)2dgJ?1UXS6ZCW7=Q77{}jEb*EMN8GD;B{0&TSV+HOVuOkFn@Aw!`<#V*StlV<
zt@t#dAA<BJ7SgY%gzqlJgx6y@DiEYUv5<bngkUW$3r67Uz|ya%MBM)<ew)MFM;wii
z@4nWhZ>C_0x0X2KUd1bc!PkN1`>%-&CcL%75&9wEyU5b7m=LK}e40k!yU6l2S0(&8
zGvO^Kjz-8=Tnp*bNC?*AvS5V$A9Ysz#(;ZHb}a8njxP{Pf1DD&KNJ)0U*Tw1$5)Q!
zYsU$ZYQ<+`1iqv!{c%dbE5dVO!u=~8jlh?!rROUlSc{)*r;VE1@ZBOoz!$aa#yesJ
zzH%%*s%is$lSmO0__zOVgxsrEzgI3{ExvC?$aku1D2aF;=nKd5M!AC5?<LVwYXrV>
zEMGfT!X-=~=l;79a<6KBuUx`foF^lsB-Xqn`fiaZSBMj=^u^Q~F;Ko)EWLzDKA1qh
zJby;W8&&f+$|bDDc``zJ2Q$=gxL3X-C4UJMzk6zpklw*edI^<q2@`lf{C6YpU1Wcw
zT*6wMCnGRo;x(M_XPJIsGp5!E=^f0ZmoUi(6a1}CBQWygHMQrQwKz{kU?dJLC+>;w
zlgVFL#qXY4BcyjQlU_n4T*3r@1J($P{75fhLa-L+$q4Bk%%qo4+d<!pGyQUFOsx^p
zJD5o?p%R`CCiok$MqotIJpd<Ii}PeeNBzvK&xJB)?XvhKZvGB0?p4}<h0#|Th1FEK
zgbDucui3!pE4(GXR;tC{E&?OHgPHUaCijX7{(iC9z^JA45+(#|@qIJGYX(H8UJoK7
z^;!a2d@l22B+{1eJkRoxW8|89@p#PJY)Cs;vvx4<ZjAWS-+5^Hn`T6;eWHX3#D}pa
z0wW$k%{+jZ-f}+JUI?+?jj3V+k#VepVI$U8kzg%OA@oC#R!v(RzPtF{@2HP7p@qQj
zGF~*gcMUCPS>gnAyj{V$j8->VoHF5BK4NAq4+xCJ;j6S|i4)L4-$_EChowTe7Hqp`
zV6^)TRY|;VN=RGVfws0xxEAgq`cAB+h86c2$`U7_<GuvW<=d|fpP@{+7M{PK8zF6N
z9c^t{;#zqA=wY#z8jO3EWr-8eY3^B;3D-io@^jE3;H!w^=Z>9)bC1t(?(raxa^QD)
zKfBGTqjfG{%dhKWUe>mQa9^}6aRNH-qvBk?HQMk+%Y<wB7#mts1%k&oWr-8eN+XuZ
zM-46HTcAama4jEiL)&OJJYp$JoPd_cB}T0G);5KF3$$}5Houl@`B)fQIwL%;ElZq$
zmdBz-Ja^ydLcRrBFB7iiBU@;<jPNM6EO7!_9*Y`r%g_nM?g!pgFB7iiqfTfcjPTx%
zvcw5!ae0%G<U1x6@-5JMnQ$#13$s=NJiY-c-vaF@OPr{d-Fu|wxpBF7w8d$z73aOf
zf{w~)ZxqgBPf-ZoXH^{~+yC(si+|3aQDX^@tCg=L?O^+<#h?WfYb;@c$MK*e<Ef4Q
zE1Y|(%3A&gLnj1$nRJg;x~UD9Fu~)IM&RqG@)cB_H{k?pRqw9%K!WFfL+__dM|h$2
z(6hT1Z*0DD#u6SAE?-IJzOK4&(P!VKGnO!sj@LrV`z)C#Yx&cJj*J^zaYWJgtbgmh
zatRYWK5WFK`nW>AcAOBb#bv<=8ILM#JSqh4EB1bBulaB^!uzRN;&m5}(Bdn_erlF5
zk<J5vmW-=uKQ$9&Eq|KOkvY|aHYoZ%yO~;d2@^c;z=(0XZ&}D!v=f50xGWeUqhxg(
zC6l=aG-~1FAKnJzXoQb{u*BP49HGTmisK(FVZvKf9L<J|lGSaLEMBXu<xkTHAOFC=
zT*8F6s5lzo;~z}07MBGhe3T6T@{uw3=WsMF|GFps)$rjG2@~$yCF5!x7+2$Km9_lY
zn2w}MN6GLnmoVX;T1=sjk}<(r{AA6BkBs79KF*0J2!Gd~x!(~ZWL&L=aW(wQB}~AE
z|89iOfM9~P_`VtOK<CJ42tG23Cx{5bpR=dd2pLzaVO$OWatRYCG5)&|afCM#ti^dU
zB93i`;G^EC84x>pUE--VVuH-mzhB1H@GqAzfs*LI8xco%Bf(mnCnKaT$-FM{*#hvj
z&`W_Mv^=#&^gVKD)-rXgM8X8mXf+~^(Z_4C7U#(bX`?c<QTUh7dVsHmehnP)yQdcC
zGS~8rZL;Uv2PYCHct)!cQYU6!C;GKmi}PfJv{BirjW)_>h`>8TF9nX!^3)n}<vpXb
z<3dOzOz=!;Bc!d(ysh<Xu@>ja2=RR~_&)fT&y9gUhyEEH@w=xM=dxOF$b{^U!|zhU
zB~0*4X(Obq&AhF3g0(nLMtDD*mp()${+vC6NP7(=n#gR#B=#CG;m^bU`4A+U$Pi7y
zqF<}5<-Ki|Dv2gC8~+ebR!TUo#f0D87#m15ks+D@??hS4d)v&0L=%~fl7-+BCj4H-
z*g&F*4ABI5C(2sh6J|Cfn#gR-OXfC6>BF^{@TVDL1BoUwL=)hhC~J9-p4pISBD1m7
z5M07U+Jgi}qKORA1kRl(Yk6-Qbi|LAbrXX=oF+5RLU0Ka)!wMnWi`jS-7R)@qO8SV
z@Cjj+gC=LA|7bq7OPFwbI3gV(41fQO?6cnHw>weR@;A+ho|5ye_uf+9D3>t7Yc`CK
z_#^Z9!wJ^%JB?!qx3534zROE5)h<}!N5xtHS|cAbX1o0BpJzGm2z2+&Yw7QspN$=M
zuNyN?i6aj?v|tGnyc?0MuifL9O3Z3KAR$=mKO3&6Hhy&bNU?G9-VfAwl~ir=*S!mt
zFp=(sbX>>3>bnUsX1ARZg0;FGy`kDTZQU)z#?--IsEyTX+Y~Heg7;nuVgLEd7D&|^
zzt|)pSZn6+P1MFY%Wf(*URiEsB~D&`{emS-@QzR+95!$*C3@V}KOtDF=fus`#)f0C
zTl3h(H&9}mr&lOg!UXSGCF_btXG%Qtb+?3It=X%MR2!3aTwiR|pWar9t@?aYX9*L$
z-<Hh7>Ay#Ta<$gvKP3cfJ=?FQHhMmT{aO1j+(&Jk@Z#NdmN3D)fQ9hO1*6r*^}C*z
z5UjQ4xJ+%_xe|8zyQJS?YGd&i53aL>3ErnHgcq+rQi-wi7fA@#`f8!sn7ui6P~POr
zF-j~p^~MgCFu^;f$!zsE$7(*#nKN=E6Rh>=6K3O_y|Gj5oa4r-jr%`1rj;d3@IG$R
zial_I62Ht>sWHJ?YrksGW4m)#5*sg_bhxJK!<V<Ov4jcUk51;u3_nP1Jbm%>gkY^L
zN3`nmc=sLb0QUK?{nf^lw{EVngbCg;PgZSB*-eQt%RQG6thK^Fwon@@U$d;(`1kWW
zXsWK8KexsbCV20@5Vl#cr4kQ5+dX4~wH|$QQ?+sPeM^ds*|RrN;=-+dkg<db-ce9u
z%pOBDAAg)bC?QyDm4h}?8=vpqU2MENX*IPmWX*LlmN3D49?FWtEtXWGW#cUpg0;3j
zaJbqSdnWcNU+%o1#G^g(j3rF)zLV0n9{iHlqOAjWO$gT7{quFy#=rOICN}!?eME`A
zN9>uggbCgaQ)bU?e5DeTMvh7d*1CMBHPy!HF9xx($BZdTgl7)USi%JF*BQb(-G(T!
z>BdJS1Z%A{agf?ra%I?9bfftlXbs+7Y)r-yCV1yian@hyn1wp=>gUHM1Z%xJwIA6K
zVx$u+VS@KF)l{{5s+eG{WA0m-?v>=c1_C)}2@||8tKMBDaCeztt-E?IuQu$N%M(-r
zPmm={@XoOzEZ_GLB~VJ3V69m<_EH;GcBLdLfs)7)CU|FEE$ta{j?&HqYt6l3DYaqm
z;Eh`>nZe6gOWr7!Fv0u%>RYQe@YXWHS|eBMp*E~8xw6NQ49^@j1523T9f`H}Q5&dz
zm|(5<1~0BQtWJ~~P6^a-EMbE8M%G$X3DlxYu-0QwbyFKww@Xc}`9Mw05+-=ZW^E0W
zKx@DRYyEwVMbw71QPSdQs?g%Fgo$*ASZUSN23j>HSZnD`g4(dQR$5NAftHgcOz@7h
z+Bz$N)|m;`>b8X0FrPs@08JG<0G2Sp`{b&Zp*9v3FM|ozdU=M~FyH5;>yNbOA)X9N
znBe_>)mu^<@Rpcht@Zw8&%=B;@yOH$JTjIr!8;PG*QYk%^)bO(TfDibJ`eLn#j{i!
z@GM!v1n)Mk-m4P1c&|*b*5^}~P#fk`i-)YKf``l!CU_5Y^}>~a7tRE0jrm(oD_0sD
zh^MavJbjihk?ylC(S#DGNHoC&YkhUaGHSzO9En)8z8WGC3rm>beZ4g*(pnTz5fiMn
z^k06UHY`??$gAd&7fYDn-NrS#QyYlxm|(5l_FqwLSj;IAWDRv9B1o1nk?s&HQK}M%
zQkh__$^BMU8;Ex`5>^6{FiV)=9cg7}ik&-Jk*X1Qk4cDBYoOYY)t_SHhMilL`2E#b
z*%&2d0&{_EXI&vWV53Zcb}f$EHC0L=RjDKr9IIQef$x6t%=^}Ezjng%IkzRx4_Z$1
zaro&gie3AgqP>qSVS-zUt_jw<>~~hKzWDRXB^xYZf?J8y1{17x(LKF2A2WZrYRLvm
znBZ0-wZQ~y4O`u8%=)5V$p%Z9;8r5F!31mFwW!&6@pe2_`?Kf45+=Bn=$c@y4@a4e
zj}I>I_|6h0xRpq4Fu_^}uW8SG^Dl;!^1%`&xRpq4Fu_`b5ACDReA<ub>qA<0S;7Rj
z5~&R)SS$O=-j4y7qA$b#?0K*jw+vkqEMbD{{L}^$to64~R?wWkaKgH!RI!8!uJcnH
zOt9A24K12@?TcY08!Tah>-^LP6RdUeZ~AIJmRJ$JQTAtdmnBSao!>RVTC;by$ZLhi
z$~IWS1h*2Y4JJ}8uk-y23|{ZX)?j$voIv|wf0lD5;(1%X#l04#R`ZccJSA;;+Dfnu
zCRppDy@z!1JXpd6_Y|l3V1l(~{>38tYPn(w6Wmjr+F*jUhA*>r7w-paaqn=~1WTCU
ze%~}zOt97;yRECKs@5eeVS@X8QyWaM)<1qeOl?%_M3ykY{l2LUCRpp2FIk^{wQgq#
z6Ws5c+F*jUe(<aHH6PVBiX}{Nzi(=T3D(;Ee`cfF*0O{N?!`@QFu_{Sy=FG5J_Adb
z;9lI+1{17x(k^DB>ie*S3GVkzZ7{)F$L?s)yz0ZTgbD8VO>Hp2TI>GP-jAv;%39oW
z+cm)wCb$<jO%)TYwSFJ#<%H*)5-eeYdvUuaSnHP0TC}tuTemNofwI<sB}{NHZfb)G
z)*5={P_=RG|NWqp50)^&y|}3jCRnR)4;yJ*=O?{OHdw+0_u{5Dm|(4gN3E{;cxc(O
z4VEy$y|}3jCRpp2zv|zG4VEy$eX^+yCRpp=Us#k{y;m$@g8O7s8%(g)D@U!;#WQCK
z6Wk}8+F*jU_Fr-(wNWj*EMbECWK$bVuog$JDZvsZxKFlgg0(ot4FPlEz+sQv=!FeW
zyfBoWZ@$U$>|=PAn9T@6c62D%_dz*^*54<spU^VKB0ENaz;3kckufpru0cv)_&eCZ
zd^-@>@s<hJN>e2>+myggvFt734MwVtxO}~wQ!BgU%Z?GSf!%0X!bJP-LzM2<1F6EU
z6d<tUEfcK8d9vLcKwzg>_Lfk0Ayt><!*Wio%%qVWBS6UPwj>`+jGeuv(*Ju85esHz
zg20Zqd@a`EJlQN+5Hh>1VE+pBJW{p#&(_H~wemcU9IC03*=<Qan3%Wd+Dacd7O@(3
zrGO3Wc+1yfEzXn8z6K$)+Y0u`&|V=`*PXLg&Z*UzZE8biw<Y;t;`T2rPlsH9xE8a0
zVMAuOB?N16o^19t2$|hhXCDr2J5tqiqcw9*Z3r^6O>M~Rwj>`+?0VTSrJo;#h#s@Z
zVMAuOB?N16o@6G6%<2arv)k(I^}(w_s>a^AM$W0#nQcnQ?6xEyOnm&L<>~&9(U*Z)
z<gg*L+Y*AcI8Qn|NC}xCRA)aC{v1-Zb&o+gr#1wc9i)WJ5K8jF#II%;{r6Gm#lh+X
zq)KK8B?N16o<jKaQPgZ9JpaP5R`x8BLZoV~JqP5RTG{nfRw047b-~zKEMa2$`$li7
z{Z~uN>I4uUJT|R^3D)8~$?gHN#{>xMug1P8?hjJc>ldr#oLWguW8XIHk;@V$hCgle
zwF}X6_nXGvaMxb^WRi2%;yl^@4@edEmSyi1WeKTzyhq=hQ)~M_fWY3eEMelnnx$&q
z-srRRz2RPwed3s4EzXmy#*)1<U<3Q`viFMj4yhV{?MgYP*7nK(fqi&c!bICh%hR>b
zqPN!f>chT$Ot2Q`$@YJM4eTw;9y01Eq-xHwE99J7xks}90|@Lb%MvDbd&cONbJ0)j
z`x@#VhZHri7UxO!O>gWoi9ILTLq;8pRIUB9<#JA~?UjL4VIN+WFtMP!)uQK~f!M(J
zfW&@~Ot2Q`$=2M#hOE5L*r!H&g;Wjd(I@BB+L}8M*w>OJOdRpPwW2pYiD<(2%f#N9
zOt2Q`$yPMNhU`+1u@{cE9jRLQZtt8^YkOsYkk$Q3KA8Bybn`ft{W0PXtWN}ieMb3O
zti^e<)t?}+i!1x>@Pm-5d0X_(IkmR>69o24WeF39FJ|7^36~<8!0JyBvH~<ASc~%n
zUH_Ysv8NB85vf9r#;MiyyXskD$J<mAiGBx~XL)izqzWr#VFi2rGQnD$CtHUM0{4nz
z1N2||y-HJyoiE%5OPKiAjs2CjRAC)52;_r_R4eAmR$zlbx#DO7eZ5|;IJNpbY9R1D
zSi;10U#_aOJwdE*2Z3kK1Z#1g^c_?J?;yt?=(9$u@D6fnwd^W^vda=CJ~(a_rLDAM
zB{@=s_k#)6;yi_boi9M3zTy}Mz4b^H>MKsIzUNBdJ!c6M*YsIQX{#A9;~q9pmoULv
zoF}c@l|bFj<AWHdK&nu;b859tR04G(OPJ`sV0opj7G1Bg=Q-+KCRmH}r0t;EKs(6e
zgBa66s?ZK{YPJ1P0__J&n7C^_%agS@zUMji$Yp}HI8QR4y|D*9_Q>TCMT}-4Rqz=&
zwc6Hds?gT5go!^sVzjl+zL!4Qb0%1e^Q8Wj+JJw>V~`lfL#p6kacXT>3X~G;U&|6E
zZhFXQ^JIK4ee7S$1Z#1g)ECuM!58ImPMjlE@I^Vb>cc4kAC4tVJiWfr=Joma6W}K@
z!CIUro7In;!*AztPS8jd{B}-l2;%Q*s^IUkgo)$&7;PT1_|!_kr)Gk+I8PemD1jJ<
zM@Dg{kt)PEoLY?ylt6625++8CGuomFtWH4A5q~hjTAU}12bDlPh!ThO1{i}tsYI#}
z4{~ZXj#2_~6ib-swXx9_d0`b2QiWKJ3D)8~Y3!^7VrL#p#T$%NA$I1}YRstwVosJY
zanCVUuUM3d6<bIZ;#wwHi}R%Y3`(G%fk$6a+aXoxXW-Ooe69rIbCxi%R}Z5tqQ~ks
zqzZiiOt2Q`N&94!K%Wec*P>-Ws?aCHsnxy=CD50_5+;`apS4%k`+=2!NEP}^m|!i=
zlkHgx0{vG!CX7}TsY3r1r&jxYw5>(I4@;Psxw*CN)>GtPH^P^Wm|!i=llJwg4fOT#
zm@qsJqzZj~oLcQ8Qv!WtEMel1-<ls}y=qutikzb#jtSP{Jn0%?-5~@!x4=(CN~~|v
zy|Cf%y!G9b+D*>=8x0^*NhILg#VcXuGE!CU7iBHJBid)F`9Pl~OPJVZH}gxamlG>~
zVFUf5Ot2Q;w-9cAdT_@%D{Wk?d&@@I4u_#Xq$S_^vX9!>Lq`7ayX+m*2I7WUAYOcZ
zBPo$lQYMgdw3<qcY({`~t^2RXDh{))scQ99rIJXb-g3WlZ&2c`Cq`sUu-0*{tEi1D
zhJGyh=ot2t5<3hYk+Fmc+(V=g5t6J*IdRz<QnlAn8zcm4E&16BYGaFkd?GfsJ!4Sq
zY$5);*YJ!bOt60)!Wsj1QXA(N!xDnEZn_Q8X-oe4^#6#Bh4+tEVtlr4#u6s*79byp
zKV|jV+Gi`V^$RTt!CHIG=%qHc9sPyac;&XADzX0iLo=2z!5+D+sM_axB`&*fP(rZQ
zB4;kGHg0YCuh>}m^qZAfYV5#_B}|}>K|T;!gmBhD4=OSHs8th!wa&Str`pIq`$}va
zwc^A2JeGWL<%}gvun!-?dCNSfHun6gPeQO(_t%$D8}H2ta{R+iuPU+M$GtL^Fo7Bz
z`9LfpzQX47lqk;bnGmei=NPO;Y03Y(`J!^X?7dHvSYzN48B3U8uRnz8FNX|ecf}RH
zt}(${{T42wHtxD~aXGGk<YG$nz4P-LOPE0Wh<qS=3E_p7rIhIQ!?_8;S|`2xjXZ~z
z{H<Mj2=T_D%PR5izOUC<!UV?&GMaJ9@=EMH=dTIDT6fO*Qf;i%eJQc=pM6$RV)o&)
zYb;>`-Usr5ct>)6?`leX{mH!v!CDVJyFhK6yDU~zy**-p5)XviYAj)bBMVtQ@VCKA
ze0cxNgkY_|Kl+*4_;dyI`)n|Oh!RH~Hm$}ICg9s4ABd1-R&mE#O5FMIX$iqvZGZYy
zZS1l)`r(d0VI3tdA3wIn5+*nn3E|`8*HdEQc5Mm4TDSfg^=(Uj<E6N}C(l|xL!Efi
z@$1%D!UQ~L<O4C4^mM(of!etKsKpY3wR(Suwy7mw{3GOizlS$eV(Pd#tt?@JqZjdg
zdTpdcuXQg;2-cd|$83z<wZGVya;6by+_Fn6OPEOGkNW!?Y0gjmeDFvnSZnQr%tnv9
zuyT@!SuA0K<DDc`9Zay+oEy!?ub0QD4CTCoB}}9d3*Fs>V67*YL;Kf~&o~l(!>#fJ
z@yxF~YOy*?nBWL0DJ2QPTKAr1W%sP#ts^$PBre#lt<DlA(in$IdqS|*PCY-@eC+&>
z^~46=DCFaghfk}sgb9wRlD9S?SnG{xR+p^MZ9}o)HNyw@&#beAi8Lzm+ULP=TSBnb
zSp)v3`Iz?hMq*=lqlWwHlY8qdVS=Nuq!vvG)>`8ZtJ{})0xP}8$C|p%5+>3(idut&
zV6DF`-%YOFl7F~2R;+uAv)B*k)>*;?$8E7yTjkEr6N0s-?rCl9^K-EBo?6a2OPEL_
zuNkp*E|_4gjXpP@;qY$olF0)oSi%HHdLhhecp3YC+$$ki>(!a&`+PJw7aQcs6f9vP
zjn&9oN(k2a`V#ZuPWtm!Vq>y+WOzTsBP&?K1jmMn*Ow5iwfcGHi~je7ZNvt7mIX_g
zNTWOQUK4_~K6=1>>K!iMR&2CK54m6o6C6#-mzbj$o)D~6%(K{F#(mp~4f6C0mN1dV
zYKSJ_!$~xe5Uh3U))wO&u*3FZgCdrKB}{N^m_$Vh!CF^bW3k$5ufhf*FFf<NpBPcF
zgb9vVljtrXQZ0)tzxf6>B<A!8Qlo9u0Faak_zY6J8R1cCLd2MJcz*N|7Vla<C=xDG
ziN~D7bvz0-tZzVauCcSkoC(1_2>Z;!E(<NWJr9XFm5`XTU<ngEBT1iNy%BRJ1Z(BX
zV<w8UwOX#El+^J&P)b<BL^`KPN}}43m@^?*tM~Sp8Pt;7`ynx>5)yM3EMbD@Flo%G
zgv6W)!CJ5V7*DPxxA$D$S|udrELg%sItxi^1|=lsObFImWCC^wY00g=l9*Eoi8%|F
zFu}8)H0D$SH5?PHwZ@oD)P~i&Qj6;IkeIVz2@@DyM!7;yq1M!DLt@T^V6CTmZmu@0
z{g9Yb35huimN3Edq_o9RLSoK@V678x-%@Q@J18-y5)yM3EMWp;_s9qOVYTHf8Zl>`
z3D(+RUaQ)$_FQ64B_!sovxEtrS*0F;5)yMJ1Z#cJ(xx`dFA*<835hxDEMX#@8znKP
z5)yMJ1Z!m<p^a_H&A*bEQwfPV>nve{=VEEhsf5Iw3Bg*^?%!H%n4c(KpAr&t)>*;?
z=AGbqU<^S$OC==cObFIG@JqC@(hsNpuEd;5NX%Jh2@^bfOFd*IB<4&A)*6zb{cFk1
zZx=6I35hxDEMWq(dXNu{(5R=cgv6W)!CI?+ZZ<6bkeIVTohUJ9oh3~0d@qeT)rQ2J
z3Bg*uZb#eHl3N@lQIQf7b9S(ViFC%6L|#fr%$X3Z_1-gP!{R}SIhBx@vx6l}@C-4H
zAT{R_bIxLdwPt^AHY~1{nA3@oEMX#@<3*`zWrDR%y})c(d`>xUWeF2Jr%WSyzq<*+
zT5I<;8`jStF{kE3V$K>%m`G=ZQ7K6X)|#`bl`HEnk(g6cB{64>B~0)vH0@zg0zE8D
zu-1%z@IhO0>-UkEQ}ZD)XN@IHr1Qw=txX8l`uP=BmstOm#GINci8*U5VS?waX^)o@
z5_2X5Yu(ZdF+odi{csX<Dj_jvjU`N^Gta0NO$gT7b}6gdtv^v>PPKvFL6$JVGu^ZY
zQVH}xGQnDJE`eR%T5{_bm6%fri8*U5VIrNY=B=8<oC(2NA6#Z_t@ZCp%&9ieTgwtA
zcy63TMX`0xm|(4i1I=f!erkz1-2=#2!bCc|O=3<ZB<4&A);fI;^L?zpU1Clp(0k4j
zCU`cT_Rzbxln|`-%~|Hd*|>qkoJwF6fF(?%^Wn(rO9<AweVqBCHvU1LWyTUFc>bM^
zm}t&1V!{M#9k7@A)HaSIF{ct3m0<}J=?prFIhDZ34->5Q`H~hJ*mx9q`WZ`@;2C>5
zf~7Vvg2e=DO@G*892-}Ym{SRilCgw|bj}?`MG3)LJT|E@XGbIEOhzr4NXH|2RSHLU
zmckJ3JqB$DV$KjO=HwM4OmN(m(!45#B}{Ncrla9?Sj1>J6Rc%VRz_0qN2|aqMp%oZ
zu$16cDJ)@v<171)DN==*15B`%y=l_3I}dd{uNYx1j*wCU-!X*^%p70|6C5q2D_@vk
zEvv^uSaAUQ0eHm-YjK2>61*yfB}{N6ldgPWg0-xbkeT_%qR*07jIb8RJ1HSEQuJP7
zMhZ)q;7BH2`N9NiSsN@lSb!d3UNOR29KECjuS#JF6C9VMD_@vkE%R_fSmr(SxATe-
z*5X(sC1j?P-Yd*>VhIx*Wuz-#m|!jQALT9`i_r{TF~V9LS)>H7N?{2T95YBC*8BJ-
zpv|CTg0;-o4q@iq7%SoxBdo<<e@gJG6qZzpmfT_kUird=otu`~manAF!$=&j7-22;
z`cr~erLcqvyCXiL$SYr%U@d!2(nGx?#yNe(2xexo7JK9=fv=L{d0=KHOPH|I<9@r$
zVpRgOSealgE7Kvo_ti3zDqb<dTI`Xh1is*kRACk?OPH`X&Ao75`N9Ni+50bLZxf8s
z^NJDHVsAMmd{qi&{IY}ztCifR#+Of#56q5cg0-x!lzk}&U<L%Q7-22;eN#eaN2?9Y
zj%EoHR)e?X<{`^WawRa6oC(&lc13n=d*G`!ok^|)W|FfO`@SiGFF_&am`TnOCakq<
z$<5!z*QP*V);$xfWo@vmy6TJBJG^3qwb(CB34Fm7HZbd+B}|xS;IokA8*xftg#r_-
zW&VoHth^j!!@OdIwb;u{34D_bslo~cmM~#nR7-BYD873J0;@TgU@i0QLU?>fjEeJ$
z5!Pb=GbQl-HrT*w4wf)so+a82*oc2q5`wjCB*jz3D@It0XS$^XuS#JF6FloJUHQTU
zYuPxJKS5qG!dg7jEhX?hR^%S5Qdq(S&tcOQRZ5^-F~M3k3h1SsSB$V0&s$3gc|X(!
zR;93n37(Obu6$vFwQP*lYX)91!dg5FEhX?hR@^JpB`jfr=a=b9Jta_IF~M3k9__U#
zuNYx1o*|YJ_#P`#g;gmmVS;Cir7K^UU@e;;;4O}?7{RJW*5VmrDS_{?B2`$G!V)HU
z?pM0<g$dTO*%#hA^NJDH;`v@Ff$y;*Ralk65+-;im#&so0;^@2U@e>5;+~AJ7{O{;
z*5cV)DS>aLB2`!|%MvDdURJvDg$dTOnM3aN@rn`F;<;EUA%3E!3ae6B!UWHmN>{!x
z!CH3i9x|^OVJ)5~l@h!vg(XawZ65`|_bhOCvGRop*0MX|(FCs;VJ)5~l@j=#1#Dnd
z3QL%<=j3B7_-+jdtbAdDwXF1b<i#sSSc_*pr3AiP0~=VC!V)H|Ot<7Vf`xDVfWXQZ
zCRoefG>=kw#RzNh9Hx}OH-2CPt5R6PguVYQxs4Cvdq^O#@`VZ3vRcU_dR{TYT0A2u
zCGb5Y*ubh3mM~#;WlL_OukQ@nKnbjTVS=@+2KU|%UNOR2JijO<@a-t13ae6B!i2Re
zExC<t<2zd*u=0fo*0R>ldy4R#EfCm^gtd6KP)guCTOhD1g(XZ_8|*U&@J%uh=)You
zwahc{UNv4Z!dg7{CnfMrGT6YX6qYby{z~V(j785<0)2f<u$FmI-W$oQIarHl@}va5
z--c9S#RyB7FyF2vw^=W|Duszui~B{(D_>v_J*HK{=IErWYs`D~K2}`Uw77>gg#QN(
Ch11^v

literal 0
HcmV?d00001

diff --git a/hardware_designs/MarkerMount_v17.STL b/hardware_designs/MarkerMount_v17.STL
new file mode 100644
index 0000000000000000000000000000000000000000..c83a3b42b03fd49246f18671498d4fac81076acf
GIT binary patch
literal 293284
zcmbT91$Y%l_x~4nD-<Ub4N$aLkel5}kwROnNQ)JRQnaN&1-Q6FaDo(v0HtU`fIyHI
zcSvxjxC96U?{CgbX76`)Nniedp67i#&pqce=giERGqQVce(c%pyAB_H+4hI;JO1!x
z&!2kq`L=Jl${+pz|GSmlNciV9sqpmvZT9Jz#a14}U@y=7W0yZ`c2ks3HOtF%!Z7X$
zNr?kJELDDe;h<S9!!7Z7u~H{Q%|uBXC{gw*7+#x}HIcp|RJ|lYLY2u|sh>c2-$h6*
z>8)R@JUYQ~p9JgGTRw1p#;AWYHZ~WW>FIfT{|p<LcD6;n7fgMIeKLQhDAVUuUQ=SB
zWf;l7DH4@zMUXi%)mT9&2@>n`o??S?PZqRcWIZ|{YUQ8vJ$_xIJ)JroXCv0t5t4}R
zr$o8nn*8k2yi;s)L@R6NlKi|KnK?0i^?Xle2Z367LXHbU_H?n}eo;Bn_Y6E-?5GDN
zNaU<|nsu~#TUAGpjgL4nj}s9N0<~V2IUxvX<B!VUM-_dzE3p2azda~HBE0w+*8ApQ
z>u@8ov6&NBAM6V3>L5_-3;&aXkTwQn`zC7G&J<>qk>MVcAhEvRSvI=g7%L<_*%-!&
zew?W3AW-XN|7bx-8{KOKM8&l$Yi8Z|hbR2!vtpzumS~*&AD<}Z3etuVGP`C}ith`U
zd;OPsP=bVR<3)<<QLomPG-s@z;Xw%!RHi6tSLH5`tLHOWRJEX@=9s+;U4+uo<ErNI
zl2O0Cu4Z;@Fv)`wte46=hEB6i-QB}&WKB{i>iOmx=Cn0~U4+siLdCRUJm6l{<X)}e
zUSZ2mWj`-`ZxZImun!F*2cI90mj{_w`TRf$5;tF85H^a{_v0f-Gb$;cQR^H8Y8B~t
zUJ!E5$EHjXHM3T8^P{kDJt#rqUcSq0=%u;VjPv=pjhmd9%ZX<jbON=?j=LxbX`}x6
zo!eRu?Pj(*UC4tHB!2C7m9^Qp!1}Qb*=WUy7MvL9AW*C3mCJ&VHeN+`-{!gB-%NI6
zPj!?ak>>1mHZId*>)-{-)K54O$cfm0bON>3Hn}DUX=B}?d0Ssr9AsLpQ&vX_5_(Qt
zl|WQ<5U7P~i9!Fo;{W-IFmJ|9Ys9)VBEwPn`t%=7Iqw2^wv(SrT}2p%Pl7~Tlda50
zCoo=G5e}W$&kmQ074@D?d631FO`DKw|KMxX^@Os|ir3t+`7m2<-nF$<nWCN6N9iFF
zy5tXyezy%Lp|t38wXWC}L_5%TS{XL|Q{DDZ(Kf*gwBGt!hy<=H|4pdX2UiK3@RE&Y
z(|5A8FGq^r9hvHH)~-oN!U+0o>jc(?D+79K6TG0e0}0Iei4&-W*;No;$&rl!_SK;5
z2|enIu~{L*;d7rAuc=FXgewwl8%XF{@8~OTN^dz5q5np)*v-Er^fY>fy@*;kPPRVx
z%**#CzERuF_ORe5YZ4zpmsd!Xs<@Bc{rK?z@CvnXZt7m)Na1>g?XwA&S4iMqD{%s~
z-ZcklEDWPm!Dx|}jO}MDzwL6^E<eh9M3lGB992!&@XFCM43tc4dsJuzFHPmangqfB
z&us$<{~5<5ohICqIDuM&HqibtjWz#TsX(1*w?($&&34m7Puk6upZ^(G#<6cl2@)TF
zEQw<*jU>FP9cVr0+7rT)k5i2cL|XR>B}jB1ep1jqN*&PK;Y9+qbgwFnKCm_8;#(WW
zZy6Z1{PtybuIof=!L*C!>iHMhhFRmR-qo*~1?R_zterXKL*9;0I8pEGtAaoY5}gL}
zT}|y#R*xnBaH7x116yyj+*@HXw}Av|4WE3L<(M?Y>b3C}Cz5kwf7_H5r*Z-%<?o(m
zxj*e^U2k#M;Z^vU16#XK3tK<RVFQUdQ%|vb%{p6c2i@m3n(}t=KK71t5U54oHX78_
zk}W?l>cG|~*9%pez=_MR<3+z;3fp9+E%Zo~$A<o8RvPw*EgqlMs+r+0ZsT80q<na^
z0`)FRX5W3prVS`+rSG!K#F`8vpY+Ng0wqXLxyFVng8pwpX;Dqxs!z1YTf^ARy&836
z`3BVvCBb^h+X{=nNN7h8C;sj-AS^hc9ZJ$EB9`6X(b|e@^tWh-s>v|2@ph!1m%O5C
zhms(Xdcs4NY*bHcSD8KBs}|fwlW+HjO-yLHB2cS-gLtu9p1*H1CxUpC+{!p2d<rK}
zg2dVk57>iW23r42+sBFG+(zkH`9wRAK&?rgpNbvw!kDd`FnC;T8sDwb7;Xb4NR0dR
ziP-OU58A<r1>CD^*)EA_M+p)=gYL1<rw_OG{&<iRFF7%=<-CfMxD6ywEAmmS*zY!r
zr?~Rt?U;IeV?`PdlpwLw`#|hoGhN)viBx<%R{ir@j0Z}P_@&An7Bz2-_2q^moH)<D
z8nk;)1@a0BUF)9M_0heCVPxPoUVlGa*ig3yBtha(l3Q$Zg$Y)FlWsq5k2tWk{xBn)
z<~b6mg|{MxF`avrKlI-)$|Wd4V(ZF(*!il#R<Tzx+{RtrSD&?JVHE91pcZB&!-(fz
z_1u3?WFM3uG3c{v%(E!ix_RI%w^4@TDt%l98V@8;3$v@9+i{-Xy%Q&LNlelqT3*o!
z%s5CKeJL|hp$|)NujD_uaw36RO&Z1udy(gpa-!<E1%X%Vb*gs$?hjEvdvCK@k3-Dn
zd+&PY{d0#6sTXQStt}VW=H?wXuxti1Fh?1_;<US-!>qewUu2mVUq)@t9LutvPHxRK
zUIk*kXwNYAS9=?{X;EBc-fXR-M*Z`EwLWswY@Xs!AZby(<ooqm57?BaSIk;Pc5xd!
z%4afDmiAWtx_sj(lpv9A&I3U=oxPJ2KPG<|IRBit>W~iYGy=7bw7JhtG~H+VO%LJ3
z+%dV#o>}^BJsI?c)(-R?y)}$2%Z>*|mF!q;_E+CUVV_`Mp*_P`9<@4fTE;3{PnPHv
zg%Tu2O}xwM7FuogDpHSo_35i4f&IVuII`F6?=%9n^md&6d6n1!_0KjaD%JBFqEDXp
zEbF;@=c*{v?u^QDy?-^S%-5*-)jh5Ls=Bp$-$79*sek7>Gf#QVUT;cN$C`Mw7f-@{
zGmL3*12h{>;-5pKOtNhl-OhUj(RpV-ji7p!7WScG42`cDcsWJSt@}6qqV+Bk+djR?
zzGywhT>SOt+{TN)dk2;*y)g26SbvQ`EsSZy_&GGQm?f_(e&vcp+8a_NVvHHar1-Le
znENUq3MCjNI3E)yP>aeG`84MfCT+rgH&qsy4LnBfAT@*coy`?AeAr_#YtvrI9i$T|
zL89djInVd(%EO7+%sFX1yk8d|V5+fwbRvI{>Rl=qe)|vW&}o<%b|XJ0(&Z{5;%eLe
zL8gk5RK`a^Dz2!!^3Q9`*fYS)_L_*@{Z@H){^A$eHOn9qB}kxc!}z*cWlxj0*492h
z=>%#$I&+=fT<JB_J|i2Y1I~K9|CWu+JaV9k5+w9?R6JK(MB=KfzlxSq^r@E97*M%t
zwOedOP_VggJ=w@{+8ekjd{|_*&HYT2pbZtf&l(UhzuoA-AtSeL=`*{pMxfTuP4BS1
z%NCf!z9VAN_KfDxvG=Mx@HRG8W;peWUr@K%57_B)m(8}k{6nxTXBp_ni9bUh1=fEN
z5piHmTN5Rd@7`xuGo3KYt?&!NnhfLFzh?uVjGD4#V#m&!4J7`w?y<`GBh366$*YZv
zj|bNKtx{x-2H$A}YGIoU<JPUUfk(TtYA@6EGEsuW-+V2}P$kqnRF7;dOdwLF*9p|p
z`|5sFMso=7tCoWso7g|t+O4sVM8EBBk&oN>i?1ISw%^#)x_o03B}k~*yr~%xjrNu`
zhpoR|WoNM}8i86F`FcfT^OYcid1mOui8-$VOq3v@=6U=>nuF{Ambs+n$5k`}wWv%s
zBq3+IT+a_3Oc_Ku>i0v7EW>y$vO(=Qf4iK=$jNUx<v&Su?vz##sf?sSs$6->Hm)V<
z3`U%TKnW5#vdfyT#uJS;P;#hm8ey;e=&1L!fkgj9sRf<?D$!^Iy+W-t`6ZFj*sc@a
zcl8zZPq|Ez$dYcY^==#cydMTBy7`E7eAM2juaHnSR$ffQY57l%2iApJpJb8!_B?%R
zNqE(*fofp}!^>35U+44Mz3U!xWrHM0sGh#nm*{tSMFeW8k*$(?uq14+P@<ybdN<ON
zePw%P6DUDKl`9&tmh?%r{9OcTJvC({mg;gzC%7%2^($lLS^e*aIT`k$ZUZGq6m9uJ
z%&yjLgB*Q@1ZtHppG3qijgxKzB}fci@lx0rT%wy!c#%LY^*Jj)Q6~(PAkpr}SHi|1
zW9)wrsI@3u64@Wla}XG#-4DrleVRMvd(ICe)Ci`|n*2ZJ2WqJ(p**Jd?zt4nMZXV-
z3S~FzCzIJHZW&WOa`xaFM>|l0MAWLJf^PC)>3<NYmA<efx`i!q5WB-=H2mCXG0Xg&
zEU!DVkR{%`C_%#CBk4*33#1Jm<uaEbfm-z|NMiepgb`GPw^A3mejEy3uJzBtim61)
zo7Y{gx5JAP?6=RZ$T{flT{UVnJJp!)D0alcxv7sJN{~?Twt8k1r{zCAi&B<BEtOH-
zxgA@+e?|(?T4yilHn6owe7j%9o2#$vIY@niS{R|ihF6WC$~aX<J>mWCTV+<amf2_8
zs*8>>*CjqeWhK`-Xdr=F75<Rf=jq;k`j{IiK|=M2+XfP-RjrTAC95xNaI^y@NT{+q
zuHHqE7R~~F1W|(ZCO&JCKrNijx{ZLfavs!qIhU<HAj>rGj&05)Vl0C(-_g4$LE_9#
zNxSB`7bUUNr55E9tV#C@B}i1QBWcP?i4&-m_&i4m5^?9`%HYn4NT3#LBnemE^`a!#
z8o6&P&vQH0q_+blNECS~GaRiFi4&-WnNKICbd*`YZD<Hf_ga?YM$WV|>VL1!NJNCn
z^=j1bGaO#2c%`~fYf&eeePSL@cMzEM_tuju07WInwB8PsAaP`@q$9qc<FJ7QYN5Bf
z4U{0U__nk$EPj^51`?=+y{_9>c|@*iheuDhBSVgX{Jc*mXI~kHPog4*2(+!+KmxUz
zl$C1<+13e^AmJK8uUZYT9j!uSywW(Mhq?`vXhbtPSKM)h#Al%OG?|=(6vx7b?G;M8
z&yrdc`B+opULnyk;RNX#b1&9~TA0Ul8z@1dTpyX?+_8%UYGDS~ZRFp3QS6<!=c>h~
zq`x4_s|NeA&oj&C&Y>v_=wt3h0<|`$zbxp0i9K|}c>AM#THL*pUl2V*pws<@kvaJu
zcaA92=ek!YL1J5-gMtW4Mzs7Vc1vFL#4x1Rie`hY!5ih%@Sx=n9bV}YAED@~<#XsZ
zjCT>Fm8e&SE|E55y|U$Q8#;kniS?BlwHi^eEbNFJ%@h;PGu>P0E3F+!?8_oY@T0Hx
zI{FGFvyV%yqggh*rwt@Bd~ijKV7)`mlNb7nTKdRhJ5Yi|)}zwHlcSvHK_pPi6}w)Q
zulzr3CEiurH|BS%V);d)Jio(V*3;Ya9k%JKraEr6QGx`%^(I=OY<Q7CtuCh?3433T
z=;*M4@58Bbfujclk(NEB+M!G2drL&L`!<Uh4=N{4pw{;n(hA~1`3nxB%#>onU%Gpl
z8Ints=`JJWcRx|KZ&<h?dB#Br5~?h3Tclr-=yJKRsOx^GgVwH|c}4lJmlrHWxNlg{
z-(Q9$7ryU%l~Q{PG4YloQSilUVej;l(vI=K-bJlMN6?FL6*#M=s5hd{A6ks*USTXD
zQ7`-xLI1XXi<LNmTG)p=p<+p9WEmxtqty7jGqo=95y4|qiJo?6I3!R@jnmSa&eZ@V
zNT{*#yG}RT@}FD{R9{7grwLL$y`gmaAfz?IKnW6RZZ2p}H{1N5SH&($)Hug|m-jtw
zAfX~Au!f@@npdcmXv+;X59kg_&5tlEd5{|OvOm&Ymi#AY)Tm<RMf}ixw3@+mvyC<B
z1WJ%lv)O%njs$9{&*g1BdZp^6T%tUr8(~Gb=Q&D{_&HOcXrFy&=~W|$1Zt_iq8y{Q
z93@C}?le6S8%Us*icnfhbQ>r^LX}-7FYmhu(o&z(EYNM-TJnYPm+p7gwX#H+PK~4P
zW)Wrg%>+u2=>4{WAn3%Z+3@boF8hSe`hz!46<TznSM9KEc-43yfm-8Q$(roDK5j_H
zZrJuRqF&n3j~H83l<7R6ymj{#dUCwZWI@nP0ov2rVW0$wxtAsg+I<Ir1Zt(7JVp@i
zJAj<ce-siLkLE)=i89^XVNHp9g+x-Lji8r>IBq$$cA%E(D|<Zb-bD!#%YOUD_E7f<
z3Dm-P(+F?NZh1sqGzJfsj56tLK=(<zt%BlnckiME3AC--KmxTMoGT%0xW@w}NF*BV
z21cSHDEdl$Q&iZX)1>YdM#En3aG^!B=>5hViFykM3EF+{gLR=6#+&Aqq4E{26Kc=!
z`{>j`iRTiOAffgsF@4iIvJVodh3l^F6-G(2N!dkfDVN~*>jX-W=yg1+pj|hR1`??C
zpoS#e*+=y*jdRx%<3znQ&R5n2i?aI;K&?x()~eNqR%*4DxNn_Nf&`9})^aZrsHMDh
z+3=zS2^=S3!>jTx5~!s<w{wY$Aj!K3SEknTm8zGt5?>8)q<+1ZO^gBE4&umaeWi^#
z5^<3^1?|3J!Macj=e%wMB}mkmB~L}JC^3*gtweK)-B;8<8(wx3zSC{p!D&B>vVD_k
zj|ax+$OTjE)?!cV?LY|<yGBnFH1%}i1ZufP(Dn-b^=uv@>ZSD@Z6|I6iO~F`1a05-
zaZK(RurAcX8LZpDokfMNwM4ztqc~1Fff6Jdrua(G?weF3Pz$})ZJ-1RwNkrpgpoik
zj2QmTHvcAIO8(7aY3(&X#ns{8ccpi3WVuJucGi?buf#Wtx0PsTB~GB0Du<<|nkw+`
zC!XWqEG8Q$QDv%kWaU@lo5jB`BpZnlsHMtg39`|if6wv_|7J1SK#3|-y}|6I_-1j@
z&h5F4#0b<<<tMGk#v=ZG(I5CXi^&E`RGI3HeDqv=v$*e%9k`9e2-H&Laf`{uUH(nk
zI{f>!WCJCtO!cZa{$FqJ$ZaG>pq46s{+eviw~FJr9kPKERi=8?cLWC1?#yi@Mxd4|
zr)r;z+o11k(>HR-21-<!>Q&znXz`{Cw~-iuTB=+%hHMn$-#w@A*OCpCs4~^7zEyDg
zR99{zF#@$zIm1`Exs8fEZt45AWCJCtO!ca76;wFTjoV0!KrL175koef@!tZVc}O-;
zqRO&f`3(j6+X;yg>bnQ{TMhD;5P<M1t#J(>bL+C+7Fn|dDSOS!XW@G|Ah=&riwM+G
z<?B<aCTO`AC8|vIs(uS@L^go1TTXSMmMTw+AsaA)UX-XZ)vLxopcmNy!X81Y3$;}F
zZ8myq0V2_h5>=*pRUA(rOE!S8Ba!MtEmfXTk8Hq<@}fkQsa`c7-!38>K-e>i>Ow75
zem0nFKxXiwM3t#tl~-aS$OaI0W}v!IOO>NnkqyXjd^}|CBZ(?gy(&M>-bXfo;N#&V
zP)n5y93vZ$sl6ysWvW-@`RmbS0|+})Q(dT~%CGK_4Onr!C{bmqSFKm=E|3i%>=lRV
zLM>I^{*r9KTI)rLD$9E1x_k2y*#N>`Ib~g_CCl=?S58Dx9-%coiD6ju)-9bms7&vL
zQ~7++WTL#+OYf>BMxYjzsU}I7_xlSQ`FU<c2@(@VrWZDLJ)#@P#0b=)GTD$sqoLh|
zjYd4jqXda$H}eP^lRu>!ufzz{qB7Z#1dl{vgVuDEAW`#rSz%*lXL@TkF#@%yOg1FJ
z*I8kMW-m&R$n>hNu+g+Z25uuU0=1}2HY9Pcv0OXqT%EGjFwzH+MBbRD527)ra-HaO
zqFgHYg2l6WA_QttnQD^6*d)K06jz_uZMh94NTg~iZA>3>fZIrnKrJeh4N27P*HhTY
zmLhB$N|3lZEUjqA>B^hAjl>AlqB7Z##IOh73LE+So^L}55|ulp5jJY2U%_o8MxYjz
z$%Z73Zu(r<n4Ka|6iSdVjMTzLrKYpFjl>9DE48p82}AtzM$vx?e3L%t+hTbFYs_E3
zp0|}{x>f7k=>ze(_QsYV%7)&th*%b~mZ>r;f0M1hzgv7xWodz*qXeNO4eF=2GMtGQ
zT4QfdwkD;D6Xgyir&~HvvU6KTHU=G7W*s`%N0jNg<E#+*dD26FI0%#=p~{0hRnook
zqKyK_+6WtCZ!gsB>0YV2$P*+=ocmVL_iFy`@CpgkYC5*HATGZNk%U+E74}KQU$LTp
zNDKQ=_X;IQWGeDN&~C4gK&=8*?j?-PLg^JZBu5b2QRKqc!uP9nf~}@wn~HK=s|lPa
zad&Z1BIXw!vxuHM(FoG>(;SUch;p(+<1BhMMW4$jqen0M7b4<fqZCC@f<)63Nd<ke
z+<0!o^VQtKM1;38Gy=8gi5c0DPs6X?Td<Uf_5PcRpacneLPv!5j9$bpN|0#T&VZKl
zj^h7hUm<~7*y~bX5hy_-R{_~q)YFL*sD-mjBfJ=Kw{N!;zSF$Jk<|zTB}kM^(n8QQ
zgA*rE3nNA&xL3aTX_33JJ<e!bBQ&p&m=)4c&=g~d6R1T`mubwk_Zh^PqXY?zO5Fw$
zs724C$%gg@gs_1UByipc8(tM9I6Kp2xGUn7@*_r%?iEUqP+8lZMUg-)^|>pH8Yn?R
zmEVsbEmc$ED-LO?di!*m@E-)$g@o#b=%w(D5p9hk>!_uAz0sv$ef=;{qOxe!)RW)S
zD<o9b_T--8uz~GBEwxI_&N$UUsC9|_RkMiNq*fpDP>&LnAfYmb+bcDntB;(f*-*2&
za#DEvQ}ixM(1x19o-dsQwnMGdG-^oe?LY|<YG*(ZqY+*tP)mL8j$M=>p~^PlRkQY8
z1ZgS4JqK}YRX%TYY3h5%6%uM?pmEY#ZqHhZ4AfGqk9!1h%vEkDuT=Zovlb;tsI|l$
zyGWo`;*p5{s@0id3Fl4XEk{D-VC^p4l^IYAz13}?1PQg4xNRVTTCVwF$Cb(k7ytQ#
zsa$d;epTWv_o^AS@1xarHXs6RC*BT~C5TYtLADboP)m*GphqhuVYfq#;Pp4l?MS@T
ze}%gpHi4~GIhfk?eq)Y=%Ja3pf$zk*#vHZOT0&<Zz2#~?)9FW*N$dT37YUWS++JZ_
zsD&e|dF91^S95URM=RgcD<stXr?Js&*gG=H0H~#MK8>tKcyY{e)YN>uxGsV4sw}E<
z6j@gpj@p5=W<$$xNT}>;M<U1cQ!2FswQ#0sHtgLiwNTAe@*T%XBecFkLd|*YT^tdK
zSQl!&U(1nDnaFJe>q0Hpc-VcV=E2E>>4Vh#NZvg|kg6$XwS+g~y$QYRMFO?d=k8kr
ztXIw2pfnlXHf*o3UL;h;2%npg-;v3G`k0fysHMg{qG%=uff5xZH|J-1Pp^<rQTb__
z%nlpa4%AX7OZyE|yX9(}Pae!1q~a=IduIN<eR+4Hy^X8I6-kg#vo>s&(<_vyd0x5I
z``SQ4<rR0!(O=Y3d5n5mA3>C;6^BL*YtjjnAfZ+`ca$K3S}N~SRO&WRqB1qj53ETi
zP=bV78EB?yguQ#E5kxIjlY2&CEUAo2Bbazxp#%w)!DW>EIAwu9&GX>>n~NfWTI%M7
z-h1Xxz}MzoLPSuBLPb%6gvve?$NU$XX02F8M6zl3mLP#z>IO-BJ6c3LN{~?5j^>SF
zwESm|Xh+Y=C5s|~TIzf*-z1;)@du(ENh;+miV`H$Nnd+gU3i7FR*f2sCeqrN8z@0S
z-9N~Aey;r-(O1(4jVX!*YUy63ZTYhxuH{`>^!xIEi#v-&mwH*>P1+;Mt><^QUamMV
z%JvzDyC$-zx7dQiLh{+-#%8U54vO-SzWGf>$QzbJsVazjxV@S8EJFzrmv8PDbn~;f
zeBT&}D${UXF(go{P)12e8`~lWixFHi;$)E-J+_Ow$oFXncZxE#X-C1$qU>siaq-bs
zA)&fH$|=j_iRx+hO%Y0v*qnQdsEK+(A3-Eg>vZc)f}lR+&ufc}5^)tfX0|^{0v~M@
zT5T(jHnArDEx6vP#og;6ztPK3f<*80;eu{6a^-(`g<749Nn%pXqnyZHtgq-@&z;bv
z7#SZ$?-TXztkT&LB|r2CSxiw9@>QB8Y6Pj@k+^pMfS~W4ZDkooNB{9665CfAToeh^
zvJM^+#QnVuIZ^FPIctk&o46DuKeam|v}U*b)Zx{W20Mg}ojFEoHjp^J_^6=E8s)hS
z`A_Z{&@0r+GUk{d%9Sj@i7PkjiD>`h*@?m-r=)~>QPC7j>xvu~L{R%@ymx!V{w#<_
zmy0h(2@<o?N#a)fjNHbW=UK&gcu%+UM;pO~q&*sEqz$8g#!RB+v+B3d<{%O~Gs>1z
zjPd6~KaLP__436if2<3&aQ=&)@+M>kBi{#+qJ=cJBmW8$WxCDYUS7^YIf8<bxx_#T
z67yzn5VU;KzzN$%!I7hFN!8Y)Y#TTWqy^;_N|31h#YjQ__suqHoo+Tl5UwX!Ui7zM
z`}IPLo?u}6bgxi?#EydN1TAm2lidswBUrsanPo_z*4Vibf}qIv*)VT+UWyVV_&ZQw
zW6PtNV$6RE8tjh*YL#vwGm$+%ysCF~iLc&=KgnDo=ZEx5&ZyC!%G^g!sxFt<COn~B
zGJKo-oSw=_ePshBNMO#_3C#McOm}aI6DUDqOd1)xboZ{?KmxVUTS0ge+QI+p>z{d1
zV?@g-N)qoYlpuk#K(k>Wfm)s8<b0I5gfq%310_h{yy5S7rWq`vr0cAq%aA~=`e&sL
znc@6S7ZVxo)X!djlpvw6IOrA5wSpsui@u^KqezRE6BI=ylpqmsX_%nhPezeIEl&qY
zxFXSuu{&?JoOk3EMy2i*N|3m{U(P5ymv~h>kU%ZWuDT7BATcIJ&OvvELjtuh2kSN}
z=aPLwxALlgoKGEeLiH})u&B7An`RZq?xz4Mi;|Y|gl@CdN<=m3Hq=}rPf$yZll%Dx
zN{~=v<9_~utyNJ%^<w*UuTX-7ib}T)Bv4Du0{87XO4J(l{x|eUs5R03+yK2oEgVf>
z%h#<bv;=qFc(PC#Ro{gZff6Lt*ysdVLjtwb=dLF|HbD|3RM{O@SQl!kJnw#@h!P|)
zLPcMB)jU^mMOjA8F6SFCg5dw>&TvTZH;+Vyb3a{DBPh=@J}vdRyLWYok5D$=k032o
zle>3yiL@c>m1Xw`zKb9&)eG+N!2F>y9L*0L8@+c?f`rPb?m37AY9*da^xP+R1N3}I
zZ=du_A9LA@K0@v1{`=_?YN5A@w;TzzFLh^XtP8a;gKIXtYJSjj4mBs}IS$sO6R4%K
zHa(9@lrT_&gc=X`6D%Z9OO2-Mxq%lYDoW_t1lFXrL-Ps=6`}5DELaz6sou4pv3ONx
zP;o`iBUE-Kt@n#7BvhVvd1aq*s9rVZWDmVfyyZx!7;`_Hz`9WD{n~+q+H1RQ=yk~%
zMOxU0q8)bcVxOp$^ZlQzA)!`nS6tb<SDNRjrFH{$?Al(TMC~%({|PS=Y9*risE;7_
z6>6!xYd^KLz0xHzpTGZ;QMJk-;l9~MuT&YI#JUM}V@{HH5w81odpzilRkfUM{#C!Z
zpBt!grso_gV&4CW2@+~Px}VCRbv6F)|NH|96=UvaEUJH~<*0@2)1ySqS|Zdur+a*r
zuiWiGiOO))S6EZxHjq#m)%|n{>q0G+!QCy#=u>59#OPkBzLF6qqaDkM$CXn{)g<rq
zr4@Y#ASKcU)vIP2J!yKkS45x|#<5OdpQv?^;tKmvCs2ZfT6f*^0}0ep>%9B98cNju
zfm(|-CGHgxYCrE94=>h*TIzE-PST1T50oIG$~NImSe<PfBtb1zlY57Z5+qdF{YJ{W
z2+~r$U}tLH6xj~UGHUI6|EI`EsI^u;SHr&2qgt-Dq@}!dN4qZZ5o&FB+du-fFcS%%
z)Ogr$i_n>aemjBQ*~PN_MoiYu8^u$ZR(skkq2I3{E&44j`eh0#)30)=XZP~-5`IuV
z%_yDeNl}y_LBC}|H2rRz>?su`NT8PboW4)NZ|Exy6;A>DI(e5V-^pM4O(&|Ce)CKb
z(yQUAlZbn`c_-o*qXY^1bqAv5FB=_Lepa-6Zjp*hkU%Z$5v?7@(^rP5t9I4d?8Sk2
zlj>dn<y=;^{1j1kN4t_NuQ-m)D3Ddq{$ppbm4{M`a+1368!2?x=dIjxx~)~AM6f7N
zPwRUVP_|t9C8HhNfkeaSqXgaZgyY>>Z%6+{Lh`E5JeEAeLQ$r6sG8jEKnW75hs+Z+
z^@!G2UL;UUeg5C=K;q+&*}{gaue4}KE$l<XX#9B*5hZ_4+rOk|NJddtrs&b^`$lp+
ze!Mt}J-+G@pZ9z~Z!W)lT1OB=8Z29aT6gwj7h2U%jC2q)c37bl?cSs#{jn}2vR=<A
z=(n3jIQj|+)Y`VTo*>${bG}cF5+u~TS;qgGt2Q165~!uh?(x9bUDs)ji15Wf=y9yu
zzz9cT%F9)PE*?Hk_sWX|YE504U$mSeU$=o0Bwqd-C2X8M=&)fRfm*#&98bh6oH-*i
z4i=tJWV~POBJpXx-ieGL)`eP$j|WPSpx?EiOvK7NqXY@m!dNhj4@U10dAH=2@yoDJ
z8iic5#~l06Fe)wFE1un*3ajRi5+uUEh!gbFWRCIhB7s`%GnE$YkooF^qw9oM6W0x0
zh7u&$xg>&!?nb|Q+9ZC4$nB?c6kCb}YT-;Xj1jdqh;}SmG+3LpNNn6JGxggwW4MjC
z&m)9a&65vbhIOG9<`_M8!w((|q>-Zh+U9a$(La<+T8Dok%9M!&;Z-{sTqkh#!MUm1
zK*_rZJGa|5kWgjPs<(dZyGPJK2@=>oy&XuPR?;c`g$+4^oUy&a{y}0(&%A=Lv#3p=
z1PNbxm?M|Gn;6DILvjfl?ktKURc}^Jp+#$n&xZ3k4oZ;t_`_DR9U`toZzb$rkw7iI
zufEEWwKzpd=*PKAe0e0hs4MHDq3qn(IYs%e?L)yUYI&KcnqrMAls4ZA)O!AzY;E$(
zPU78O4P!{CzRJLF>ZQJlU0*wVJxW@NaQANZ9*4yIAWs_9J0i-|jx7Ak^D@H?b=W`&
z65ZM!7c}*V?$!RASA?W>^P%j=9k)bzN}cz$fyB&Gv4XDcaoRwyP;2I!ctPy0=p@kJ
z0#jpz)~b>3>lG5m51bRUr>D~fdWBlpBZd(Zc3Nb(`Ui%DR=S-^^gFe%&b)M@OnrqT
zYZz%8rz}QeUaUfkP?R9ymp+rAsn_-Kz%fS;u_o@->dYm`#)vhUOP~aaN=cFn8?twA
zRhcT<k-Ft9%`4Qx_VMr0=g2ME@mJRhq3Cb!+#iT~sYlVaVbn@hTo6Z^XVz>W@i;7-
zplLMu+n+mfE~j?X`5^xatP8bpHjBRUsu`s+K&>eon92<K>W6_>lzo!bZY<{c>wQ`M
zeKzK6gvvzeKMv<agIAXYG3%SLp(-cltF;O0jkMRROC=*X(e8uoqIbzZm8nVMvlj_v
z@~X&&Uy4#Y(yu#G<lV%4dmRidu#potidPiG->EMaQF)gnJ{x?EO31;o9iq3m4f?Oj
zaLvp}rg}7Wt4OALx<~&=ZbSZ)go=ifJ0tBJmBEO#BY#x5lTZ;(5|!16P|>q>Ndn<b
z7(p-EP?6YVzfS93VZBJG$Ul3~=@k;FrLqs%GmK;PvWqbfNcXcp5-Jl>U#W~reVDjc
zYBk95(K}ksG1<G=CrIEp={Ar+Ej7C?20Oh%2@?94uROU&%)#0(ZZF3^QJLB~{`{{y
z?w&8!+BKz<mB7A2LahukN)Eo9By6M!c(5D^)KYm@M#+k?&z4bNeb*#&F_frGO|8Y6
z3?oIARAL0z#oy3I5DB$1$Y}pIQ)WRVnY>0LPz%Rj9}mn7%9B2wHp6^$j)!li`g|us
z(KJ_lHh$mmqWHTA(o(Ag#TftVz+dDR?dVz|n?Fjh-o#_~kGT2b)G#G#5lgpE-hR-p
zhNu&ny+gKR7bQsS%p~toY{ILe9SPLJn-^cpsf71QKec-z)(pCz!Tq&PpacnHhoo(<
zI40*H5~vk(PM+1M7laM3BGk8<=)P68iSBw;*=++Qs!YVLjdMk>f3^$$rk=>uN{i}3
zEgUDU<z98#qP0(*)o4wualE3i5x+d)+nILDCwx*%Nb<M;!@d`#NK|(xwAyJljJ}6{
zwuvj*huifkZ|%Eq+XhOI*syY(pzq8|_{O1E^)B{%gHo@>m{U}0<CNf*dj#J_{IGw$
zqa9e6DwCFPrqSv=Xzf}tqjC;7rR^DzP-nQJugOO0#vd1>b`&U@a~al!TDV`)dl!8l
z7@S=64@Cyr(+QLyv3_L+L64gQzs4@&3JKJzRz%*5@ANpoor&>-aWyxzs6K++H8~#Y
zhJ|A3T`}g45{!oS-KU6p$rFqoz2zuD!oNgFA}vP(wQzQ6HoQ0w)SV^m=dev0VW0#F
zbzds?aMV$%uaH13>~-A+N{~=DEbd(&5~zh4L)cJWdDV>|E5Dwp`^3j})-zX>a7>Ol
zN{~=Dp8du<=O7ZOg%PT^9Q*1*gJxo!)9>)*E_Yn1NF)go>fZ0{LFaeekw7hs9^EUH
zAW?XA7u&<c3Dm;usu5nCcj~T>GEU-i5G6>c+emvnylMoIKrI|6%`5&rCST4#Lfw~A
z#3W9j7RH-lg!XDG@~*M0NT_=5M87?+o=4Gd(qpe1Mnt9g;#9P~MUACMpq6?nCx3@N
z-M$_oQ~&T&KryUWJtd>Rm4dWkEXh`1dNsO5C`yn}(L=wbsJ9#m)KX=4?5bS`Nfb@r
zWL9N2ff7|FLOorizkI{LyHvKjX!+L_qy3c@)rDGmU-6cBRg}<QouykR`fK0xSHP)E
ze>Yq`m34cC5+sHXdo12!O?xG`qp#@iAIqDqoBWsRWSM#tYvR8mnCU}tHu&(<N%nV_
z$T|}A_j#!%`)@DX?Lh16o<9_xoXnZmVMC6g%y4KOiD&8W3%cNk`5f&)0=4$W+!n-!
z!$f2n{Cg4V-MlNt7Dj*RuLG0s^jD{`Cc_x@;UqzH`}$mAlpsNWDVS*aH`W7_)e$!n
zy(@IFzZph-g<3eWqTP01p}$exZwTM3Sbh$#66-4@?%ug7=)~UxAg@qMwJ&jkcF5bl
z{8!XVd-dp@vP^qM>641x#*>qXKB1k(n661hnf9N`h8??h%bWB`C$wl!{atohruFsw
zLOBcUJ+)1s4Xk&|Swqz1+L3u@g=7&D+AXmOvP?T~-)}VHd5~J<lgwxS6(vDCiy5~w
zi<;a!0Obkw750z%+-^Cq-5u>nq^={|;XbioU8t34%e7yp#5PU$lfP8y9zm2Kk$B6I
zK&|KDax~rTz{n`vDw*g}8fR=DjRO61_Z1Sw+b0(^ov)<+y9m@$xywBsC_y6QPbuV>
z^L>zE{MfF8SO>>6YEfkH6q);I#~RgJmMN}I%}E7b^}EqUtOhmeZCZvBB$RE6P`w>U
zpw{Cta%G_1nNFYt2~~Et{9T09k~Zu;oLBWO{ry_XeI&tp^}dpRi4o*~`9%F5YGfjF
z(D?+*N6goVLEYqhlsCd)Lz}gzg)><1E6g&OeX!Sc0wqYC*)PXmo<B-tcpz5JAvebP
zBY|2NJ^bGI;X1M6ob&&vXy0jaWueSDtCgIov=>Eh4ddJP>&1#wX6KM)C_&<jt8xy~
zErs3=Bv1?Uu}*Yam`RK|d2%4HEYlwMkM6SN_PLg0a@L{*iITw?MNRJAE9MN$B{hr4
zcDQo8ff6KEj+L33))l=SNT3#as}m?eVnaS@!`-_`pceL_ZbR=A**|nP#G3dsk6gz^
zT$Nup-CvjZi0Gafpm!UuIxXVramkcLkw7hsH^ZpcxRN0LxZu$u5s6CIWK_yC&agw{
z1yS<jk2M0dFe>@qH)woc?DTKU4lnL$Au|Kr{GV<l%XDw7R&9A(Tcz(6(ekc)t1d$V
zwK}wwwEMXMf7>J>Uq!NFt7QHl8@m?EGTGM0L)A+e*_Vl&UP;Cq)vxxJ<%%GGktp0z
z+Lm|7KmB-9v}0bqi%XF}ExjGR!@S~7f0X~);sZ*{y6ColNq$+T=LT34-@P^n7S9b@
zE!?eng+z+Xl9o?pp3Yh&Z1DdU$GUVaNw}W;c(E7f{w{k|jzJ;>?>3(ViSx50E&EFK
zuKcf$KrQrE>Z$C5HeNlH^-^nb{B;5)NVK>tY3k|33DlaoQ4;QFMJPdH=rKvSpY|bv
zT1R(DLO#d2w(o`5WsEMjeL2peE}zMMBTw|c$~B;}81wR(HfUpxM7ipcmNwoTt0m%U
zYwlfIT%i_5sNPpmzsXYrz47T^NtWqJgWC1E@AOfEMCR&}{%-=c@bn_Q@~S9#c3GZM
z=<Tn~FXicl-u_dz-R~#jue{&uAoC!#!#C&uYbS%md?sn?5xuXlF4SVNavhZKy<R?+
zPmJJzd<#O=xrW|P^3lVX+6U45Ub+pGAmJ-J+wpF~cS5q?BjbkT4nXa^NP_k1?T~)C
z3Di<+JH7R!w*w_e6!}s1m3)7<Z>>$DuWCLWvK$H2Qfs?>=dMz0MzPax-1Ec|lpt~Q
zklg#wyVb%guWC8QQm#*AT#;7dafK2j&W)4jLHB#eNT8Pb{J-Z15>c6?4cGhB+IKBc
z3um)o#I3F%vQO<b6^dabs*FSLT=~Y|`NkGXkWgj&9WT3g-$js?S{dj~E<H-r{*&G$
zR=Y5IM^qodZE5z3b{w0xtQbm=Q2ROg?%<dfjl_Ds@AJOPkU%Yr9^EUoLn5!#{)*mK
zuAM^0mHRzplptXkatG*s4;cy6LT?Qt^U~6y<--ph@z*83det6PzE2&qr(q~Xd!w5L
zLy<r&>~+26>hw$bN}Yr#M;$95?|tMO@sg350VPPNGnG60phTV3D1Ts0x>qPcLY<0a
zW=PB{)JmIQp5a{If-q2mggS-U@1$}wvgJsimOirR6-tm$yKvXr(FPKzg%PUvl{)v+
z3Yqt=yoaH045;kmUO7>MM45~74#+*`NT3$3+D@<Jjz#7SS!U&jGPS>UX9iv3Bh=p4
z{njKBsHOJT?l&{liG|(^Rl6m6CsFOx<Xd_;f+#^k?au7?EWIj9a7JMqt8sF__lgoE
zu4j|?SN8Wmlns81Bl8l~g<9%!_n4yu33Y?y{`LS8sD%+@7{@=qFY@lBA0mrm)>o$q
zdVd#J3B%wgNPp@peuDHz2@>igBj4Z6ltaFgI=K5VjX*7RW{@Me$jmNw$oE@?Ek}vk
z!_%mt?Zjgj3ANLAzr~7mp_V!)&|9;@h8jTwBT=0*sjo1`bgxi?1kM881`?>H&IWF;
zP=bU$qtch?E%tD!cK=lzTd2-aH1DuS_-J36CdT9GFRPcM1POK0bI)@mbS+<&(ECa~
zSD{~r!Q7?F^tn!;M3re4>A!{;c}Bi98J~Z*{d9@yLM{Eb4I36KEq1SCXB020o(cYb
zXpyC!L1js|)<S!Raeq?1!Zbe~Ub(&qB}k~JS*vG8S^WFlejNqz-6yLw0=3i=vmM2b
zaN?8wsh5(C{29MqiW2oyu2h#x4zFZy$#oFDLPBK>`7P7L2-H$#cfP_ARL|9F+_|KU
zCjVu$0U1RuskwDP5%dZP^-Qm3)AXicbl99n^wq)N{#c9zYN;ofFE>}^#K8D(1u-;s
z$zqhKC!-Ay|7`y{rEJI35AuqfcxFJcrDy{Q^;EXc<we{^Vts{L7(I%h|9Yc-9e$O)
zsPU_5Y(HC>`Yo=vuS|dYjy~53(oz!oHC<IUi~vS|!_6kVlB03=NsyqjMkE;038KFm
zl-;6wXYn;lm36P)b~()d_Hr7bRjOdLUG}z)W?4@s7oQ8lD>?psOHJbQ5Npy2UE(9&
z&nwiTnwFb)eO^hY_;{cM3B&k<eR}4)kFeW;gs%06+XkofmVebRhP6I&Ghx(xZAx%R
z{6`-TB)m6Iu@g=A`Nli}(+SiHS$u}oEwtK4aE}cBKmPl;AW60G9Gmqx<p04dBw8K2
zz`kfb#%JT5UZEDobb_+@k2eY>NbD(inVF~f-$?(@`GHzE)2MRlBl#~$!rvLC+(%{g
zHz(ESYS$+SFEJ=_5=3i+G{XP?Ue2<XI){^%D$CF1y{OLyVJJaDmVpp9lvi}$uDnuZ
zn&;|$AD<0Hki<!l4Mk9d&_A!Kaz-lSqac+_sH}2~EK6-kpacmuvhO11i2R}IrMx1`
zb40#+Hz8XnJ@FB8M!AXEdt#t2U%e~ZpJG=to!~8}ntcDfrY`Xj*gl^=^_5QeJPCPu
znpMspq1*5hfqg<{S`EmPdM&T8344Ci32w}5qU3UxORPhuVL}UQ(!D|n63;H4XDfn&
z-(dp@UCY-d-3Imv6624bWqX$`c!v!nP|Mj@e8$`V<X?)FF`8cdHBwckSWxc)xCtrI
z35xc25!r%#b1<8*A)lqG&*eQF+CYg;;0#7WwnOF&>6I!|JJgQMO-PAOkPZ3y>pxfV
zzou&#H?s~h>5WgC6ZE@$RF<us&NjU4CO$trn!c-#1WKF)(UPc>Z16U+@%7ezCK6Ou
zS_h~7ENsL)CL2hg#7Ph>iM7{{3mdg-eP<#;Wu@iWJVe+S^*h}mBY_epL9`@BHP0kg
zgHLibHj$vR(hAK#O4x`SIg{H!0wqp@Xi1zYSWejZ_;`Sc1eKLm*AwG}jkclm+agGy
z#7Ph>iJiy46gI9@$!Q`%Wu<jxU9hk*EPfWZfdopN1ksY%H@$<fk#F#gKqRQFv_>wN
zB5Xu_KZn~u0wqp@Xi2o)(?{4?bZ=T95>!@NyGBnFHtM{jCqGD_#7Ph>i8A*G2phSw
zBn?D@%1UcotLehV_8IfI4J1(FB#4$o++X6anS0kom)eR1m6g`s?9xW10Qv?G5-4#J
zL`xzy`-R%!Jsa6<8xmAjT7x%E742AeWFfbK1WKF)(UK@Wrn|6l=f<{eNKjd69j`N4
z*!a28Vr~NolsE~ZC9&_#H^N4SDk-Copt91Mduf8O(JgEVw}AvooCML5$XwDAHeMDe
z9)$#zl~&rxV}y++50-KpNT9??5G{$UCq5E38kDLXg#?wA)?V*$VWWH;ee(qglsE~Z
zC6R3X3(AS!>jS=xLW0UltKPyv!p4B8P;LVWlsE~ZCDDA+3Spy5o8D1KP+4i^Z2qIL
z(Y!8w9|sAPI0>R9F*su>VWV-w-=dJ9veIfkw3D!LD41*@ff6S{v?TVPDn;v{_X(ei
zNKjd6sr6C*E+-NwaS}vJqRpvN9&W=R8%U^?leCuo_6@WH36wYq<)LVKAlab4LW0Ul
z>(-JlU_5wV*#t_Q1kv^g3WCNQ2`VeCb*(I6!;TW0K#7we+Kxm)Q0yW>Wu?{oZ3SV&
zj&_?siIX7Oo>3<C70p2;sI0UeoGT%0*t6CqP~s$rwljkuD3>5XWu>*-DkyB&*~cbO
z;v|T+Gn^nOCn7;*rPZ=q9$~}IqBemNCqc9%YK-YFh)z7WBSB@Qm26UWVMDG4NT9??
z5G{%4)-S@wzgwGaLxRdmtJm?Y!iHSckU)u(AX*afe+?2gZXPYQ6$vUUtp_!v4Y@ia
zff6S{v?K!V4-hu)W=a}}1eKN6ulKTvcF0`@5-4#JMB6(VVT1NQNKjd6#YN^6HtgM!
zO`ya{5G{$7(>n-a2H(RWL1m>?W0s$=A$NU9pu|ZKEr}b)zZ5oB^Svk%R90H0z9}kf
z$lWUvC~*=*OJaS&a>7OfzNbcl%1SG2dl_Lv?!u8kiIX5&5-Xc$5;k)2vjGxRR$3#*
zRuwknX#xq9I0>Td6N|`jbjCq~%1Wz3*IL4ceJZjElsE~ZB~d8ZU_rFvXEh|Kth5@Y
z_)6H2r#mE2;v|T+Pmp3Aq%$WHR90GQeU!fu&(EATff6S{v?LOC0Ad|nSTU72lhf)|
zsY^;xrd6NHbl#Oa0KV4RI{=g*K~G7^hFs72(&1hFLAfov{v8yB1ZwS{kpgV+J%hai
z&?UZl>2tDS?_|Vy(0YypYJIyuxv*jHmTUqgPJ(Q>*K;JOthCOhkT%@wIZB)a(eCve
z2`VeCoAr~4cDUDblsE~Z-Rn6LR90G1tC9*E?)4lcPJ(FndX5B@l~($~(uR9IM~Ral
z+P$75L1m@2J3NVKhkHFoiIX5&68z*P@)e!ckf5^C%KV+QVV~}70wqp@Xi4xBq#)?b
zi3F9EmcK{ZuurKrff6S{v?TaRSP*n}MuN&pt9}J(!#-`>1WKF)(URaNdO^?~01{MI
zT6^nB8}_Y%O`ya{5ba*ik)X2DIx<$;aIfbmaS}vJg5R(Rujoz&2`VeC#kZvm`xeJ0
zP~s$rmIS{k5(M2XAwgxOHKn7RANFmOO`ya{5G@IQ<0S~XBSV79N-N!KX~Vu%vk8<q
z38E#zZ|(#^cYR1uS!qRt%6w(t4%!4toCMMC^&AN*E3HMHWZreJ=O}R!L`#C-q>9ym
z?p~3gveIf&R<2R@ZLLk9#7PkCUeA%BvQJB{weIztR!ep3>?DY`30j@SJv9<)ttG9M
zM`TU5S2m$b<XWo;pND)WvyE)f-UkUPE3H-`sf4%oZpkK4;v|T+M^F&7heLwOO6#*`
zsf7(YN^AlpPJ(Dj@SSB8wS)GeNKjd6Jx!KI*syo6Hh~f+L9`_J4p|Vir$&OxN~`-U
zX~W)y+XPCS1ksY<JAFaW*#HSDE3KB<(~5T3rwN-tiIX5&68yv>2s+~+L1m>?u8*`~
zpNeb(B~F59J5vjS&T2?dS!o5Vl{W0vz$Q@QB#4#-KS2tD&YVb4S!u03AZ^&ERGUDF
zlOS3W{3J|-m(I>eP+4i6*(q(<r)`@+iIX5&68uCj2)YA6g33xOcDl4--x}BiN}L4I
zlHfNJf}pz$B&e*ks@9P<?As5UK#7we+TM`~g6?FHpt916J16Idz3a0HlsE~Z?VY6{
z=xzxKDl0A4NZPP>uQq`aCqcBmLly+xks(24rIl-q%vbg<+$K=sB#5?m`jp|sJv9<k
zR$4_~%DiizCTs#FPJ(Fr#3Bf~vqXZ*N{h~kBlvmHJ{8#nN}L4I_Q^{SbXG&cdHy6D
z@^r@=ZBnL||6cR=8R}ShjGX)io62dRT*vB>w4FtIZbC|&L>jAhod0_eQcKz{VI@g~
zkP>M_5%k<yeqJnVj3@P)92H;B9B4*#KgBlvQ{5`KCO`W;^D)tm(3Az(p#JAsp454*
z!}I-k`+hzc?OA=HNtN3n1I=3*AG1rf7nyl-<Yu#OJ!0c0FEESe&&{f}dd#x_w$xml
zGB+od<&E*|oW4EcJhu^g|1SHa;Xw06n>;K<hWl*agCXXm!g<)~;Jd8ni~;6vee!T(
z<p(jIs_}v0Z#j|o%S$ZtisR;Qsr}f<!<X5qV-aS*jrrJL9WS$T3$~jB4&~#-Tu$Ua
zV}=od{_Zx<v!5oGwl@Fa$FO~d@#w=C&mR}ZRDR-UITHClJ<qOYFKeabH2>S=ysu~&
zoqdH`WP@UX`jEfN$-OGNy=?fu+y-iW*X2CR>&L9Ji=|gS;shs>N7t$JCc!HuK_b_L
z^XyQrTGpp?$g4S=INJ7(XgOL(txNMxvB?pwteH#5t1Q`KJim<c+wg+h$T9UMJO0f?
zE92*R*=Nme@^|1CTc?`kWogb{XX7$0whms%%ZYE&#dyB{^WTlx`Isl$a+Q5GYk~Qw
zem-VJUuD*Z^Udyc^RW)Qud^<tgUx$ah#2)e+7r6qWJFU=pah8z_FZRv!Y7(71@SaP
zjHlSLu!xKf0=2q6yw09BoM?V=hHO|lV?5(;WDdB?+kp}!mYl!A0)HK5{@$C2EqP)*
z%U`t#xa1&EtLgI_Y+1Wu=E3iY`2AkA=hE{L5d*nb7;zYh-(0`Uwv>o4udJg;{5v|@
zQ!7c~P5U{45+sJ7yUfy+i7+EK5OIJLBYrFBB2eq@kgIHK-Nj~P3nH@fNL+F(XC;b6
zlpyhH)K&JN_#(4!b0VH|B5P%{5{)?$sD&eI7`F~bdp>V7X44hk4wNAAWYtx+XypQP
zbtAIz_C&NN&DNZojyed`!tv)VFBIbmp7FHuU)(F~-KF&|vDS4@n8o>=$NA4^ZIKwy
zMl-hZR!*P<i625QvW@>-HFJGT^TQh$<2jJ2Z$MWEfm%h9US#V|J~A`b6U51A&!8r&
zBaZNPpahBfDK4_sl^>fOz9ixtCpu<X6LHu<pw<_07uatFpP2Cth`4ko+H*YV2NA<K
zff6KcHNU{BKS*v>>P^JuE76{H>&iwfbP%XDCH)1FwO0)$qAmC8$L(E2J5Yi|;Vc(e
z&-7`n2rm(}d6Zb2&P7mMA%R-BG8o2(oM=6{@dhGLf<(aR^K5^n+*aMWWaDC%7|+nK
zuPZ0v?LY#xFoPS$a&E&r_*}(T+y-W~rjO3ErvYDCok#jHJ;SZ#IdNC@J!1Vp2@+8)
zFR*B{g>|AAd3A{s{kP<;NO>0t)XG`$H0x;fwyKVxELw(pHEPm7V&y~$61QV6u(&oI
ztRl_G2CW~ruFP@~s1;uP4C{S!uywc**%->b>OHmb23plng2eb`7uo9FJ*>JS+M99W
z^V>bbXvIMSwbu7L%SQJbV}+zA8^<^iGI7)fYB{b3-7ei?CBF)`x}?xo2E*vciA94`
z2phO&AhDpq9rk1IVC&#UTF*`1@|GpzD^Qdmp=;d}tB+qRA|m+ee4|16h&WEP%Kw~A
zTwc@q>!{ja$-UOC+|OD1;<c;|$LRB_+{UcR=S3vy61hX7-Px2wuf#eSmX?TrcssTa
z>=8ySM;jTxea`OsSFqab((Uozh|e73$>1GXDH)Glxzm%LAkn(*b4KqJUf)Ud8E%8`
z84R+4gsz1<z;(PGM%yJ7U)qG+O(L<g>~r?%<a}1%Lu8{{rWjB09_Ge0wpWrstv%Ve
zSJ`q~Z;lf&FIkMIan~<5f6NJ7`%YfD!P<5nW{&KYm+9-^y3{eAg6I7s@^b<uNSvy0
zla(qy)XerRt(<o<#&~LV`7AuGgFvk|Q*N@S(L>CNeD`4(r_#rGepvr|L>5k<1c~iM
zZ?l2*2AEx+QItIPkMYE1`n5_p?<*uw>%4WF70EupydO)%@!~O_^b10&tmXttkO*sc
zn@tJ$%{+RWh=2Kb<aiq%Kr1H_sMU~1dyj?#%=04JKjlQN1<9&Vw4(%xT0h)nk3Jk=
z-u^|jgXhF6*T!!$c*~JMEq#ZakB{I#D?3Dd!U>ch@$;0s>{6it=EEP!M!VcGo;M$F
z+<2XPg#>Eh?wr3<#M_a(*YFAyyO=+MKe)th<mqD_$mYlNT(X-Ji_^aqv5OKUR<*m#
z`o0`w6*^3N20DM78q*|<`U(luI+guA8<cyp)g+9vXgWTl;?H}+sjpCiM1?t*S*;|4
zt#mud#vyK_YP!0@D<n|s=IaaWlle2PV)e;J2~Iqo(@NwklpxXayQ}QLnGsf=wq%1&
zENPO|7Q1jHQ0rd4%WUYSxz>#HMEt?WqvV{hO4oSHQG&!d?^RYd(@3jCOCn}*uZCTl
zyMfk0Bv9+uZdX~GjSH+F+Ymvk^Y?WZi=2pBySrUyZ@Z1PcE;spI`M$d+G&fLh*^sg
zBsxF3&PJ3OXI(u_vo<qt`M%cMHqdw=fm-@$qAfpveDP<<hUdH;C_y4q$PIRD&IIek
zAhJ<`x8vTN(IQHaKrLLmc*5m2rd(OMj%F>cGWp8fW$T6pTd79VoWK<)l+VE|AA2g&
zz62#mT;wO#a@{6c9r%gWF!pnz|4(&Y1ZwT{J`m@q9x-$hZkj8`vwq#T;WxQgC_&<F
z|NCrdsfpI53}l1$?VZZ53Zr%)fm)G|V#Sze_=;>4<m0iaU3f(r50oIWXw^gZ`s;C4
z=@~?P%Wdqb)kN&CkU*_*pFR<>TQw#ZCw};ipSClU+7vQlpotPBs;_&<hSVQtRhmvV
zig2&a6h17xLISlWb$%-5V5;_HV=E`_7W5M{3blTTe8lqQ8D;e>mYeCsGTx3YgENQI
z{6Gm3_47VvHQtP{>SQCYR&X1iO|2npAc0!-8^nw3^Z9F9IdAeYUz0p_CF)(&dNtz-
z+Y>y*`t`3|Oeg;2HWoF@Uy=53C_$oD)i}2Q%pj}PLTWkf8A_zsE%GiBs1^C>x!A*v
zTTEWHDjegfQYpixo!rLFs}I?(w!!ABvANlIMPk{!oRiHY19P*!sbZP`_mj*ohEdB$
zo{RQOJ~*t(M&1sTAkn2?EK50Zs`*zpBHn%!<0+M*Zp2}30}0f^`yifoQ^t4-uP+o(
zl-ocF61#gnVv(_P%x?n7#_k8vp2lC@4(RJ3Pz&#w_#FTr^Ez!tiOhigv!MJ_c0975
z^|*U3ruWrhP8^?|A)NMCC_!S!^QUZ1R1a%N4H}Old^~3N`bq2)kwC3r_EPNIpR}U!
zh~Y%zxg!LD5+r&Kea8Oi*2QY!ucEz1g(e~rkwC4Hm0yYThgpJbY~nU9W~?9xlpwLL
zc04Onr-ha4EfGyQ@l(3!3UoF=0=4uVaxP8;J$x*p9VJNI9~jSmpWe(G_?T?0=EU^K
zA4Iexfm-_RynfG9p8S_uZT@!ZK(l7`C+uk6wdRgfx!9p6kJ-tYtIW4Ia<L|dAG6z`
zE6ocJsIOYgjq&*9-?FI$&ps$YBKPvgY+c$F=GtdORO0z+@4YdbW;qDd((f!sosafB
z3&~k!1CK<MAhF@2$1F6{VzX6Nirt*0qdlMQEmQTyY@I+YoCW+;#BaP({arsGGq-^|
zui7c@v!}NPo1YZb??~lNe^0O40kqS{+fyVmh2Lk>#t$>oB%$@=3O`3x&ypd6ZaI-a
zt+}V~vqwdSn}5Hcc1+@TWC!1bL|o<sN|0EU{Q+zH?{IVTJtB7T88z?395JJiK&|R=
z57@-uF{b}EA{Ox5k9|S?s?hBRN|5j?@Q@kp$C?ovh?w^#+VfraTLCp31ZwRc_>dhx
zJl;&TfQau_M0-Bkm9%Q}Sp!X!Ac48kFmil;%G3VOZJQ7CNJIj){Q0U@uEa#MnpoA&
z$HaIJRqVRC-SmMbN|3-@X&8O^{P?VG;|(+i@l2LxK3`>qr?W=grCEgM!Ka*9V}w-p
zogn4u4vCWE<JtU^X{<pHiC)i%z-x~qXvM+0Q0vOrcyUwow;)#TIO7@pw)Ey-#|<=5
zf<%|0@$C5P)YkY%WMlW-lb$S%CRe#MS0_;G&TsK-Uf0yt9g!I(BtPc4J+(*GUCRfW
zC_$pz&+)8Rk<`}GCuE~?`lFt)3xcaY_(La9t9SQ!cCk<@tHd)Rj(bme{OXL|RDzEn
zN{|SuAJ6g}Ol}Po>-m_W*F32nl-lCgRVPsE<rnenU`TT7jUd{7cHWcg`r6G~hYmDR
zg2b2<@$7K%f6b)nDf{f7ALGe&dc`I`o_#RGC13W0l{p=5Hr$bmwcYxJZ7CdK{vJt0
z?efu{u+QF9xx;e_5~!8^$`iJ}=4LZ*7!hZ`Iq5lZs&~~bzYjD~g2cFtaV+v&q&Z<F
z5iQO{drlp=5wMNVC?rs8Wl$VjTWY%*GM|Y4hoU_PUZ$;bgA*u0!moZD+i-5X`D!i^
z>rX{{GEBb_@Rx%?t=ntj_?`Y9v)gDQ+WMdNcnhW3{AAKVbL!S-Y<A9PX2CqUShEYy
zm|wD&=1<vju@~!}u^(>7nXU2>(dP3ro{IZgY|b!2Cp4`&&)AC!kIhdC5|NkRIv?8@
zuyGH~50D^nW5zSqeHXtGE=0siei!~*ulWI2c{@;oM8DS0*xYG%%>reJNRjE3XLaVO
zn^sKI3DoM_<QY3R<&K%M91$hHjq#j5yffl8j}nw1F)-;fHmv_uvu_X)efC6qK3Vd2
zz$@+*5~$TX?K4)f$TjnTMMT-qXiudMS*o<>IT0mDyx9Dd{eA14IjA8KqdP`>?&l1t
z62v1BN6IhbQx^B?kQx0`E@ozZ%2M_{Y;NyE#3y;9J=vb^uM#k4potPB-qe4}Dtvgt
zeBGId+K2g#*T}h>hVv|n1ZsJEJ!KzkiZ=b*67jM#zuBJfLzQaWE0iFyztdBe=FCa6
zoH$Kv=66d|T34z30q-j$P)l$5yPnskyO)E1Yy7qNX1OZU)82jF55>31olkhv@ZST7
z<NnGUNMHHC2w9htsAJu{l*MPmOLvMYw<967BrQGc%vXc>xW<+EiW7yNOey)C9h?(n
z<qdhl)@6RqT4t|hm7e~DdrRxbx@Ku;XPH3AcBqx1%BUyo(udDkuPnK(O@f%miMo*~
zfv6)|j`gbD;P#hfBOQNMl(gi^h?5}$qyEZ$iEX)m%AEWxmSz0xlK6gplUK2<n{km<
z-ucM9aXOY0RroW=HlKeMk%JQz7u{g{(~K~Kc06K7`JE+wEB@4;M{LK2>*71^b;m#A
zL_fYSnY(;N7(Wk2E$)7vO}ye~1^*e#25&qr*1n+S581U^=h@EOWvu}#$VN_1#02`&
zy-yTMkeD&xl(^sBP@IS`-twOYjjlv}g*IMII?w9*<+j?b)9o3Chuat)+?-A<QCKe$
zzsH|v*AAq&vTP+AUvi>axzXWH0=3lBni^3=<lv{&9-C&;J$2NEH4j<xjuXw84UgIS
zYY#>Le6sm5Tg>-~)Ne}%J?6x0-n-MbT%squQ8>0M@;ztWpX9d2^7E~VHyOu~+^bY=
zkI}7~79~hDYVn*M=~L25`8&~n^S+{}<vSUT(6un~cjw@7)x5yQ`!*rt3W+kU<b8X9
zurZ0-__kIooj<f_M=gwe!|2M}@%C&(y8VdSwpu<Xe_1+~MU6kt!gJTMV%Nqp8gqIQ
zFUPztC$_DBBSsJ<NKE|oJRAM^Q!CXP8jl{Fpq7&jBv4C_t8=^^8D4)#?*Ryco+yxY
zB<}FH6OMK(XO*&JxAB)%H&T>fU8sdIZ5St0#CUG5|7c@zKIRxpv)Wu>#=ps}Tzg}g
z9#<E6l$;8z7ycn9P=Z9oix=3|uj0)wqp9T+!=pXR2P}&yKT9W2OP}ZCjTleG`o}j`
z<2F!&MAelSS^S%;=9xQW<8DcQ%ULIPz*63FBv1=;3_lg|ry0vjuiMC<W@y<bS*OeF
z*rM%b`&^H-OvIm(jgRr98_}c6w=)JtVU9wg@RG}HZuv+v<wul#hVJHjhI}7vddqDf
zfm%DxUKYO;5?X|aLT{rzW$rhP_>>bULE`ZbSJ~5l7Ml|r5K)z{YJ=Ae+?drtpw>bD
zjGlgzBdRG8J$WR4pEOQH`?QhrIp8n9#<ERC<sEz8Ww9)@%Vkz){~&7x?*;z0NSTwK
zkK4DY_TYCtm%Ipj$eMd6njOOQyux?kucAHGDy<0koO^{C2Z``qkJuLz=bKCKQTFLp
zAjb1&+ZGWA`3NF`TA_CyiFRy@C1MtzA6qi{t*3e3s7f45c5;w)qVyB{?(Ny&C-%Kh
z^eW0eyLe7~9FegCzu)DVLEik1YxtO{Th;4RAG1LISCsC5G11!Eoosx~?~t?o+^#&o
zr;dudE#HT^I{6VR#P7d1l^<s<n(~OX|4rVvk8dc(gXgQ!*Gg4-zzLKfQRA=ctaAKV
z>)r$+lJoJ%)4T=U6lnx%9WN!H8~mD;h@Uu7cgwHkDVLxGiNTw$^1r`4(t6p9hzz{1
zvJL+|jNe&m1Zo{fe^K1MmOo1~Y76hH&39jfQD311iM;%m&GNk%VfAlBHj;3!THY^K
zk=lU-YGI7=U)kkEP?L6oKnW7lu3cu+;s#sOi;|5soEVciS0!3;kU%Xxc6aiYH=G?T
z_9ZBZ<nNcfXxi6G^E#H{ERge~%baYk`GLeso_!kp(ZjkgvQGfFaWL+0dKw;ub)nYu
zD)OoRw_j85(mh<cs-pyf5+v%SyvQbB>|_l)Lqt3$+9k~|`U(luimxHxPFNmD#2Zdb
zeAYw|C_&;)>kF(@r54tMJw%-5#M#x;=+-$33Dm;%(J*2;v9iZcVvRxx5{0u~U^VYI
zv7U;3NefQA?pBK4htt+t)WTKNFqYno_AHsdCt?DRM9gYe`TJ1!nk+V}^XStvTrGa9
z=IOk3BfnLPLJ1Ok`d()p)=W0{jG(wGR)R-K@ah2mOjsjOOW#?R=1<&5FRxjVKiiH%
z2@;ndUuQWkPBf46EMXWy+^g@$W{)7RkU%Zm)f&cU+(z)pC-hWb+wWfCZ|ps<KGa-(
zR^R&?#vcCcu3A8Wh;*F5T`>|fZ{K2@`0Yslx8&7V$zwdBOG<Al?I2LA2!G;EzfBdB
zoO0qqo)fJfGDpPozCsBS^ZC>8O8W+w6$=yL;bZ>j`%G16%#lE?di-fP*;p1t#5erC
zzJn#QR=vdu)Or?hmkp~qz?@(GG1G}~zMi+4|8D@T=O{tqInV8r-V8C1iQImLXX>Gu
zOGVt{HjqFqeTTfa3b%1E-RAzBKnW6MhwwLAvkfx~{X*?{%<mblL?4UbZ?|a#YT@pj
zfA525xR{KW#m*AXPUmLFv(-x*TQ^2OvEN~l=cwkqcP|e8Nu2KRgoVT*E1pd)-@<C*
zrFF1BCmK$AN>2fzkU%Z<bl}w;BIx<~+Fjq!{caRWkT~?`Gxq(4j@Ij5L^R^WKeg7-
zb7!3ZE%lV6z%e4e;499)1MMm$<s*m^tT*-3r)>P6J*>X1h}gi}VYMDBayt^JrJmNv
z9l(Bm7ye?wyl{RO9)%JlzV7yv{ZQv8D`$POQIgx3+iDj*wbTgI!rceo!*Lte8ng|6
z#%-YF<@qNpdeC6YuZX@!;b$stqd}W}<tgu~r+u`0L1K8m$834hkyiF+6j!v?zHasC
z6DNUM>S^YTden}NJlZz~od~CW2}+Q-mi960>KSPjh$9>Hymr8iL!#wKpq6@$`!*Zd
zph)cAZf8Y`E0iEHAz3V2x^ApBZY$ZKx5DD1JBrgb5~!t~M^B3(g5Lf3@|S`M;~}4V
zlLU#s|9r@X7U#P&e%|FLVV<v!Zd*a`I`a|q5vYYbKz?(_y*lwYD2#d+B}n{p@;<w;
zV}f;Z2-%p=iLv9mihBkmP)pxg(i_;*jt#F!UZJGZ_`58qX|Uz3N%i{ns5}z6jqoJm
z-9c^lio`cO??$x>wn~Y-`zI&vooSVDKKIpyS`|9WH@?qD(`qo3zuoq0pK{?Tc(kL|
z7SC-~twXTYAk|~06G!=YoO(P?^c6~wu=sjar_n@fCSR}kTVZ^j2algB_M%9j7VfnT
zV?6Jx0R#6}q!kAxNGyGNgO$2B!MeYXY)s=`WnYu8Je>`YKrP&n^Or@^@;Avdd=`+0
zw;azL4RSwbP3J8(cRb}!`n2;$hO^P0kB4Nf63GdaAaP_apT!5m&0qXzex%<J;~5uu
zY}1A5I)Pg2`BMP;<;ds)M0BaocVw}bBg*l1pah9NmE%~N3){^F{On^G?LX%8qh^hW
zl@0>6IyQJJZrF-_K}6OR(Vknil2sixXJ8a+9jW}3<y>~moKoir(}_kqqdm2cp9)CN
zPxL53q5#j-v1zZF{Y9oOlb=UozJ?o5a<7m;tyD9giMzg;J;<xE$M~ByUku&!3-2q`
ziW&Zlt!xr&{@Lvb(}^n0Vm#lJ9TJg)+dv5t4L^-%wc?XoGsQaCdMW>I#`9F0((@BN
z5~zhYo`x}i-<S9goL9L7A9Iu-(QHsWE0!XSb#nx@V+w!At4y~U;rtyhjX*8DZKFFP
z`X}y@y_f-TuBgvjWR*9<Ho*&Wo|6QL(yuRzcWb{)pUeK$Q{4s;x|XcTFGLbvo^{ke
z{8i8Zag!>4O;wiF-^kSox+RwqooKl+mv!!LetEO4Y<TI{LVc0|7SOD?6|<VO-q!{a
zbISx+eZF+q;Eln$0+>%reqOaa-SzXaP+r-Dl<35>t2M3sd;I<f;nNCWH*+_#ihkrE
zyyTTn62QJ6)6!bjGN0Y@|LqkLn;&+tei)qhe|Y873Sc)r{NB1dC67)BuY8gKRywAK
z^&o`)V)py?6%zMy_Oj-`Gp;B~RPXw<0{DG<uY}L_r!sRO`tTQf<>z)JntbRI{>_1L
zo&$09UxY7qb;1{+@A67op967>-Z}|i^r0tnm@i_SgioRqzCQe4gzV`#5N|+u`8Ug;
z-(^{jnzUy}qSm`U>pI~Zf3U&F1nZguaWzMeM9qdT66Y{q>|#y-WdjM{T=_4;r=|Cm
ziYdwv7^B#4`uxxdXJ4uD@O>`z)l)^iM}2cb+Ez1)7)78&_sU0eZSKGNC;hEpcr9uZ
z{Vf1hCa=`r=5P~Iq7(R+1Z={qat0FeSKj5ig1`9gYlp8cpAG%@`(+E{s-{caglv=E
z^339wpyh8wXBOWqR%PEWL?;lu4fIbE^7o>3g1%WSKYy1E`MdCvP-U{A{i?iIm`Jc8
zB|1SiY{H%&N%+{Sx~QzQ)aU9q=~d6tZ{16RBu+xM!}%N7J|fa4sI}^I_wQ_@MA=XT
z*{}&a63drQlJLviUPfh#z6^#c*RkmDRZ$O#xDtIOwWP#Nq~XLwA0ayTT?A?QK9_`0
zCR^rbSLn9|$cC=<e~g_6xD>_m_D2!PNt9&7fP$FF>Fn$t6$KTum=#gX@>dbFEP@gh
z44@z)X3U8o$k|m<E(&<>HGqndYeo=BBBFlvc1_K`J#!A9JdgMGbE<w*ovOOJdv;g<
zUb2xSRKm}-8fvXReB~_H^6h0){NK3^oDKXkA=}fxqZja-lW9UFO!&2mh`iV+n%1X_
zU(BWL)ym@Uo{fl52@`&;tlbzFYb~C|_N?V<BTc9cCafJs#ABW>*_aoP8np0tctQQ(
zb$`qqVUiN91m;-EM!?TfLba@HHcG#tP#FQOTD#ZuYGrNDhb-ae;_s-HXCsf^H3B|i
zTIL^UAIkQ8{J)NeNs@$lmk}BrTF$BCX5#GkXLuu6=Scl~>*wir!(9Yo36G$*saM>)
zu0|<>wfd}7Ph0iuthgOoE0!=Z^>HP}|7*5S<gHd~j~^Y+68N39@B9PC_(Z@GvjM`|
zq+YANr7I2-td;Fv*Y#nGFOxRxxi()BSMa;hIyPFadOYm8+qCq@#wV;Mu))NXcePes
zr@o>s&m+2lWrDTX=Y1R8yEZllo;b?uX`ir`qZgU55ggrRWMVv+V6E!c>zE%^n|`_1
zwS((ht$#f?20y(tw(1d#TaH>WVZE@T-`GU0tgk?@mi2Uc%z12I9s%F(mHl?EAG<2=
zD~uo$N3T+P^lkGJwX(hf!CGG&jqj7`l|B8yh{#7{p2u&<LV|1pzf6m={YEm%mNU5D
z5punY-z<gXG5Jka?rHo6EdCz<cBa_~Si%H;0~Un$i=MENXB+svRA}K>RhjntiX}|o
z7hOSnzx$e+C9K8c@7u6(hUb{pA$?x?hqYqD?B&`=K8QwFSu1E+o7VP9dM$oK8ZDgO
za<=<5Ym~oi`|4I|#k1kTM|Ea=HT$*LYcYHLmh-$~Vw+!-zIUJ3wnDJhM{U(>D{h>d
zAXw7-4AnZWIOiYMiV2Gh|Jm?r!Ung4wJffr){nrv=&l=v#Xi{S@L_SSQmcW>888Nr
znAd_Z|F`TFJ*;DHwF1FfrN3*wTOxS2<5$OF55Ep<bHV$qUpKE<g5UQB;eP9vGERTY
z*#;B%wPw)XZ~dm`E^DRyJZ~-MS#3Ul?H&KrqnNN5(`rk?qw?Gi*0Nglyk~~a60237
z;~@7ge(w@3k7J^An2sPzm|)vp@5(R5mY&60rN1X*J4=`_d+>SBM!*DXS^IYFIVVAw
zPhd?ok6M(y{U6SDCd`}99)4TGMrl@$%dwV4iQ7Moe*fIYBjAy;d9~}YGq)1qxPO?i
zd0cn@WM;_(Ynk65y86A#y=bc__OjgTKEV<utZb(Sppx@yUXHc!8?cy(P4`I767EHd
z)ZLC8{trix30o!J_-``$@CdRN$4bBDL7?@uUz$eU@k`VAy<C*>3%fpn-*JZIi}CZ^
zuRx=G#dUr!ctqa%M1R4$WUtig(Y&gpcOfYe_$^!5^M3KxML2#IYvK2DL3qDx4I+<U
zPlg07#P2Ypj2iNjympY+4)=)C_;0NptYu|8DS{oHSNH{D)C9knjNcYU8NWJ=-xEeT
z-46WTG9>tgX8dw9%J@y^f7T8r@axc^^*5xo?aA3bJjYtxhfY6l?J%vHXTcA&?$}2e
z(Kk%wyMZq$5jHllN5wXLNr|xDO?#~`DG~TBbhP~BcavVr1Z&xNeE4R9$eRQsWd!Cc
zkF55s^%YB)uzpMBC3z-T%X~Bbjdd~PMljEQfM1|SYca3>*(_lKzt#=f`%UkZ53&}|
zP`~B)t#~{O@dLl_jWT8o_qtE8gb9mR@w~E@2TZV*MWuLN#e``gGMEkZ39VsjJcKMs
zn6UQgZ>(!e)T5YSttv+_V2?7dMZejT;9Y9L<`qkru<<|yubN;j8_kNxlLSj_mW-VB
zPiw`5&Crxb#l4FbvX;g9wAY#s;#n3&Q7fJce#=?Hgn3%J<xH@ajiB|ejdvjHhyLaq
zP61K2b3gmL?O4(TBxwRWndrRTt!QWwKTFH1RVqiP=Xp_<|MJE3b8%*!&t2aj6W365
z<A3=gOU#}T-kD`yp?qirPE1j@(^In@pQJ`s@*zu-gwas;`^wIctyXxhmP;phK7ojX
zd6gz=#pj}1C$J|k*(mMLUG0h^S2mK?!iKM<e=pgH8ZP6(5`M1LP|pD5-oV9N+#CGz
z_{b18a0kKm^zRtW=x!oGsDuf&?QR;32u%w!F>Oz8QYs@<!h~NdYd1#HS_>O&&suK&
zVT=)Kg9&R#Oyq5*=v?A4PnJs~sN+6s@#2j3?(kfxJkRR|SEJa*Ezf@E#sjBO>+jp-
z$~Y0W8m3QiSi;2G%eQm02WS1IR!b?*1Z!Czrfsl<i9SQ>I2-AE114Cj^-(&f)3*SX
z_wI|iZ-;kwHgKxywIkrZ;x;|?&<C#HaEj*>EMbD@Sk(k;ZT`FHY{X}Md7CBHKe&T1
z8<<Ph3%IlJZLow1>%;U+WP-J<cX3+pY{a!<2@|cJ*va*7>V!Ve?XY=;^KY)9-wu{A
zVdIoOZ)bwFxTifE`Cl5eboIq~!pwHNx-w29xJ{L}95c>ZixWX3wm#dLczz&$!>v~~
zeFDkPVy!ceYT*c+c>3))dsaI)e{iOE?pJ%eGS2#{ZaKHso{Li)vmMV8F{IIlB}`Zi
z(|0UPu$J{gJWKLs!=8&4S`BduY){&H?=oQ{n?7~sXR%h>1^c+(#VNPfyTSBH&0UY;
z<mR=3ySOsW#W)801WTB(u}Po9F~M3@j$ptNCTuRGPotP%tv-_vcWp|ac=dT@jFaHR
z^yL9lTp4Gt{3O5SEMelF&CfYHzMBwC=M@vIRdr0{k=nc6{%+K8YsDk$*NP=f^xFRr
zN2hPem|(4{*AH%ojR$<NG_uJv8I~|%GX{5Temj_8Et{dKQ=GiD1NphFi71!;UV4Wm
z?dMEb%W+TP*NUITTGns47x9QZOKd!FhR9Fyh-f!~9mKdC6E+ucepxlaTITcd8M0v7
za$YlRZO5H3kF0NlB}~}dP2VUo!CE%+af9jGSbl0V=Q%h}*mR^uBAgU7l6QeLpHF5o
zEMdZCN%}O33D&y*&);0encmlO%-DaYvs_JZ-p=jw+rbhhw!P;%N5^+8HXeB<Sc{{Q
zZ-aZ$q7Uw%`AI&(5+=+>d{b?;^5QOQSq;-S)hw}=<7SL)S6wS6tk-cXS2e*}7U$#J
zzP!!$<NEyDjV<QYW&PfFWt@2N_<J_;Cc!#bibPu>;*}FKj)^8$EOGYICthX)1Z#0^
zU9IAFaNS$pyVN}wr&0VQuN_{kn0SBDa!1>F2`G&W{4Cab_xrCMkv@}QkLt9|c5a5l
zi`bj}TCs$QPCwRgbow;PBS@>)Lv<XXr(bGC+p%`$j!uI9Ip*I@Tp45DqQwrboNhTw
zm|)v}JD6at-Rd@QHqw2?5+<r{hm8l;J1gVHwKT_~)gW&p$Py+jKI)AS_Z1VYWi?FS
zN7)>O#Ks?Mt<BK%Z3au2uvr<O*2eAN8F%#?Ke*Y4aW1tfxf-y9iTe*&<LLCfVuH1*
zUJbZUY?h$4+=u=wVF?p9L*teUrgN7G*0TAQx@iblVsi|41^lF{YsG}kMBGzUO|X`E
zZG20XkJ^#vSz-|mvyaE$x4{x7s%%G|3D&Z>lDf6bv&18!xDvNRs;1+?Hf(0#xv9Au
z6D(oE=2+T>M?~`#S{8%TW6lzOuFd@P2r|K1=4pDnw6UZ9Lf*qKPOGpt`!(Cvx9(AX
z`S%9y{oQ3<k+(D9OMC+Fw=2<i)pbR5*0|aO3rwJFTEBj$HkvGj4JKHUBtR>%>#)n5
zjpNtMFED|!X|-FZHb!59w<eijNs<7q#2r0PcQz)zS-r>v%BIzMs@fQ{4mOxzNs<7q
zM2Dx#osD(5Rz)UIHm%y1sEyYy$NQp8up~)<R-#{dD`#WrQ{_b_P&Tc#ZEZYYg9(--
z3D8ZJf|x3OgfSl}eZ~aJrgha1_1(Ox(*{`|6D&y*pq2P@^?dj1b^T@RnLydJx=d9Y
zqb`IECRmarKr4~2Gtk*MQsyudD4SNZ<J3moJ79wemLv(#O6>L$d@smv5MN{h<&u`#
zcybbKFoE|eaVrB!k^rqlhaGMXpS$7F?(dx4qHt>My5;yKyg>tQ&oyXXHyV%IbE~)4
zzdz~x{Nz>Fg*Ob_e(oLOwJc$xj}Wk-e!f%Vo5KNrZ$Edpvs!orYfal$Z5+G}{QRem
zL&A{<Ozt*Wq7O@$kWY|18yb~<eMWyh`_2BxdW5ePwL@Z85DaPjg8L4-W(^VPN_~a0
z_0Rej>bX8#IR?GE_lwiYE?P2d4kDc|DG@&iQ5u^A8op4rMu?VTg9+ApXS&*Wadb3G
zGAnBTUsud4mN2ofpW4uwShvQlnXj9#nRD&~*LnnN)jdybjJ^OiF4^wZ%vVCp5rQR5
z>~@k8-OdKFW%c~bhGReOdY*U`OPIK`sn$w;aQ%%RX1+Xm&$)|#yvQS1Yp-T%W9YuH
zG2sR!cKPX|B1@RKemf=Z+6lyiZ&nXa9on$l?Gj5^!bJTKY#t-}Og^h&*zoP_+%^}V
z=n<^-rx5U)(?0-_KU0a7La>C1gXSr*>}3$=l(!0-HfY`L1Bs$6VPfM1t(C^zv4^z_
z3&)%|cfs7w9>H4O?o%6kTnZbF4p*Y55G-Nh%$t>1<vu-d$kXNF@>e=`TO;cSOPF}4
zpVmrOoc%WR39sGe^tmmbZ{iWGb##BV(f3!ZYHK2*=5tMoEMa14FD1@@2E^!|r-xnd
z>eTICSru5q#Cx5!R=U<6H0gqHn@>)f`_!Nn1twVQs;+8d<wdYDXtEMR2d*fvgo)kv
zQsV6TAX*H&ENnA!|8B=h&cG5TINAllcO$L|Z`<auxhq$W_XyT{u7%pz^CLvK^R6Ep
z*7@_$xyPS9y1)`9I3COQk&V12l+_@3?A!4k!CEL|?jnM_jLZ>|!<AL`i9?)g%zZ~c
z?ReM%+_6YxiwTz4XB3S<gi}H?GDk=bmtg{B)B0b_VeT`S)!V=Z6D&y*pp}q}%-N6}
zF2e-MrnTVr+ntTOCg6=<CRmarKr0~`nX@4|T*w5<rq!(LSZ8BgUD#lPB}oFb5|WWQ
z8<N9?OrUI93kr8T8|U7QcWaqoNs<7qgk)sShU9P|6DXV3+<udz@qi5`Sdt__S8oGC
zGBRgFa=4HQluhfsUmtNc8ZO0K#Z0gyNq|;DGO`S2yX0^o6DXTjy{^wX8+YFi8%(ey
zNq|;DGBRgF*4mH>luhf;Ei;{s23Nxd6D&y*pp}q}%w-vp!-Y(sY+5)MSFeQ)CRmar
zKo1%KLUOobl*45<%=jxr4)^4wIk`Q**b<G$oZR7i{_Xxg$oaYCaK$Kx%dmur-ktt-
zwEDT^aK$Kx^9a_e@vPeT=`Z-X<Z#6(hbv<V6WhoS)@VEM$rs7tiWqar;XH!1P}Uq3
zgye9@kORr#LhdV+t$*^{yz6@R;6dms$>A!Z94=%D6E&*68;?y8NDfyK<!~OsTEBd!
zHZHv;nk9uOhYMN4#BU2ea5i)%N)A_uayXA*tuciUTs!WX3>%We6`~w2WC;^T-t>_p
zzJ3^l<Zy*3hYMN4M5p?nyIQFaN)A_uayXA*t?7S!=4?#*7&at_bA;q@AxoI};{U#M
z#OR+uNDfzwa=4HsO!S`mt*ezrAIag0Q4Z%3tkp07t+Vk)Tf{5L;T$13T*wk8THo-4
zBMv(Tgye9=D2EGK!bB#w%GFBauH<mVD2MY1*7{eoRnEpA_riwcaE_21E@TN4qfT1m
zhy&eccqNA`Mmb!_5+;6Lu+G&=R~*UVict>d5v(<M;yP#Jt@>EiB!_c^<ZvNNm^k9?
zjgFXo5(vrRict<1vV@7u_P@JY=~^o}TrtYwGEA`68~@$pY#ekSY)B602+83xEMcPU
zls_C%@hb?);fhfXmthGL9PL~VSB!Evk6^8VPj7KHes`IS<Z#6(hs&^p3694uhjS55
zayXA*EtGZNjwl+%#60%3+eEPsJ6@C#;ZU~d8t<Jg?pCmb35&tHKkp-}!RAgQyN!??
zz11D3XI3j@lRgndtHI&tv?#EI30qh6)PU9xk6<mXZQNIR<h#}<s0rJ!UXOEX8;=4@
znBew#W9|{GWwR&V8`!)mu!ISlW4dFZx$6<EWpi40EaV>rmM~#{6YrzU2a7CW!u(Np
zcjV_D!CL13y1S!TQe+7e7M0>Xr^TxxOPH|Or8{AYi5|gP7AtipOmVl!5+*Ey$NO`O
z?M0R_VR2s1ENT7l2-dQ7MNbWAjViK)30v*rvkY4Yi!5Qn)<ivFp|#c{Sj*O6Jz=5s
zyvPzJEHjADeJp1vvV;lCAM`Ye@)D0=Ez4K*Gzu9Ra=70lU$iU?XOouCp=_Cxo{J*u
zLq>*^JC-nExt*Te;q0~l(YMaQsTvck#Wj?Zq6RNiG#vOu_udVL6j{QA<#u{<M>(8F
zu$JF)%Jf~!HR@~2HMWn+*`6Uj5w_h#ktN)3woiypoo$cf5v*l<pZH`uCRmarP(vkX
z=T&6Fc16&#JzRW3Z@ar9OOga^C_y_&kFebxv}`XL-!#}RwaAhr0UJutPS_)CmkKT0
zQ^z+Z&IWEwSdt`QLkZf^dxY(_p=D<S@y(C3ftw$eBnjA1f=(tp!cGmKWoI1m4VJTk
z8!VP23D{7APFM;|*y#tf?5rlfiE}n^6UUMyq2m$V_BjIggG|^d4xVdgPVtRmOt2(L
zz=jfZ;#I+fokl^+&d&6vfeDr*3D`*8O^El}9Sioada{XAHM`}A_s(|zQRYiZgx!Vc
z{#<gnFv{UFc7}-4Gdmr`d4Nwy4(D!VB!|nego)MB&5xcM&^?Yvu$Et2I<w5!*(7Sh
zHth5>&Z+HOG{X`mxP9K)t4FYwo#MuO13TZ%u!IRa>(w0#ogsS!YuVYd?pWxYI>Qns
z?EE_3N7-3;$Py;(TwHf|bl&a}tYzo$y1Sz@{g5S0*zG{P=d^o+kR?pm9fIzJ>2AU!
zSj+A#bSF&rA0bPau$z>4e{OdyAxoIB`xZSlpnDvTU@g1f(NhDuD+*b{gxxyDXBl=M
z6|#g0yPMJz7P|BD2-dQ@Fg;<Rd$o`yOxO)weC}g+cOgrduzNf`jiUQOk6<mkH`LQ8
z+>A;JmzNw);;-I@>e-~;tD<Z-n0hXX+t(<E3w=q6up3i7xx?9Ol*4%hYjF)-4p$cC
za3M>Wusc>gxud&Ok6<mo<<X6Mfb(6uMYfh>1wh&E?&A|-m+yk`C8d6|`}+9Qxqu8A
z=hRHFmc4@zpKQkjOOga?s6_Mzggb9%!ro4Rmc2_6pU^uSIH6}rl7I~*qBl7L+#4`q
zZ&^Ug-U*3s8j5H+2$m!X*ia&RBPGE72NU+T2(;|omiWfR*#N<kBmo;rL~qsvxW{3_
z-g<$Sy`vM~{5TsRSdt`QLy71Op#b+$OxW8y(6V=p;u|by0|ZNw1Z*e~z3CL-UX2NR
z3kh2G&QyF8=WKvrNs`d<h;I8Ff%`!w>}@JM*WUe#ZxmyKB}oD{l)(EKm?gO9WWwGG
zQ!V~JTPE!7He_K*0ygmX_+~V3cd3xzoo&kiQNH`KTinTAW*Xi}r99Eyz8b+=DC6%+
zoTPWD`3mVPmN1c>cfGT5Q;!O<5fMR>U@eqkLy5ihE;WCkj37&xxS{S<&c>Smz(zy_
zNrJUdh7Bd6{YM@%ktIxgbjO9x#@f>gVuN-p9>H2D!-f*kK1zPMpjF5cCT_U(bZ4XG
zhp<6AFOOg?lwm`O!}TsTzgi*#OPCnn<EUsniee)of+WFODC>BDcvJ6E^H)iPV+j)%
z@6yfLxN1BRL6TrClwm`OXn&qZq-F^dKi{#hv+>Ik*q|M~N3a&ku%SeBGn&U5#S$j!
zY`>$nV;yYpT`Ci-g|cghBck&Xybl+$gbBQ*i*pqHUIRK|@d(yJ88%Wx(IohW1tU;4
zdr#HHcgm6tk6<mUtrFDoB1@RCerwwfHmV|6%lc3W8o?q<n6UAGY9MS>MX;959wnl=
zi<wwt2@^JtADRyvRS~RZUZ4bdRFNf2m_Kgbf2i1~ieN4CW+f;x6j{QA#g*1iz(!RB
zYgtrMf+AdzB}`a+-2b3k#YR;GYgu$vf+BT+B}`bHe`r2zR7J3strAMmic??-6SiJ`
zehxl8P!+*iw%RE{D`y2um?*8g_~c7f1Z$xTKi6+6qzpi^asQj-5kH{SXM4>V;#ygj
z;SsEbGHk>xcZ96Y1(q<;pt;(Jd$&@8wNQqQcmy3Gt8;-ROuW}wZN#&rQi8QmhK+b8
zIs&JIEMelEerhA0?UfR&g)(f!9_0v}a<YVpjT6*H?6s8=tc5ac#F4=fvN{)8!bJTK
zY&;OJB$iZ4uolWX9#MpI1Y#mfn7FfPBlnhG97QW7SPNy?h$FS_yoxMgVqrhE5w8Z7
z60C(XY{V;$?I4RRVd94uqIS4-P}ZnQ3D!c{wZm3U+X)w0!UVoaOZ^eOOS^54@U?bu
zHn38AL<lWd*OgwMi?Z3f%CZcrl}E6a)m8~=xtvUB3n5{``Yq0utgk$RwXE0UjLb$*
zPA1d_Buv=&$5~&c1Z&ysi8D)^i6Kjvuz7q_k0=+dlwd9M0wu_!LY6RL{upQB&IWR7
zCRoe7InMMQfxQ7sn6S7K?<OiGSj(bPykl_$_BbqI!s27RE2@-WEsL)4&dU+ld9j2E
zi}UgBu2O=vY?X+2kdD9(k|j*odKK?dD<xRVR=ap7><H|gS;B<v!m*Eb>v^SwucdJ}
zCc@|pK)iRyC}tox*fEL*!)15h*p=h;yi$U-P)78L*K<c;J!c6Mzka7S;`O{zg0)bF
zjd(qG1lDtwFwt(I+KAWlN(t6N88+he+!0vMS;9o;scIu$&nqQZ3uV}d*K<c;J!c6M
zwJ%W{@p@h<!CEN8M!cRo0_!<Tm{{A^#v@wKD<xP9WgU-bJ$D4wbCxi1)epL^#Oryb
z1Z$xT8}WLc!Q9o)tCb{7beXC);`O{zg0)bFjd(qG1m1vP2@}nZi`rr9d8Gtvq3qh>
zi0Br;y~)86CTtDX)wwFd*HRlXfz=r|4Q{s$>yYqXea*UMnNpU)@0ai{p0!XewIf>3
zah6eJ2@?l?^P;m6_ih0rm?T&W<<fY_ZW{#7WQr_dqQk$&Xgh3w?rbCp)<W5}!x6IE
zF2V-pE=!nrr{0OqM!Y`<;db;)uolX&5%15P4fr5SnAmIMPR>T`wa!M8U@eqkBaRHt
z24V?In7HDu`DGaMIQlpnNrJUdhK)GFIU9(HEMa0~mvfwrIEp$ONrJUdhK)E<I~$1Y
zEMelf>lXGvJL1*A*+>$sg|dzZcJ#8_b~dm^v4n|fufEeAHsV#y*+>$sg)(f!E2py|
z>v;uBn7}N8jr4At313TotyOHKh%#uYM8E4npF1yS_R?7f6Rc&n)0qrQn6Q3JXG=`5
zmi2l%BV!2@HvZ|Xj|tYY*^|yJS;B<P<8=1Q1Z$ZWq%&leFk$|f&cc~sE%WAdrq2>4
zEUu(?6HKs{MWytPg(XZ_d`$0(m|!i7mFb-qOPH`YpWfXu!CJOTq<4@kVZzp{^e&YN
z*0R-330gTrmM~%KuI{O;B3R4T;Fxg!t#1zKN^kpf_&Lg!Kg6}Flwd8(KH`>JCL{Of
zY6B7`EDwr%w^D+&EQ^Xq&=I&}VF?qK&&9K(Qi8QCPmE_`h{z`Ex!j*e?T|YmCM++F
zXM3dtYgtwsdz2%v+hz$9mS4wSTPeX>mYv6u!4cS>vxEuTC&baGQi8Q?mk~!eM__->
z5+-cF6GzcX3D&aRQXHurf&Dp4n6Q0Yyc$$Wu$Jxm;uXgc*q^h63EO|ht6HT5YuWBK
zUO641_vgC%frN?DK00}~?LW(Q+t9LIILfcdXWV7#<{y?%I~~7wo$_a&{3D!{smP&>
zwH@VWo~Z50m$$=x?Vi_M?}*0R4{+}e+NT=%J;JyCs#CuCxv#=K-6sy0v>O~Ax^chm
z8;>2EVF?po{8Fd9S*I1zt^TVoUm5;UqkfOapPQax2@{Jxu2X(xvv0$je#CnKC+nxM
z^UZ%8pJ7RoK%0~}r^h9(9j8rv&m%ya)|E5slvfP<F?@d%zKeC3e8zoM|DoM?y>dl{
zB}|+(M(GiIp?7~8bFLe~u`4!s1Z$z(VZrK9iIMVIeZ-Q7<#S#<20S)Qi{>7^!Ylf1
z-{a)7b_-d;#FwYnDgW)G_2Kn1QL76(pX_X0|3W>FU@gB^<JQy&KRd5;kDtFkHEh}h
zzjszEyW+Qkd{3s9JKs}C%#v&VYVK@oGxX??=TDO8@qG2H&Z}r92AGLVpln*)rXV<0
zzBK}U)n7h8$OLML5kw8Swm~pWzWqXg{QrKu$ZH1^O9t0+bo)^_NsWjgNw5~m=n*BR
zZhxz@apeQohAd&?x+VGxtGlm&jfe=61Z$xT8%kWO-;t8X=WAKQ1b&?jy`ZahM7U4n
zGQnE<dv5kCuGI3P^-tHDLvz-q9|q@L88%S%+EKLDnilGgvf19U>(&U?vNkC}?I^N@
z32TR*OjJd%mi2-XG!u*FgSWnMtDE7NiO(+?8qao=gMemx(PpA)8DTU3o6A5vBHv%~
z$lVLNUvSZh9>H4N>p@VlwuYPS7p^?j8;>M`p2j$NbJruxCz7KX1T`f3+*W;D_e15I
zLM)ct``NIZMTUoa4~tg@^oV@x#R*5cTJ3Sc?p|Ld39KthRMorY+sU5x;%>oW?L$p&
z%UKNWHF$WAYwN|`0!xwv;x5|f#YC^=76+5P5U+!Qtb^V+G}#LGyL@Aktv>p_AG8iS
z0-gg26SmsvClr2>?=ShT$Hm=0|6#mGuom}75KI|-r5lgy8b9szRg%EUi9VFiRO>nz
z$U5i|c&=%2zqy>Dh`1|}y1067y{wHb%4ictu+M~@Tv`1?at24BulQ4+{Q1#^je{(5
z2J~AHNM9ABoT0!HCid8Nn=En$?JLO{ic!u`U<ngPUA=AA+T?NuS1ZXG3M@$yXj9x*
zjzC{AfwF0>nZ8{XIRj>;o4ds*XDG0QiGzFBaJ0@u$r+pt$r(I?wNNh2UC9|h<Rxct
z<6&dKW5cw|8H!QPP-F=cjZUbYMa}@9cmCmQNY3C9tmW5Aa)x4*GZZIH-A%sVT;tOH
zlbX9S;-EiEB#Js4k~0)pk|Zpm#xoJwt4Dw~EpC&`8C>s5&fpQKA^Ht5k!$OsXaTcb
zG61g~OdNF2eva04P*%=L3D!c{)<m~*IzlplB1@PUxnFx{BVIWxC0Gk(*oaq7oX{f!
zD6)hJe9t<1AznEvC0I+pnO%P$$?L1o`UhE<wFw!LwJFY)tQ{dsn6TQ$*;1thYgwD(
zY{}XYvV;k1N1QEHO0bsof)cW-xp{@`)#4!bPBs&f<Jz3od^eiy0WxHkFkv$v`L)X#
zic!ws5v;|%?s5iKE6EwW@kkPwB^alwN6>sCIhrnKC`LI$Xt4x)8H)_qb8wHioWa#f
zat5!jl7#I=V?TF$1AdnIcCx3vxSO$9i+!KPVC?9)wk~IIwZdMFB}t;RSCf5|Be0KR
z0%g<UHo2U^5!gFpm9f3Et#H^c+v<bQ<9X|#BjBBoFk!2mz7a1uLov!3Jc6~jM_kU}
zY9%>?*H=lRwA+@P!4cRy^RrMkE$+7<_|Kf9LPVbjs_!iSU(<b`<q`62dnn^P5#`PU
zYPs@lh1&A>stDFX8GWe4@YUxy8@ukdDZ>&bRt&H0Z0s<nrr4;8U@eqkLy6wk4s<ql
ztUfct5+-V#QpeeNZQS-^qbh>6P=*a9#%yzgvvE}KGczn<qSr@iqh_D&#70#FYoQDq
zO8k71exqEk759{}goz;f9BhqXTd`3U;cMxqXqEU)?jB{x^WEiby#{~ucHa+Gar1;M
z${2H$5C7(1SAKf_V_EsG0VRSY!CEMz9ZEbZcc`#&mD~@qgo$e3@9b=R`oEcCBO-z%
z!CEN8h7u>pT`+8%@XP!HOPIKGL|td2?^O%MMnnWjg0)bF4JE?pesK4?0}Cu+;<HxO
zoQ*b{my3;v2$BSAp$r>JY}U`?<hOreS_Mm(*e3e^nvTI5u@MnLl3*>AVM7V&r{H(_
z9KeAu;FE__az8iwzwES0&1L>{@yZ7-y&}7MQVaR})`*hUlw7F{qN{wK;l{f7o;a3t
zA+0XC?{>O0yYil$BO6r_C9Nq5;tIJlSnR&<jwSruF1fkCoS(gF=q{0ss)&--lmszM
z?hKxEpEY3#KetQn($QyTpFDHd$VOE}Noz`iXe{4v*xY?)h9&&mF1hbpoRDp`$8M30
zs)&--lmv00JbzpFJ&G*h=XS|$Tyc1I_kWp<s)&--lmzjN^wUu3FN}Ffi=W#i_uxTY
zvV)G<J!(f)L`iE(f|w-ZeVzL(7EAcKU2<Lew$3hn!E97Tl(eQKh#vI@W)5_pDPsvg
zw@dEK+0C=dSDKBgh?3Tn1Tptn@xM-p@hsuzcF7^@s}bxG^;K0wNoxub8@B7{V&Yo)
z{~tg5!bN~ZYtIc)Mr=o!V}1}Y!IC6lD?<?c{dXw!4}!l=Y%R97<Xj}nZj-hAq0=c3
zxH1SWZxdw0o#w6Ru*DIYSwOP#r}a5#E#3B3c_Kflx)89jDPe;Nl+g=HqgKOq|7m8j
zR;=~amfsxl<;*$q^z9=X8^s1oP`<3kxGc2h{kkbP>e|uSLmDm;qKy#Cdykv(o)9d#
z<gwp#U-!B_`^}tXAwMYyzLi>?FrjnDT~6|CFfl&2Id|pvL$g18wnA+DCB%&rG97{h
z!CIXbZq6P3{0-UJ7yc~7*;1=_uHAFi-BK%-jOhGF?t<)<**-_DPt<Cz*x2KclR6!f
zu))NKcm9!UaPNiLU2fbgHvT8Xj;r46xLbl?t$UXIk-PiVv$B`0`b&rtrB(w@9XV^7
z)QTnNuKOc*UB!vnN0tOxzpplkjRn0cI@V6uU;?uQziQRS&9~ao2(C+vps&UADw^$q
z_($vqryN(W+;Sh3&2P$Y!ur7kOOgcUu@dATA!Z-^<F{XSF1NXhGFpzmpWO~?E&QX{
z^4?d(Kio)}gbB{bV;{`RY?r<+<?7~xn!{_$>-^kQY|w0XHZa3sooixqdhC<P3^3al
z{x)dF60yM&CTt#O%0ZkjM2(5{W{nZT=F%%?H7mDS`JXAxJbUsfIvMjH^Lt~qdo5?e
zW`3(5n~9BYgt+PET`?0qg0<4MTK3Y-v&KrTY%aB5*R<Sb<s&tdwfaJA)Z6ev$GsCa
zn6R1Ou`O!#q7YLjbnnzRL9iD0NDyG|e)v+hlg!=32$n{Tds+#^L=e8DMA*#NF<&LM
zI(zNxjyoi3#ai4WL2&c)`t4$WNUnI^IgMO&##)3jW+lqIeqPI!JA8_DuquMJP=<df
z@rvZqXh$bmYgxj?L8G^IHlDp0HmV|63uV|);yZm`G`L7|29_{!OY7g<`q=&@<UUmq
ztc5acC^10a7Y&|~+=nGhoPPXI&c;bIktbF~uolX&p~R8VC#rsy_e)s91V<%#r?v`$
zwNQo)jaShK=4H%_HqOE8pLVwKN7=^dv;IwG|3G8z5v*mSsYEn_c^UH}OPH{68rQFh
z>>p^%J%Y7tG?j=(FfU_XWC;^CPA6Udq}ZS__XyUq(NrQD!Mu!lktIynI9>Am4&vD~
z<{rUXHkwLABbb*lFS3LQ8$slA-k5s?YuWfK(Pz{mcal2xwOhg(jWmxc3;fjpF~(Mj
zAUJ5`qKdKy>&zN2M4{JWmq*R4)~tNbX-i%C^AXL;H)NLP9=oG)w%Rbn#GQp0HDUa0
z5ViOE)oH!+Y4dWnH?GaExy@(P&bD5T_2c6aiz@!Ur+&w~gkT91v)}qPw|?C&+0Ryh
zxI&1!Esvjdw-B3_t<JSL^xEuo70t`X9k?d<bKeWI_rBNMtvIE2w3n7QdcSAKJ79yf
zVDHP1PIfi%Ti#yU@yNQenP>+~m_V(*Eju)-)g&Q)ST<?KxCFsk+@>H{J7iJCUOPV3
z>1iQY!o;Lazsg=+?k2xQ%m0veynfjEvqmQf*7EzRx74c5;;&~UN03MDnuh;%Hr~!+
z1Tp4!w5a9?mN0SGvX62TZf=$R<Yo~23xU`U8%(ek{*D|@Z6pbkFoE)6GrC4Lt`!?U
z-!W$<dY7NYT920h*X5!;4@IrsmRYjL#4BFLykZFxXj6yBj*jLoX5#b-b7v$8)>^ad
zzb?Oitv763B}DUU-tT~!$Py;ruDvX`>W#Cr2j2l=z7YSueE3Y*V1l(?Sp2@*8>~MC
zL=$QGec$}Y%|w<ku~)~BbJa!;%r=!=D+p$bjmP^oeFZj{V69JEeCYN#k6j32hS(Uq
z;G3Cu3c(U4Zk+i^ZuJefWRH9S#6Du<-p9vvx+g)fR;Rfi<%YDlJKOIj5aVR-?s9vv
z!x$l0!o<jF%X00e-JgBtUJ!kyR-aycUq_5NOPH9KU!FT^;%(W^3qUj!Vr1w4cEn6%
zg0((=<CEO5FCWZ)=h`vl_C*!DzPwwf2|}=hiI+!xo+~~yI@|p#*k~a(7GJZXJ!~++
zTC*E|mOFR$!`X|LfM_c%U;4(^GZ1}P!o=Bce3_fu;m+*6TR`*^8=nn2+_jtu)|zz7
z7rC(w9?K5?8N~TQwBL7?BjkKIcjzaNWp|Uaz5};><;us@ZC?KD4d3L-9vz?E)CIAm
zwh(jvxFHqcjy>)-H)^l9Zc)zBH3;?-;`n;II)Wuk+;!mwH-e`&!X9Ufw0y)V2X;cd
zVuH1vICxdA>0P&GPnwQebr2gz^*P;*Ah(cP&TR^U%Vj2x+_G&)_#jJ|xT5Kb+-Kd!
zXRm4j8=XhXiZiI)%uxw~wfw$nDzzH<f7iHLvE<fIzRNAYWL&mqUp%+e>p^g|%&U11
zwVX9kY_NohoA&%MH)HbH>`j9}|0M1BZQPA6GBCkfZ{}CKG2e9#i2bB@n|Gh?RyCF|
z@z!B0b3=|8nSE;<h#u08y-)tG1LiIhtTpe~HE!;n_%VpVQme}kzIrBlmnBU2BY2qD
zIBC{?Zv9|_wZ<O0&iUZx4Y1Kl#^aeUj&ZYuB~0*)k<Y$9Kdns8!=-0~y!F+V&lkr%
z-Dc4hS!-X1MVDngLLeO}5Uge8245_cCv}t)?TkAa4Du|oGM;Pg`*_(UVuOglwD2s}
zvU1<w-Vz)8{W3puhCAU5@+`43o@+gF#-A674I%>5!n0V*%9oeFAvT7~N$vgaq&CR2
z#L9TC_3q6_Tqrh(2uuslVl68_va~{M$Q@BA_eD|)@+`43o@-HJ%j*}24I%>5!n0V*
z%G2JND^Ff2&+nz*HYF|B6S~1ypD$xjI;}H8ZS+0(i15_+_6Ykmyt6w?n6TVVPX~V-
z(k*Oz_CaVzzyxdA-?diwEQ5V3P<$G3VgIb{`=>r~UR=hRoP1}^s)1q8+g{F`bpAKp
zO$!n`{lNJiKPd>B-gHrT^XW@v?;<%?bZ*#6Y*a?*d7|8_g>t9n+QEdCp=G^*J`938
zSDqdIJnN6lF&{7P&Jrf<gas#_L2&T$lfva)>pL4vu$KK@Pg3Era(g9v$sn*(l|q~I
z#JZmEU9oMctY>|fzB?p*{qQ}@Zrf?Q9;O9}onPQQ(SK5*>n&lO*=tfZDkJpFvV-{e
za(8>>*UFv?EgL6{W)K|y=M7<vYkFmNz2NtF1R-I<&VckJwSWJ?;o{As-3aotSj+yd
zv*eVQ%EL}wTZIE(?C_fP;?h?emD}w5>(NGuJr2)Zo3A+QW5UW<+kGEoiIri)d~@QM
zMq43R%gUMoa4cbomGNAQF<t%-HmV|6%gVZba7<*0mGNAQmE%u<jj9ONva+s&9NSr9
zWjxnn{^{*uqbh>6tgP!ft!nZ50f}kpb9L=HqcLn$Mc4|bTAY`3e&LAl*+celUdyw@
z<`_<at&I8R`MIo78fzi3G6?f|JrVAB^y%SquT~E)>(|$tyR2n#<$-r#W7Qewgx9s*
z?EIrLEt~@T1jWQWORNmS;v-I=gW%fRFAKl=e12x$qnE#CTCmPq=7ZmSgj$_=!2gA<
zJH6y;Rhbq}xqX8CJkJs<gD{`hGvr-XUl(@Ta7AX^qeEUZEm&tQi!0}Sj#^#6WJtKv
zzxQwv&SIjT{Av{a{>w(?7VU82E#L7gakt^rX=Q7^8~&OvDG|O6j-pJkmX&dm9t6c5
zZwzO@eT3^PmRK2e=Qah=zr34?dyW{D`)1<R;mpYm%e$RD(v>@()v$c-i$7%X_sa+D
zAU5=$5~B{C<FvZfygT>M1FyPrS&MseKfXKLm52QLOwK1*QW^0;{d>1U7!9q_@*TXW
z)d^oFiL&#DJIOnHypZeirIx?`?KyewSoilq112VHu!M;{N8IL!FTQ<tD+FtO-1l}z
zq*|Wm`i^*Orqk*%V!}V{D<&R#V1}bRZ<}m~^$)DGmf3!1kK}l;go!=-zv66^9h0=d
z1Z!Chzr610L|?Il3A6XjpHKNj{>LBBbk;G>ZMQkYl`+ot_f+o&*6-g>Yfx_E@oK9E
z<@<bos`i!4V{azro44HJW_5CgpLt&32zY@{u!Mc$ln=IbM3>hiA}<LzJSu<6m{a0s
zozdc?Sc|>Ovk|a_iOG|Wcl3vg6SeXP*5VraHdw+$)03)KVS@?QO0^t~cCp0910&V>
z=n?L@I{W^K4>DmrlAc%WwX9`vES^_+tCdBZul}5rwb=FZ;Zw8gPp)t^>=5L$eqXVK
ziQ5Vq`NsVCNEHO4rTHUfrTNXFwGty3M+QjDS1>Ehb~^5|gbDMg)Z7i2U@h~<c<xH`
zbp%^>{n_~kqG*GCR=YBysEvO*in4@>SKnIW=yViig0=3dvEC6WKhJYCFyD4jG>RB0
zBH)<8g!yJAQIwv=T4p;PMOngxd2l+4GQnC_!}M%t2@_^7p6&4nnk2cN+mkTIL|F#h
z#+)VQQP47fOwHYZ3Dz?I$IN#&V8+En(?UFNv-}+AcbHdZ52NW5EMda@JRU)7N8Yq%
zJy^f|lrd*J8(0l2GbpcB->+4`5+-c+q}mbi+_gA}ab~~q+7YmX30qg<c359|1Z&l)
zx6=7X&(mJ?`zl}w6Smr=de<XZtKKKSIUDKx%6uEWYi&Z0_Fw+FBi^io3|ar_nA><D
zPqf}eo@lui{_YV0OPH|nNacxnCRod|0oe0w<VV+<>t@Dwm)9$|c#d{(tn>+vmT&C&
zvZJvgS4ntrmkC?D((AeZEL|<3#cQxvtH76(h=+=!T@BN*oe9=5k4mi{dG1B-UGwwQ
zc*GeQBurR26{++5EY{+P;kTS6OxTP`uQ*Jwmd#MzC#V%&2d(9ZA2!D@^EvYQwPFbq
z9Al~`Sj$$4blhbL6V?mqcxAqgcy7Lp=ki?eYsC^KY;{iCV1l)(j0^!wn6PXBz3$hF
z3D)AM<PmxHZOh>>g1)CIqhrnzCM<tU*NO?&;tbHMRbZ`!A6V}qv*2~bCs@LSjcht+
zV1l)5Wk}}?7MGCSS!BSfW^)YLpkFJNFk!JIy{a+6TAiEgUOm04v4n}Lz1D~!i=NDy
zpCjux0$IOnN8WNDn<dETZDjy$BfIsz0TXZRsq4zNOP*C5V#uFYcou6}dC-766TQpp
ztF7%=uh<J*J7OCwVdCKFKe^TU!^QZFnf}vSF~M3^esa=Fey#E*K?{u@G;dVa{+@0J
zOPH{7I%lYifR?rCqbJ7swF-<ttxO9eXf{y8%3BTz6V~hL-5o!RwJiF?^GXb9@0zcz
zKkLq{Wqn^9a!2-|`@VPMk)Br;!_RL!F>C7wo@*-+=CR)no4fE%p05_W(yJOvn5cRt
zGQnCF?b2&4OPDZUNsk~CtYuL&l`{k^VZwUkgfGV@W(gClW$lY|(Y%eIX`y$`24WQV
zn?D{bVZwSL?NLmymi>L}X8=rCIqm2CEY`9bBCh!Duvm+A!eaXuFXObXic=ivvy!AT
z;>k&gvpz9cBCHH8%a&8;40&IoG!wB6sg3#|6IO<n<@2fid7dSe5!wsdTWW&|D?`gp
zTheQ-t>M^VSvG)d*&<PT9b^d;mItNwINt7#wJcVqW?~#gAz{KIT<jmxcx^d9i?u9P
zreeF7^)X=)HSM+hEY`9fNyie7yBupR4_eV{eAbO$-r5n58lrP_#*V0Mev^*WEMdaV
z<kB`c7vUU*W4^1E{Ezl7OPH`MD!oQA!CJhQ_%?WDv0WHeAAXV}@|D$!3EN+d`SI?o
zZ-bx3T6Ve<_myDUa+?`g`)np+?X$VC_4S+y^A)to)hcf`_*tyQGsY3}KUyo6Fk#-D
zZaEXIRrO4?lRL~l+fAZ>c)t0yVhIzrPmF67x18swolQfFpH#ICCTvBGdpGVYeim!l
zIv-~;ajn{3*w39=z@Kflt8eSxAe~v-tVUe2*^c;OnSMH6v4jcVp0-`boC(%y`QLM0
zZPW3JB}{Pp{NA;Ag>@p%6J`D2J)B46SyCAhuY-bVJD9LCwColrz1Fg%G9tE-Hycb?
z8Cra1?YDy^l@aN+mI*6E%lsz2*4hXn6SlEIK4)W-UTayxgpJ_V313U+ZhEbi_iWt!
zfrN?4lhg}Rg!FQW@U`^s>8#HPNSLs4iimA6fwJ{TI!|N?KiArnBJxbImign>Pw1Jj
zvDrGoS~eGO2IS4eAoe230Bp8bTQYVldo_;jOxQdI?b~32wK!J#1WTBRXTH?7YJ#=Q
zKd`R&1h2xD^+StSZJ%HX6LHp`sudHgm0F|3kj5*PFk$<Ibni03THJ?zJA8@mCh%O#
z`qMU;U@guceH%98kjdCgMBZjzfKv*eU<ng8^S4g;S{fPBr%@IeAYsBhI7Q@{@U_%N
zdUZAe5+<zt&j@H)4K*9Mf4}pJ-@Wxq=E4m_<egOgOx)9bhh{(BesON;!L_r<)t7wm
zZtlGU)`Xh3*ZielaY}KGdpC*+UrV3Vtv%k@s*Hey2`lHDHxc5|sYexix5oE5$@f%6
z)*-PnYH~owcXBKDe=n+4RRn8U`N~>5iH+j=1B)N5=;my&#LBR-Aos7__;oKvHmV|6
z%gWF1zN6UK_mh7Y)~vtS*%(pd?c8}MPjb)dJMqn2?ad>+@``16D{RR@^9oPzctsd|
z|3z2Rf~4@_{M>Cz$At@;G%n{S1;Kq?{#RIZ(FG|Rl@S%^H5MBaF0NNxc!7RXGe679
z(6V;um}f5Ct~j*m8R6K+Kkv#CChlmvAotV-kA>lDu(7H`lVZDLj&-$Sg0<}L+E?#X
zf2N|@&idU^)Bi5!*37-Z^$$l0E9)sv<8c3qmlnv|fCIkj>Pen0<Yt_EO*rB59m@Gh
zL2%`cL80%TH@jMSl1hj_Z^d}*(CU`Lz(21|5k^DH#!35X{<xD0LoT}^T=~J5@d!e~
z#MnM><f^?lG`#f**qHI+J%!9}*Ek#eEY`BW>nzC~JRq!A_bd2dzGM4G-FGogJO8b$
zmFLZ>RX%I@<Jrsi53;*Aelr^cOt7RfVpV`|NjqxKGsDlH+ZMITGht<D)$ckzJ9pRB
z;lIu<iVY%y%CxTQn<OTLy~BV1x{I^H&$2RzM`k^r{dW4|u+6@8q*g=(rUmP)W##r?
zzbdtQ?tufsv3vD!Hdtb1Ja_Odv$Ct#yb$iQ2hQ|~2uuslVl6A5)BGi|acAec;i(6m
z;%u<Q%6M+=(~H?^#rwniy5n?^h`_Y)EY`B}qO$2?qyOe5nODx%Z<c3?mGRu;>%5bF
zc;<-k^(&E)5fPXcp2b>L9zGWLI33=;F;lkpb*>#Ou`-@Jpw9={-2FF%d(Op;A`yXU
z;aRL@<$=BK6&pj(f2!=N-SyK>EU_}4Yo`f%;zdMYT6h*~S-EtU@sWH#N~7xdE}<#z
zbKANWmDVL&OLWEAVXxgf{3-;#D}`eeM>zjU-{sbH>|VWN_>B9$qLK|JI0nnSs`GM(
zhC(bAg00(%qw7-XN%HB;neV)^Qfl=_!Uhw56rKIifSCm$S|?i0THHQ~)IFb?SrlSl
zA-KMN#Nk>^9kR>JkA<k8u)ze!t{|8>Y-pz|rRCQo+QC{JALVWJwbN&vC^qgD8=izB
zwLc#7E*RD6VzF^^!bU)Zw@L)~hi}o*@5d>%(AUy$v(nk)6D0`~e0T3mkc|?-TI0vm
zpc&ds+5qm~QZt^_yx&0?-y5YXj?_QgtNKqJ(3Z;l9RBDN>qYb0ySM8If+dxCuzKw`
zqB&yO`yH!E?U<;{AJqpp3NdBdmd>kemBAWiD+AUgev*9tLx@Axl{<nZOmNIsqWz5P
z9KjNf+WaIXKIr~%$_5i0kKMN?g-2eyAVshi_qu$$jkE(JDF0uyx?{DpUcl<?kNI}e
ztII}jJL`W!@XWCBM;!DCjNr-pRPP8IEMdaNMkDnPLJaQMxzpc5u*Ak3v7Mjfw}T~2
zSj%-)<CZhQTGns6)-u5o8xO3`{G_UD#e~fT<PTL7ti|JmvD1AsO1PCdXTO~@*u~im
zjg|5Dp#wU(n^8yPnSdlo;FA`%S4-Pq0$OI<2s|DC@*$sJB+pAwE8cCF2$L{@vi;p@
z%8IG~u(yN+)_I?4e~(+9A|Oc;Xu0i#^IIjLWj2hkI^~OKxz=i;JJYqY^+<g7npZ{%
z?RTHBUN9m(9ym9&5wtSw<=TH=#h62qBw*W42h%o~fR>H95pl~y8!0<!Momz*cJLW8
zsJtU!JxN$!8Ic|jSho?hve)v|2%;THLT&3?FKHW0pm%M|`Lx!xqi8L}`<qsGl&wej
z?avZ{`X&jRJw}wq11BsXbjI;nkN!QL?IF4rR*X=IPw0Hpw~*2{m{8wV8)-ks*&AwQ
zCuvsZGdWk4y!&4lxBRm=Blv_3x~1{JI}Ff*b$g$|%J_TS@_5XRfFwzv<>s|%8%#jU
zo@9i!LTgugpTX*`o~k`!Uh5Ouj)~q|51{SuuH_iP=%4nx&Nv-GD}%rcg`yk5ydp}d
z#3#^l^V;;7Gof1gBqQ|cYD-%P@3gwBr<UH)aN1FgV5=ly!ul=k=hpAAZX;-AujQ#R
zM>~>4<$i89m_YB^-_w3>?SOY$-PKdIN6c&EzLMINBurQ@C^1QXhaSvE_dV6xSIOtv
zxwyXN&4e#0*~8z_S4!L`-@OYP`^opiF~M4PzOV0vGr^K10UJteaNijn1Q*En!!d!f
zY1s{gekz3tmLv(#N>q=&Y2iEhemEvjHZ6PaK;Nfkf+a};v=Zk=-+Zx5z8{VWlugUt
zhS0a8nP5qh0IkFd{RWTVMEN#BCQvpldtXD}LuP^{NdmMIMg1m{pr?F~A`>W^mffrC
zEg2ImNfMxyh`vz;pYks-fwF1&w|z{oBuRkQ+rH?VVel#c0uv~kmffW29V8PhNfMxy
z*reZZ6D*hSh-U)jl9onPjfqUy{RbpT0<;qKqVMC-Z<jBv9~LFBW|(j4yJ}4M67_Q<
zU_*&M(YI^#AU}u1ycT8iO?_vZ36>-Y*ifRje3K4hNk8&)NX%<dHs91wA~C^|Bmo;r
z+!*=!RPu93%xh6L-_*}8F~O1~0UJtmi2QsD`8g!!wJ4i!>L*{AU`djI4JD#)>T$p9
zz=U}%w9Gg4y*?&bk|bb5348+$#sk0Xz=U}%w9Gg4JsBogk|bb5i8J+^lY-sJ&ml3d
zMcI5)-;-g2B}qcZ1Mlz3FFUw);FlekFt5dP%{TRakO`I~3D{7=ymm49IV9$_s-=Fe
z`7RUY=a3``*ib^(ars>``91n%E&?q?1OIJYCRk#*h!LRU2#4G!kC?~=%BE#+G{;di
zCRmarKr12Nx8w-<&ZPnqD4UkOPpzu~6D&y*pyL(C*}xjb1j?pm?~%o;T1>DcNq|;j
zsrWbgs-LX2OrUI9_THMV&P=c*Nq|;jfPO1*{(Z5<1j?pmZ_{a(!30Z^1n4-EaqU3v
z!vxBvW$*jN*-}ifBuRi)0%MK7!bmcKvT4~nu$uKT!IC5aT8W|c-1k%G+hC1~-oS+f
zWz({^EHry%f+a};v=Z<=v;&^S1j?qx8M*v6AQ3D{5}-9ZH?O^m{G4~DD4TC;Tw#JG
z=I2Jhh7$byI82z=Ld$$p<1P~{NfNN31oCzCm1N_wpF?6^i?aEqt_Do7BuT)A60+hr
z8(5>5Ft3G{`DVPT#RN-|1Z*fF-&*Gg`R2OV&ml3dMcI5)S7#<zk|bb53H(A6`bt*m
z*v}y`uSMB>Q?m>vSdt`kJn$_ylF2w5$bFbFuf=oCH{)z6CRmarU_*(<vW}x2=a8R6
zVqS}~`KD%lOt2(Lz=jf?^?T^^l8wiH4vBd!%I2Gzy)wa)Bmo;r>?G?r+JT&!3G-TL
znK$d13==F#60o5JWdO2I_fJ)zg_8oyKJ<N2CVYwRCX4{B1Z6TACM?T<mgPkH=}abA
zk|bb53ChSaOjx!AEz1V=vt&%LBuT)A5|mknOjy<jEz42$vt&%LBuT)A5|kl_Ojz~`
zEz7m_vt&%LBuT)A5|rtOOjs5UE!$=2H-#|4k|d$yfp2J{9ZSfB?I!SC+b!v*ewkoN
zl7I~*Xy+9&VY?z|*{)CDr)GjBNdh*MpdF-)hkm;lB(}Rl*><n`mNyeDNfNN31nq=F
zCTy3gTBUQwAYj5y?r_qWBw#~NAkAy#3?TM%J8y>;%I2H;W+oH9ME%?d&`QwBMC|8~
znAf6gzNw%2VS*(|0ydPO6PDP|Au+E-*?dz!$;t#vk_2oh!CuRRc`dZeH}&%$Ot2(L
zz=jfa-S4W&uZPM$oeA?=Xqj*7r&5?;Ns@pKC0a#i05!!H6XvzhGT+os*D%47B%$Mh
z&qqy+&NA+heL557wRo=irhYz(36>-Y*ieE_Qe!`d#Jm<|^G$s(oC%gB3D{6V_T}!}
z2P+Q~=C#m@ebc=c&IC)61Z?2b(m`<Rb9xs3mz>8j5qquEQa{&QWG2kdAxRRjp+uAc
z;8z|)%K#7oP=*%DmP=?{VS*(|!nMPFayH6j0(dVImSy0%mPKh4Wr8J10ydP0GO|E&
zxR43UmY`+Xpsof?up~*qM!e!6vkW8`4Vkd44_cO^>N*%@ua00zl7I~*q6`_of*LYm
z*(<axJJ;2j36>-Y*ia(M^aFgWH4~PFL(6s<nq@G-k|Y5eaVF#X3f~6JgzYAvWqY4E
zTZ##mBnjA1BHDQc@LnctR|GBF^=a0}1WS^Hjt9Q?BicdY7gjS&*zOL`wY_MZy}EXQ
zU`djI4JD$Ta3Fi<GA3-73N1T3)0;RZSdt`QLy1w(>2GZzmYAO>Z>nS8ba90VmYAP|
zj{VUQHFb{@WZBO}!dm8=8bz64Ns>T2l!#7P0(}2D6XvzhGT+qIfC-i)3D{6VRvb5i
zSfiLQuZ5QRrmllbup~*qh7xUc?;KQ<wU!C<T4<SX>gvn{OOga^C=opE&H#dg$<HA%
zuSMB>Gx}UA5iCg(un}i6vDY$TUJEVr%{W_%36>-Y*ia%mNeyHqV?T$)ycT8iP0jk4
zU`dkD@pwemTI|aa+wtw$Oqkc=x#pX3_8Jo`NfNN3gn6x;uEl;1iFqx`=FOUGGr^K1
z0UJu-*=Pqyeiw(|zp>B!#ixTY!IC5a8%jJM-JkC(eZ~aJre&Y))l*I;Sdt__$0w;S
zzrsi|fwF1Yr^(~f+L&NTk^mi_2#4q^oFOxTvT50;*W**?m|#hg0IkF^QBM86oRKks
zvT508>h<)T36>-Y&`PY1?#~aGn8F0gre)s^ptk@_up~)<R${uuLiE)o5*wL7*|hB2
z3-mUF36>-Y(D99lvw?`s1j?pm--Hq0%ESaqk_71Z=Eo7ZD`Em=)3R^ah;Nr-f+a};
zv=Ufj(N|bOnLydJ?9D^H4QGNSNdmMIdT$=&k&P$c<ufh&{Gir~36|Kqe0VPYZZ(W!
zqPtgPg0<|EnsM(IrQwcXNs@pKB~FOW+fR@)SSC<5E&D8~&JreAk|aQ<@70(<*|h9i
zO49dgEJ+feV~=tzhYvD=vT50;fn%?Y36>-Y(3RY)Mc>#9324)@PXnj#)mV}wKr8Xf
z8+zWpUSc8>D4Ujj+lEF_CRmarK*y2Vowp;lGl8;c+2^+7)gUHVk|aRKD~==F8a1Z$
zo#dcR%RVO_uWB*Dk|Y6IiCgKGj0u!Yi{F8j9X$~&NfMy-Ud_B#e!nL6bKH!X*P?8`
zskdZIup~*qM*3cj3G-TLnQx}=)mV}wU_*(MB0uj<eh!IwEz0JbdP~LxOOga^r0><3
zFt3G{`DXfFjU`C}Hk6Qj-FYptaVE@b-Mw1mn|e#eg!wrnNdh*M;9D{#%xj@#zL~yP
zV@Z<G@xZ;>1<}3Qv*hP^mU%78=9_v;#so`}1Z<@5)tE4^g_e19`d*DCNdh*MI6t~q
z>yBJB@^eVcYf(1e)LSwpSdt`QLkan{n+mLI@GK_GYoTS{thZ!Lup~*qMtl?JvT)e2
zyd4tD!cn$dTWcjNe@w6>NtD_lEzck?aeWp2f&-pqSvbm;YsbAC6D&y*rSXtcHAmns
zl?ltj@m$Nb<5?0DEJ+fup#<Ih#Cba;mW88ixwiTT6D&y*u%QIb+0j>WiXP|fkXROu
zvgO+9wM?)iNx+5@*!#l<VhIzLg+t47?Kt|x1WS?xY$$;<4A{U41rwHqL(6h)jiOAj
zBuT)A5^}2MY~Y;<CM*kwmgU;I8Zg0<B%$Mxd>@Vp%fj(o%eCWG&DBcI;R-BC60o6!
zW#Kna-VTXn;V4^nj&(N(m|#hgfQ=MUW&}>?P=*%DR$DzCBpYQcNfMyr6G&@$h6$?`
zw5$*HT$Jz6S&}4RBR)yBG0!kzy$day3-M`fOt2(Lz=jeu6GJ9!mO#tqw4ORM!IC5a
z8%mH5hD_LOhnD%Ko}M$ok|Y5eN>F47nJ}+~mPIAK1z>_DNkYdXd4JA?MISuZqHBDc
z;l=~E87xT>uo2&wSfus{i=xo7m>=KD!~{!{1Z*flYgEXDtp?Dt)lToDm|#hgfQ|SD
z%T~^i30u{mWoxkBhSOT>eNrz;z=jf02H@`1ECYZ9Wz(`;LTkkYOOiyX9Z@EO^*m(4
zvJ5=ea-z6*3s?<6up~*qMm&O!z`Yt1mMuZca=Unz!~{!{1Z*e~WtM^Dq9GHO^+C(B
zTJ;YmSdt`QLkYemW5TjmXj!hUUdseak_2qTk)ep*mGwMi!m@B^*`6VeJ~6?PBmo;r
z$eRO>z`Yt1wwr*K?R_+gGQpB00UJt0JFh_YY8fVMR|GBF_33KB1WS^Hjz{udjS1V`
z;kmXKjaN0-a@?!2BuT)A646dLz;C}YVY^gl+1Z)ik}<)OBmo;rTtfG1=I6K>Gp|KC
z_Dy$7#so`}1Z?Pg0643}yu$rC6S3FIbImvPmW&COBnj9^->WfUUJEVr&Gfw*OOga^
zD3Oou)gB-}hs3-VW%EtFC1ZjmNdh*~_i9X-*SdSPXn$VGy&6f91Z*hLEV?Dzk^J1<
zt3~H<D4TEUEg2ImF+Vo~Hq!TMOqka~%X~9^uf~!j0UJt0C#iv)y~chHiFqx`=9_x2
z#so`}gpS7}+4v0E-K#NSUW@0NZ>I0nSdt`QLkaU*tkO)F*Fwv@S#QahU`djI4J9lK
zmoxo1Z->OPaFi|A)><*ak|a@T2fy9Mgk|A)uI1V~9!#(#NtDJz&Rj#p65ORSVOcny
zYq_@05++!ZBw#}c&cd0nEF4;vYwK)hf+a};He!!*?SKz5VOcn|EZ2^`HYQk-Bw#}c
zJR5x_-W%ubkXROuvgO(ueVAZLlF;!;z7NNQW#M?PW#<}2`F%K+BnjA10%MJKU?iEa
zEF4;vYsafWOt2(Lz(%~{I07@03CqHv73bP+9mGvLY6XHNNdh)>9fa?JfM+ogXW{Z(
z%iFQ;x*NEdU`djI4JBSWuw${?OC5?A9Jz7c*s~^PZ#lSL`1*Yh<=$-YsN0{{3#R23
zHqpO#>hiFh0X#26D8#VCH_l@T6LsEs#L<UM193~wLyB1;cK)DQfeF?cI{RK{`{jQ>
zBE(HX94W+e?>8&3go$U@PjfczDLyL1g2VQ6M33$xJc6~}?{&Acas3I83GucNhl!28
zLa>C1`LiE%HjbSCxDX33ZBaZ_h{3H39>H1<etD;}aoJ1|ZwrBzj}?L?OzhiclCv>(
z%9BFe*RrPT-9M-P;t{M>`|i=s#>uOn5aJ;r4i_6A3&9d5`d@yJv+-sbew*XbPySZ`
z@paRBMJ8BlVg5E}qy2i+YP1j-^L0Y7gozo?jCD4Cnv7ou{`Tt^9dX3*yLkj_^?787
zvvG5Ax)9Y@yy$AxNeGrO@pY5ioQ>a}!WqC-PhMHT2;R4)jYqInv(vA3Hcs!2mY*g>
zxe!x?U<nh0mt5~`?A{;02)*Bd8!B=_%$e8DBUtP7VFR3vCF5bEqY$w1st_z;V(%9&
zayII|0UMn*ZkX3_O^0HA`Hu<K+BP`X+0fngdFwaKgElCZBnkNWr;B0Zi47ZiR7QX{
zttW3fjoPtx-G&}`egpZBB}{yNTwiL(z6Wk7vz9Z#T0cB~G>yj<LSSB@cUi*3o$Y$k
zc--{lm6<XjrpgF1!CEh$m320BUY#WbY&;|cOPDz9{f^Ft&Z}>}e$f#<WhOGgT37zn
z!P!v%Xtd(ROjogy6M`j7JUG3Tv!VVm`;-4=ItsB$Jc<d{TD`oDv!Q-|rVxleL9=>A
zmN3zMpXSbn`uW{0Ylc0ASTB)*3D#PW-P767c=f0dh*w_<!4f83d8VGTq48?br7c4A
z?hO**m|(3lFWcGK(75}B5M6{gO$e4Sam)DaoDGe;D-YW*>>$LdZX-N`wW{6K#M#jG
z<0&Cd6yhF<?JQy9xC6F?nEASXoYC`;@H8Qo${NK4YyIE*jhzi$2ZsrP$nc7+QLMFe
z`Fi(UtbIQ5@_`*g%-wmJjq_N-MDWHsM`PU$f>}bKuO7<z1Z%B6OlyTzI|!Z>0wefJ
z-;MJ;2|f3k^VG&4gFxK)ReLu}E;{VhGA3B-#-Dd|E$_AYK_P|<(MfEy>iKFJOPKh5
z(QmFDuN(v7p$iTOI}36AMJHvLV6FA@nmHS<UOGjHsX`nq#A`yZgozD*1a6ib(d_{t
zrmSii9wfv$y&m-l);etRZqCN=-zE$3ybwnTG3m%hGb~}^nI$!yjcs~Q5~AypMqwWz
z-gtVMN3hlbr?ql6`b`JXLI}*=%br=5VF?rWwQTHc>^tT@As*bYInz#vhkxESWP-J3
zzJ8Fiv3|t;Li{ZRYIU>_EMel_XLffsCf1%P#G%a>Ib!>;iAS*3?PIz*8zZNpR$n(;
zl)+3a7lI{B^lxyWvvKAJxN)C){sb2j&j|PN2-fOwNl#~E=~~okh7j<N6NF$16KhwL
zIU564<F|ev`&Xw-Mu<_j9OMzKb$s;`osIWK!N&JOAZHjN1WTAGywu0p=zkt;3~MyF
z3~^WNcm!+N8mxEQpEVrpRyA1*LzW~7M4w!H*cjPpa0Q}hlCZTFS~E6ZM(t=Q1fq}l
zddLzc4()R#wPV@8Iu#HZhD*ztV6DXyuBY+%SqRh$1WTA0QGY0n$K>-T6fhorWdxaE
zt+KhdIvYB#?iB(yK(K^~<2Q|THgsO?)qIh&vA4`bCRl6w?jxNI^^aCWu!M;YZN@tr
z>K|`y*j&I&93mdY1Z!RL!B}TQ{hSGwFwuG7L}x?&yzP=kMcCL`A_Ehw_4Ui+oehmw
zdkcXP+)oIWFtPun2b>L!SC6b}S;Q>aBoU4Y)*A8fJ<f*4-KT}X2!1aFOPHv6>qE|l
z#@)#m98l~b#L*I|nP9E?qb4{Tx_*om0v`345G-M0yL!5V)b(TVSMA+it*NXyOt2R3
zUW34hW<s!pi3|4CJ+7{UvU0lK#mdP9Yw;e}t<FVTonKm1yWIB9oBGu)hi_vI|Kv^m
zyXFj%0k|<o2EY;~TArq~?wzlZoiJv}D#=TjV68P1)rRIi1BEzQh({zZVF?oxcT*dh
z`z(^3a9<%ll>CYb*6P+vZD<bnh7ibipOE~DB}{CZRmb&$=5X)JP8b=$Fv<FuV6FAb
zYq>tuT=WwmFcVJ@f+b8GzK_~S@12=ot=tJ}BfWQK2@}s=UfZ=Jy?17UwVJ<J)3rnQ
z2A9g-87;3Rc{@v(7(Ahtv!Q!~m9lrnygFKT6HKtyKAUSe8@k7-BYS7`RSzLp!o+8f
z)O0p<k8_>ugb{bK6J~<79_gqybnkqQ5SWS6gkT91%cj(DHgxa2zwCrz<2BjcF~M4$
zF52F;L-)>?MZ4|ULa>C1wWGIpHgxa&$cED1nF(J@ZRp;4{kqcLIS5LUBw@Q^$@(^K
z=ut1)Z8L$gX}x=2b!x}C>vivp9k(wj5%sUBPVL~mGZU<J&b!+=8#*3x&QNA26D(n(
zb^q;XJO;~77{p{5K_*yhd3Cj+^Xe2KkS&2=2@`vtRn6JZdG)#Mow4W4%1mT}wZ1>L
znrnypM{U_VV^!-e1WTA0eaW`YhWf{|vJ=K^|4#PKOt4n*xow>d_48pupdG&m!4f7;
zx_cXEBfWQKg0<@Itv1qoXO=MW+NXiDk={Eq!CDJuZR6UZad*D#ow0I`!fu-+Ow{b9
zHZ<<OD?4EjS&7t4uvWv1)rPJgZwhgQ5GM=45+*)+^KbW7hpr#8MuokEXe?_K6Rfpw
znc7J2oms1Jj6N4@pHIlCvpZ+NsWVHMXxKw(-8;+4c4#NtOt99m9kf>Iy)#Rg*te6~
z(40ZCj1cn*c?lD&wXl!c(A>ue<RvU&qIi?q(A?*4*$Kl&PO>E?SnJ<o)Q0A8AP}ja
z5rQR56dUL)(H!n^*$IQ#B3YkDkk(^AstwIWpA-UK`;8DR;pZ+Nt2Q(jZ7n-tM4zUT
zy)waC_gtVJr8#vgA>ilx3&9d5nzvK0)tp+gaJPd*-p&MT)!CvpbZ@`}OPH9uS#9Xv
zU~kzwqgMOK{(}kDdUd)+INjsO{=*S_3BeL3Hh!fMPWL#nk8&rFr^v2|3D$aafJSQF
zJ5LY-wK`P@mN0S97aFN`@BE4Egt0o`Cc8T(SnK42byd^7^G`xx%!diV5+-(8sVk1|
zorlZb8DlPXJi^z~HCXq~jfFt1uoJem7Lp`U`QDicTb;3Ye&*k5L)-Cj!@=%^9<}l%
zx;lgSW=G9rv>j7rCyW~tw44dnI%|?<OFACBcV-C_|81!mnT`kVota>*Bl~J*sq<>K
z?41$ePL?re2@|z<*UVDq)w!}0#;NnpG836#tqs*QLstJ-)ND}!XJqY!U<ngPRM!ky
z{o_j6JD(uLXz@WNSnKl1YD4{ekByrPI8QuF2$nGM{SvjIetx{{gmF6fjhw?V!CGfF
z(H)D%tC~Xe7UFn`B`jfLpR08@q48>n?1YaMqFl}snP9C$2B{5=yKf26UWgYZCbEQy
z+#0o^ara5t3FFN242jfCuvV9s)P}Af_X~l(dPNA9FflEsyE|P!?vTARP9SfT^Iaxb
zi+8X7-kBv#{CvLJNbjAQU@hL`%KI4dTQ5J#e{#K@pFF9N%Zlm+^W-e7q04trw!aS=
zFjxLgMBqzGgwaY|Fu8xl*%cj%r&J)8?BHyCx)?Tga5m}(ujhVvp^+<JwXP_C-}}M-
z73T_ZT!LV&KYr2Lp8PJJbW88n1=!fJ_rW1cm{{0PZTzwXHvT%Yb>UPY4oMKKb;eg}
z<HI*$<JvbzI~(~S`-UuG;?AZ~JI2Gt-$L{k8|Nel)*AL-wJ~xQY#e$`Md2JFe!I6t
z$Py;%f1o{mQxDkqYEVVt3?W)f@CnxX&wRB}@i=V!dDBWq9QIkQkR?oPoS-&ZepuKF
z!CLpvRvTZ8hmGq#t5rnrj=gDRh9ykA(@$-zJq<Pv`Mg%~5+NSF!6#U2zvtA(71zN=
zy$LOfX9`i{nu-idn0T+V+F0|S3L!?{+oE{15Wf!g3D%nbnA)g$7Hpg{WZxos_xSmv
zGb~}EL30}q*f?DX)T(oWV66wIs*S!OZ0y?m;Nn?Atnbx2!xAR?Y_B#l(?Go1>)>K{
zA>KK`Cs^yV$!eqN9w5#aZSkh!f=T_$Si*#Pt@?je1Z$c9D{+PRd0(+1Z4p1O@BDet
zfLUU_zVrE9`&V+!j?=$4xEg<d>c0LJX!+?v_>vOQcD$C?_IgDK_H!m!tIJfiargbO
z@r*<U*k~+%&JrdT?b5*2@Y*|IgZ-Qd*1GBkwb4+%_gDS=WU+CD_&H0M81RVNXtf14
zT8f|d5n?CtS|(U)ZQBN}539GCEyOtS^V5XrC<IHGn6Ya^*N&d|%n)MVn^zX3XNw)g
z&zWGY+Lx$}bMJ<Y#zJ83b`ydnOguA2ZR~pNOd;6MnP9EXQ`N?}x~~dxjzk8G$6SdF
zEMellAJs<P{n5MZ=S;9xyM=1wt_iTQheQTMpJjt8GAv<Y-;U}Z(_5nD$3<Ryv3M;L
zto7@6HXd_?I5CP0{e)l%6GJXj8(+3Xt#*(6{3G#mCRpp`-_^!p3t(f5_&H)??x@xo
zmN1dKQ*G?p6U33CeVP3CsQ5V(zLv%kU7hiKc<qnl`pY|OB?%Me=SoOq2rZUeI6&8P
zjQ~5k`HJ$(zc+SejaO9>thM(A`Xr54`-!)nAhr5i`idn?{Q8~RxTy!??$BNbhl7Ne
zATf~%);hnR+R(Twu|33WM{H*a6YUnN4P8IZ#5yiSmjuCDWoM`jT|XL$x1x9J$r{BH
zCOS`58@di&Ei3<pLVPG|6ceoV@d;`}*TF&Jt;l_bi$}49iQ1Q_4PDQV{Jd6(b?{wT
zYnfoJi;h$qx}HnUkU`6lGq8k-wQX%Yke5_Nu+||x)Q09Ihe;oy9h;;FSi;0rKWNT)
zmCLU_760xh1fnPttabB&YD4p@!EcVvAhR4IBgqmbx=d9YnkQ~2V~v&%ND!>``0i>$
z^Td4b))~yJCNhUv!bG#<qIS4^cf*mbGv^7hZ-QX0>J8O~=DXX8f1|G?%7rXpg7a(n
zM!AXo%g}OJLp;LQQX86`v)9TelB4x}ZtlVXx(7rw=(D~4UE`JXQ#e3uER|To5+;gQ
zDy{LVzO?uXA>I~0XM(jFG*=td+aSVK7XoA6TVf(hm>7DG+R(UreB`y4$Vf85TJLpM
z8@hg+AOuDbv7IGMeDbc^(Dj4;oC(%?NA4qWH>vC3ZZc;vuRfGH%n~LpZlb$XT?g6E
znP9Dr6V!&T=l#T6kuwy;ds)K7$%E8}uIGE-ywc6xc0w}2TJ=A$@xaQtqY!9EcOh89
z#L+9%hUO(Zh@Yc(Ye^3<!CH4Vt>^km^Q-%$kFXka7lI{BOg>9@!kS;@#m_;Ek&$GA
zwHEeM8=5C>76P@pNC=iN(dmC`L-R!Tb0%2phZod_=DSZzWPsQ1Aaj@{Onfx3p3C7h
z-(^2%!q?(l`zP^pjJfP0y(~OQ=*b;&QQ6Ul(HTHcTF-}LY~2{tlkZzE{T=VaRZc)s
zB1&cKKmPy3JhG7{N)e~BNTk1<=i5+1B|2X<d(m=@U|ad!*Z&^@EsI@BRFk-i{W;cj
zJIlzmA0{o-cwR5a%N|F|Pu0!K-w%`Vz`R1v%LHp#1Ygh*Pm(>3n<a9VQDg}dwwAPQ
z2ODyhk%`VSJc6}sB|4%EHe`?EY{*$gktIynn)uW}*pRb~Omvpv5v*k^>OH++L(VcX
z(OE{3B}~}b{?L5bkh2UIOXMuWBUsDU`Lj=l4azc#EMdZOl+F7O-3q~4mf@5Qgbmr_
zgwa_>fh9~>uGRVp*pRb~FgnZd2-dQ^>$wrIA$uIR;>cM>fh9~>&ba?Uw+bO=87_yD
zvkZ@5Ez2JpKMEVjcM+*2-z~6&3Cn#SnhzUtmf>n8XBi&BT9!G#^*U_GSw@JNE@v49
zmM~#C{O9L@kh6@iyAX1g;SsE5`TTZYfuOvkf+b9pq7UL&RRn95A{>bG7Ip}aUD%=c
z?8V2I`4ONLKYD#s$Hm8*eYTTWa-tAt3GwYEKEYZWLXAo_8-v)s+9BZ?LVUhy=L}1j
zsBwzgcx~MFLR1stY$1M15Uh3i61{2I&;rEWV_UmgebpwPVF?o}hU>}p4s&V>@rn>V
z#m37Cg0<Q;QX8A<g4j5Ax3ISm?>+lMh9yjN9-uc3w-xYv+lz&`K!{BVg0&85ptmy5
zd{Ik?t1}J5{zA09ZFz<zOay`6${Zm%P!Nm|qOTCUCkWPBvRH4LPQSg55Hd^bj7+}s
zOn22-`)pT?vYnUd+^vdWEjw+~xhwnHVzjR<u!IRa_fsE~eQhz?*LnnN*{PxWAkHkY
z;=s>Y!i1e)YAlg`tvltEeXU2ZmYsfTERlTIt%0(yEwF?MJBQVnDEr!Cw6FCD*0NJv
zjfs-)7NdP_fhA1Xd9ucK+1I-BUD?-q1Z&x8w8nNi3oo*S2|E|pHL5Ctwd_<~*C^T7
z7NUJ^ktIyn`M$2Tvac;f`&y4+ExR4iwO01Eg=k+}WC;^?PoX)3>}v~H4P;;I5v*mm
z9GWvozFWY&l6`HFB}~|Ti{?JEuPsFTT905YyRFgO=X^OsM$UlKRF*KoxmFOgk-H+)
z>ZAnWYw5mLGqo4y*9iZTJFncezhqYav_6MD*>At>Tz=c|weD@2+F!SjXuz>#mJsWN
zI9>>rFyY4%$t+X%YEMqOEsiB9`!R-y_+E{p57YYhX0L9}43QhfXKPgpxhCAE|7`x%
zwQo+}U8PMOgt%6SrxFBfy}aoc*9#vu+eL^?U%#8VUWg&bHwjt7M4c(CosDHT>?TBm
z74K%Q7UGr!!CD*Zu5vc^+zGY1x$A_?l|n2(a-WbTOq~1uPtL~1<8~Kfst^|o@p*z^
zt%XZ}bT($Z2OHDIcgkEO#JZseg)CvB#-{I_jbA^2jqimxTZl~wg0+g5f9Gs;&7$Q^
z7F<&XVwAkkz!D}_{<Ol`s1fWT#OrTeQ+BBkw<HMGLK%Ct%Ll*)uQ;|Y@mxaL&V844
zy<O&;^KtPFIg_biiOoI`cGmmX91wCQQ;g1J3QVw;onJRu3PR3giqV-&fhA1XnRSm3
zMhGEiGH%6@GZ~LyEjx!FeF+FTlX0t>oXHee!i1f@U;V{MA$W~qg0<{EVaz(%kTV%q
zD>;)Xu!IS_Lul~PC?R-_VuH2oUgWjQQ7bu<!5JLRWC|={!tO%;dU3Q6awg;AuAIpf
znP4ru-)XWGHsnmk#dbN9DYAqKyVLpTvN1x)nT)d`XEGkaT6RxWrwv*zXEKH8Os2>Z
zChTr%L$$F&$eD~I<V?mRSj+C)MqLOSawg+yC1)~4mM~#=Y>!>#Y|t9T1Z&y7Vck1m
zL(XK}>MUn6MV2sOcZIEI!3M8UO!!)QCiCPZ*mz#<IioWfIRhw3l7zm+3>)}|GZ~yv
zY<~K)I0A4q;3%<m0xKLM&XUE0;wSk8OZd6xozsZo71xRh)<U@yuj<Nq3HHv&f4Jp#
zC;aK+vGVSRo{{Nzd>fsYU`_WWdJhc3&a!ko_`HM(*0S?ComX-voWU+t?u3ghVZzSj
zbYAg!2@|Yk=ZxwfI4_Crgo`X;!p;`eKjcn06Ws}W1Z&xOsrtFx31={`<W9KA5+>}7
zRQ+7;gfr2dut%_#o%?FMk~`rH#zO9di!5Qn&U!Uo@p%aotYzod8h7PR*qs{4op6CA
zOxT&V#$7%yVS=^n9A4KCxf6D$IC3XkU<ng;_O9!P+zGqW54jWei2p~}c|cW>G;jZ!
za}FRVM$DKaaBokeV$PUzSjC(ZDk@-Db6#`KIS1g*m@(^`GpHEA1PGY*tDa&0`!x4G
z=X=lD^Kz``M|Jni)O1(ZG^jH76O8vD?Fs7{7V(Zk3lioYg7F@tJz>4)v?nYPs519O
zjQ2V13G2Bf+7njMf`qvjV!Y33Pnf0b3EPp7RYqRJm}OG#O5e4lJz=|<Zxt3K%&dq(
zgf8!67jFaF{b3jZFftT*nnjN#H6Dri)uxqw>_dnUtwRD;gPvy9W68D#V(vpbKB^$T
z(FmXgiORFn>OS@i5I)inA?77nXq1saRX|93-G^JWm?!q3H;!1bh#D`nAQ4#Zi~bc|
z^@E~SO^FZ@Zb2#nRVBXt)W6iT)fYa_(j6$Cs1kHXq6LZ0tz&f`en$myiU{%4mP$pS
z%Kv`6?jv!4n75}%nE}+JCkrh|#5{SX`|z2Bgik60RY@^#bRQc#yONLpl|8R%iBrrw
zM*M8vCDZ!VqPN=rA`FXh_aSZESN}gks7xOQk=A0-66nqO=g%Kot{+YG9=30l!>3Gv
zZhG5~RLbsyeWKYb5ub=4lA#5O!yhi_w6m9!7~K>f^#2lpDtW9XQ8ub0WurW&KUU3^
z;<{^_X{?NOX07(C6*HIRn|&Ak`(z^e5|KL<fhsc-mM7amBBCg(CURuQ_Uu>Df`plq
zdr&)+h*v~3A|n4@nLw49(c8a5BVs#c2OAO*SAMFB79`Bv;_{#?M64x3<SaL)B2Z;!
zCQp~WK}7nLEa#)It}0rPFmt3H3!f5^AtjUgAr*ltGsEiPA4x<z%GP$JR;?Y-+Kv_^
z@IE#&!YznM9w-y2GVes=K5j~HOtJd<M7yteFX3I;Ai9cvhpy-^GLV80k>PzR0#&wE
z4fH$l-dK@IEt0Zgxl1zvv>=i0jdAYB;(8*JD%Ln6SMoj;fvOhAs_8z~{VnpllW6uW
zW-_5Pqd^N2^Jiw)`*Aj2WSz$mA>!_`R0OL0qe|&Ms*Dmuwv-j*dzzV{1&Jr6)9F4g
zP8Hd6k%ekWKDtmH01~J=JFKwo<ESDCe^Lu#+CP1)XhDLWXx)dg+b3!n#9Pff6@jW1
zD~+>W3}RnOZmIsbPpX-d86CBmnK_wzX@i*j{2x!rEwv;9El6OL(4*-8<(AO<|7z9$
z?Tng)#Uz9U3G-)Tmz3hJNlg7;gix9PZV;I$`!UeSWoYIqrTEROlwmV69+p#&YMYsm
zufwWPt=Yen{Sf(*IrJYAs50{?^<yI`^R|<6GCfHBV_IbmEl8Ld9h*~SBA%w?eLkil
zP-W(W8nn;O=v0-I+|tWN?iyN<Ff&u_SDzst{}3^fT6H%Sfhsev^*z*+eEg=Yn#hp_
zw=Srm1qn05R<b~OA~I7}P2}Mwq#{sd=I2^ppFl)$%Jq#W;$W6^8d{K$@3C?z`NYks
z2vp%cO_7i0a4D-h_Wh5>#5z+{{EDB&8c<aHW=eNi|97JTf>w8Www9tCLkkikGThQ>
z$BJJhQ1#`)ZQX}s#V=ZrXtVOA?!&R-7YS6=%K23H;aKsD79@@}Gfp6KtoTI&RZZ5t
z(tS8q{GtU3{y2>u;T$V|kwBG=f6#q6R{Wv`iQ}Qh**lIEzeu3!{e{oE566mMv>-8T
zWlp^xjupR1pvso<o9@H0;ukGQ3~FPX@8ekUiv+4lJo}k)JyKWvq6LZAh=O`Q94mg2
zKvk1ke{>&?6~AafB44z#?!&R-7YS6!u^lUZ(Sn2=+bxv5OUXuQX5L4{c5~fk{w$t<
z5$8z{1jcqVmzDa>pc7`sOMe@fzYB?yIWOyLH9=E;x7f?WFX%m$K0{53K-G}-7x};A
zm~HTmP$Fi&t5wsD)E9|D%aEoQ_{Bqi*`CebF1@d4zFV!{(Y2&*lFA1X7Rx!lrrJnb
z`lcJnhv@lRBL2{S`0hiMxhgisYD&bZ8h)f+Og?1Gf4_Ihk<<UzLaJ6DR_gFaBEHgp
zNT3R@6YbGg9bCNy{r(k1paqE~JvA6B(UE7Q&O($#fa+Pi9j*suIsdQn4C6Vz8J2wC
z3$dLtsd_aP%`O>QkofiUsQ!F7R?s1Vszd$OKy1e<J+vT^qwXHvhw=U>L{*<+-rk#5
z^hlt}v-%R<$H>c~f^IU+bLs0gZ59z|LE?J+Cf$ee{(y=UYZ}W`-6G~uJ60Cbf3NsC
z^pf%Kj<vODK_YBeVV!oYtwjP=FN+83z8!08(Sk(Js8YHQ$J$yXP<7$k4BdxgZ7o`m
z=zgr4?!&RR770{2*PW~TaICFG3lc3>HPC%H*483{stf93-G^gsEn1MMP@tP}J@jv7
zu(lQnRE73hm2y2&*Vdv1iL^_`>pmQ7Ymq>ed?#XUEn1Lhad?jI!<flDq`O_LAZeAy
zkU$ka1r$h9vQd;<(#*Wb^1Vx$nQgg}(36>&se$|Q((KjDU!^8cW#+Y-&-jaob16Bp
zlC-`>3le6A&2PwdiqvXK9xgS3Dl<R#;BzJNF_3b7BHvEWxrP=b%uL~eUIocVJt9Qa
z<cw4Vs?0p&r5_o|hacrEMFuh*t#8qSgqiVt(#MI`QOUG}CGw)bs8R?CRGHb&kJX=2
zt5(x2d=L@M=|8j}f$tSM*O_Me;+r3_|BM8x#Lr^ZZ@ir`b7w|4@nw)1uf)&hzZ)ya
z|3zR-MA{(IrsUy%|M{bu8J0`4*C}R(#XfnNV&>#pwal(i1sxG_^j4#JkA@Z`@UE0{
zeG-8xyr-pVL+k(Qt?0+%!GZd7?)ZHa5~%vx$aph2ejkMvB$V(8x{pZ?-$x;Vs>dCj
z_2=C2`zW*^5s-bP?!)o>C?rtT{6<0DhvWBAXhGucy#Bh61pPZ<{5}c^R3#kEulsQP
zJ_;>J1O#=~eK>v}g#@ZxT=MEZ9KVl33la;xo2Fck)Za%TfhxD`xpW_n-$$VZi2;Q@
zbsvu3M<Ic##_O}`J{-S~LJJb_=atcYIDQ|61gdJqWYT>&ejkMvB(i19Z}h|A`zRz(
zRVz(;-G}jg6wWNsf<zw5-iuX+IDbH|Bh%~j>CMKFK$ZAeL^$L7C^I`anRfTh^^(Z^
znrkZYvzc2g|NSvVp8*s-MFvtyMWD*eOrHDxlnB?9Eay*(@n}K9%#n5&d69_pM2PoC
zV|tGufhsd!`k~)dB1Y1?Nz@J=q<0lskT7$-k6s=nB8Ui)5nh*yK$V#(o^&{j2=R^;
zbA~7M&P59nX3l!o*)2pkr)0KYr6N#eX1q@{-a|x_l<fIO+C@eS5*X)=e7l(Ge@I23
z3g0XA{-F0@%J&}(?*_a};y&NEiTlbp%YwfD&@*0CZy*t<TJh_PP25+GXIY>HiAvE2
zbRUjqSs;O`6&`WA5681C(1Jvbh&e_-9L};p0#&0<ztw#>o@Id+BrfG>tNU;~%K`~h
zU4HXi_u+V!1zM0OnOs2k;dqt>5~#X$<+1L=@hl6pATe~&S*y6_#ybknvOoe=#h2dG
zeK?+FffgiY)#;)8a6HQb2~-X4bxZf*c$NiPkZ3jjqPOUWF=xQDERaA|s}?tOAC6~P
zpaqEyCoXvjAC6~PAc3laL$B#R9M7^q3lbLkpYS2(T2j@d6$w-wyLwgkVG#do|3mCA
zo3UN|Y{vZm+uJsGO#W|=MOct9e>V09|CbLWgv#{cNXYH|uebmG`v&Sc_^`;9|A_xa
zL44}~#MJ*ygz*3VT@YB4YW5JvNBnGNCLL>1(PH*i5N0;gu_hG>RGAr8$C^~MAYo=z
z9cxmNK$V#(cC1N73le5_*s&%R2~?RGZ^xQcv>;(-xgBd#kwBH1xp%BdMGF#Uw%)NO
z6$w<CI}naFsc1pM+;woQNksxx=1z)ZO)6TDFn3QJYf_OwmAND2Sd)qtB+Ol)Ee<uQ
zNTABx*>bE&MGF$<ZkAC4N#6<UXKabxI3!SIW>t-vRQgW%|7udvlA18)yL#O#{qB@=
zKkRY@Fk?vwH)F8l_fbfo%8bX3-$$VZ3G-dz_<a--s50Lxj^9V21qt(===gmU5~woY
zkB;9*p#=%^-R}5(6cVU1-}8>&N1+7?bB^NpeH0R?GUqFf-$$VZ33IOH_<a--s50kW
zj^9V21qpM`==gmU5~wogkB;9*p#=$Z?(6t{6cVU1=fRHON1+7?a}MwLeH0R?GUxNg
z_fhzqqXh|bEh4@}rv)oL=PBoYXh@*ST*(;UM`87+nT--}WHVbQel~Xm94k!Gf`qvP
z;aJ6r1ggv(0mn*Nv>;*bKsZ+8B7rJ%N5HY-7cEGbI}nal#Ymva+!1iBTt*8L<_?5o
zbu<#FGIs<VE3namgt-IZSmlibs>~e$$4YXvAYtx6I9978fhuzk!LcG9El8L<5XKAu
z_9iqWP-X5-?5ru?YOr^wp#=$ZAJ3Qp&^dS3lymMhd~=GQ&9|kwyJ)=6>6|;O_})O&
z@S+6?b2roRn+7CMCASK{X+R4S=5D4jFM)kd4GC1?h*&IilBa&^kl5?Qn1Qjx%&-{|
zj!yE_PaP8T1|(2rX4@Q3zd#ETW~R{b^a~_VWo8W>PrpD55@yEJ@$?HMP-SL69Z$bN
z3le7L*75WUBv55$aUD;;KnoIP2HNrT3nWlwW}_WXzd#ETW+vV7^a~_VWoFeKPrpD5
z66TJ8<LMVjpvv4Ga6J72El8L<8;+-6Ab~1#m&5V&3$!3%?$9`%et`t4%-tHt(=X71
zg!$ezz7vL813MC^GT-wCK{)_so(P1N|3!$|fLz&c5;$iNzt^M<g5Nr-K5!q#)||*`
ze_rw<|GH0QbxtL5&&(frnhYvyU{B&->b>P}1MDpPny9)zzNEE%(#|QY!}6tJoBF=v
zZ(1H=)-g%E=7?B6Va7q$q)QT?yfd1Y{C$A!Sucobp(9w{F&oup2Txlk^p51?me*H;
zJQ8`@QIR~Nw6D^jaw4y_^&!7s#aFqTR}k&SF#E0JQ?!<griXp`9>aHD4OaHINa9}P
zqxG?1rD=+fJ`aNx!^gJ8<FtdNN2qOwowuL%OXQapHB~$YB=fvm6S;dCu4p5Y`LTqL
zyj`qKsZi3Hd|V`ARH+f_03y(W#KdEXy!tDfvU*f9jqaU)Cu_F7d+i=WFG~cfp1FMD
z@13hC72So8dVdep2G)yEE44o-wF>>^vnBGQyt#6wpYY)}eXO=8-88jw|8sV<Akk;y
zN4~m6bERex;lpXiK+T<e<aie<5vU4GpU7*>Zmq2ADSX^=^ViNt-%`K!J84G?5*<!_
z;AbCqR>tQOKJsoJs15OnP(RNKmk3mS-13>f+1gPV+FtnRI8)I!ZYiVj@D=tn!xQ+F
z^!=5fn#p``L;?@F*GG9|OXd~#zvq@p{T0uQ!biCd9knJ!GHHX4?6ac<iOm^4^TtPd
zDq|W5AGfo%)y8$srClw)QzB4>Eu=dA9v!tl<YR7)J$AGpaVy|6cZ=w(#J3hcrVw$i
za3<|hDgsq<&&x#D)*hCqswKNEwTJY7$Ct#8P@X0^`3zYZ&(B^Rs%&;k-Sgz>isrSA
zzQzq(A@u`^TKnSp#cV^BN5w>|D$?lQrO_=yql;sODjanxr|*_dJK3R&mTpE%`|7=)
z_@5a8O7++z-aTU+S00X6c79IcS7T%Nz%v2LqZi^CyhB6}BGS)nX-5kZd)mbD8~w*A
zSAQf?t9Fle(oWrKu0@|5EfJ`~5uq;>HkQ;D)U2;9JTXlgD<rO$i|2m!5lVPo(erIY
z_!Dt76@e-oH#*sf`Z1jPaW+-Yu}_&FeB^l-1u8>ti+(V_SL&(deYM#cJnd*fLd3-C
zp;HwjCT_kSs(N}1)z-DkD-o!wM$xr=|EY>QMOTaEllwBYOT=g`;_2t`DpOwbRd0fn
zV#l3)8t4DO7v>LAd^Q_#_dg#4$VUV6(Vu+a??qy3rjPv2;;BkairVz|wy%b&D~NFR
zlL=JGtzsjX{Vv7bZ1bmwVXSS}`5kXGJ6I_-+KBD{#a%c5)@uD30ooGJ<KZIen-(PY
z7kbYpybV%j&l0WrI3|r+>BD4g_OV71fhrsk`g-7CYxVc^0IhMrCTXmYDAV9QKYlhy
z@t7xk+}+z+twF8IJx(T2h2us~)Hr7UmwLW)vHZrtKIPpQ!?!#QR$LkgAKjRTHSXLL
z?et}TFSH=h>*fo-YF4n4ZI*bVR^@+cy*(*V>sPL>Hxj7YxAHAd8W5~xDkpqI5OIr$
z*+ifPi7DUS@Kq&)mCsIs$P(7xmW2ms>*sCrMhg-FX`b^1U#2M^hKp9cEj+`v=*w6w
z>EI)YK-JvGZ}^F{!OEHZ!pDW0w`}>U4A54sFK69Y;1xemJ5b4eDUttm>lME{YN}G@
zX(BJ!B$BV`6R7;`EPTY)xMgcV#Eo_3tY|@EMg7-2uHH1ITTCMP@cn7GRhT_Q%Qmin
zM4$>=NGAwTKUPvdR#QLFf`s4I*F5pTH09nG;lom7hHV}ZB@f92s^p%}p`I6`ehf_2
zbL>-{&}ja5>?EbNCVYHal!2Z8)k*8Iw5=5_NIW_Aln4DYR(a?v#_IOs9IV_;KW!cB
zD-ozlN_fe4hmKeB?h-y47O%v{JoVJp@B7>Or^yRmCVq(WY*HexU;ZU86g*nlyEKs_
zO&wp7gMGc>r@1M8t!P2QGvp=D*ng~2f1U7=m5B7zDoZK?RdTDkP^<b-t9GVp75ckT
z^aa1Rd$3Y}yzp_jaamTnqM|j<I@5|4B>J{}!mZ~9D}`!`vGR7Q#PUA#)Q;?*BN3>Y
z82_AKZZSw{J4*QYUCo!Jxm`?KcWkW{El9jA_n4Qj)=ROK7Cy2DG-lm47uHsVY?KI8
z*^{Gq;iA2iRUL(oguOl4FRyrYM4lto(_bR_z9VgvA=X6RGj|jZDdVT)P!jnUpGQ2f
zmY;IeMfkWx#7ggYwG|O)L1NjxD8Bb*55=RM@X@Ppcb4z)H}z-9gA#!%Y$1J}Ik7Qw
z-c(p?Gkv2KEl3>x5XD_j_f)oY5I&lXZOlA(6xP;ElL=JGJ&&k3oY@xbQYVc%WyKji
z&h)W=7RwxU1Zy~YqgrA7DXAYwG=Cq-hpca{)btju8b`z#B8sFUP=%vT-y2K|WIOJ8
z*aM1Qu@-CkP@kW-%jx8^z%`QdG_{mZ?uoo|yN7(ztlG*w`ge<E#I=bm-4Pdc<>5<K
zv>@@eL?llaQd>D*TD0n2u8HhhP7l?+uuPx|M}#8WzZ2QmLoTW^{h~BhNIYyE$y-$5
zN>~NqgA<YEu#3u45vaoTmBq61S^(Qsy1MQ9=!@1v!y@^%G%m`!N{QUoHj>9>DXKiD
z-z!>`hW_1HdCefAW!dVsOGKariHpS}d5ueDl$CnVL-I~!-*bA{tj%NsRbmXg?JS!z
zx?_(7vP0Hh-t77neRNF=68*@>N+Ra#KAug{ub{Q+7MVa5URnC9JqH6>?+(4ZTiCBk
z*Bl9Vw@4mSsESfk_c4Zu5q*1kH%~>N3a>x?jrGd`tjfUZwm~E1(Zz8)GCYzOyHiNX
zNNZe+C9KkL#un|eCEwGmXhA|eA6<TAONk7(+7D;D_wBUJeIOI4s`oLH_gIlr8K^%W
z85Z<l1qLVCN?tu=O&b}-7bpB-`PwJ)Upb<9MN4+&Dl?+be?FGa>%qE=NV5IDd`N!=
zO$!p8Ge+?Z!?P<tX|-yx+@n@4qgE}TR$)s}CAVthA`e!ryBDk5aE`S~(-*w#^k^1M
z@2F^c14QI_!+hxtAYyQx$FG?Y+tV%fVE4Ltv6)1m1&KEl+jpxmtcM=ke^G4zd8-)v
zb9}8tph`r(9)Er@Ben-+YRtOSDZ-L0MuamhNIXc2;^SO?vmiaT59`&PxgP#zE1v6+
z9z{(8RX8H_l~C!%EGzlgS?(WctdKbWK8k0&_nXbu<L=%vjah?QMOgC+GJz_*vNR*3
z(alAp+cDMX;<z=f^^(^)dyge86IZZVi?Xa-MTJdWG2Mz5B*c4nUya+$n3sfo&%rj$
z_G7mv_mv1#4Gw<E(+1sUmGn7-@BG`gUs3+dUZsNdHO&p1ZdI9$=7zlszT!o4o@1qG
z&M4+V0c*}OW1e_u-fdga=l;x>2(%y(xH+2V?;OEig^PX+Uz~xR`qhc`tk+f|P=zg|
z8S;-DY$)}kSD-QXF?)za2AW^_-oMVi?G!$?QqK<&v7dU5zYA4z&xcdbKU2?Nrs_HN
zNp1d`N4tfw4s`Y*{mmDe@4C+(!Xg(Gu%ZPCF{>Rj{RA`S?QNfg*t(S*$2yIA;Ee>T
zs?mJc{o4t4Tc7VP3T<!8&I4Gs_1nC~dY~yk#Kg)Z=GPmZ<>FyB*g1(KO=q4x4Y6_Z
zac=YjeNJt9M`A6l4N7-A!p<3M18P+ZB66o9P$jpjOiDg6dfC!2%prcKyx*2m2iXD2
z`^ou4zPz<PfHIKfS1b)f3le|tkKwgmA7ER3#fqgct<^rAo5H--4Ddn%RX8FROZBSv
ztm~ErGQY^`(pVv}ht_Hq?GVeTuho1~h@PnkRN=T;EFWquQ`<$1X2m<jgkz2sbFX40
z-01ufCUOH7OZ=guYVXp+nDcZeJF4oX`@k!oKF&sLOyV-3b!nx(`6qzA&upxO&EJK@
zU$l0vSnnvSuCJYQ2k7f_=9SG?Uu~NNs&EYHoV$Xp)O0HX*y&Nn^cB6C`9&g@asc@b
z9$}009Ds8QaXuA+D$Fg@nFAA@v@^GwGfS7@dZuX3{3lFg)i#!o=Q|%iVYeweB=R#)
zpIv4~{%UMsF)jLnFKg8<NY6%@79^Z1#_?N`H`x9!;x4&+^N(8iuWqbWlO}ewT*?&3
z56!*KZl>hO%-=+r)Ej@){zMFK+(hz$1l#wCw`z2S)u(Km#j>~0EA{;HzU;b3O^HAi
z-U~EOJoZQ3L_W%YX|3md%uGBIT@HWbVa3j{={JOr9XF4vW#}$xaXhC)pbB&S7R#*T
zR;}%W^6bH#<@S&r3H)b)WH!qynSU6Oz;E#cc8oH&BF}gzQvx%xwV6&>wR88&Guz$e
zdIr+8AklwMJa_6J&35QH%j8$JwfiNivZMt|Bmz|;J7`{6YSlrjR+D^OPQOyR=1An6
z6wg1Uea@!2itOO_nZ>l+5x#8ZjX;S&6<&Xf<xGJNTAz|x*ts8jq@H7M8>josZTbJO
z8hX|_d-k^4l+L+Wb9ILuEl7yma)I_4QnKeST{~#?$;TR}-4cPST9kFJKQx2#T+ce^
zyE;Id<a@<7?ntQJ)*zA3sFF{a-anbw;)(q4S9uj@`dMV_tuOPY>;e?KG(fBBcg0rt
zP^cX(NKD9>$cJytsoc?b0iuieYijf@+v9^LB?490LW^bp`2kum`B<Zc>DhC$he&*;
zT>#IynUrDrE<o|Z9kdrEvasvabNpSXl6!tMc&xTJ-85U*2j}!XmXL<U_5GR#ClWbp
zTwJ+IJ2BWlS`TVtwXK~3ZCicMOZ`CN1MLDGp!Lpu+6A&$yol)6EzrhN5vamZrxTh+
zjMLUu7@-dDa>I_hJ((!SGxCyEnLaw1%R4`QpC@a-yKS)7e|y=E79_0C6ZN&I$9VnT
zy{YdmSr=TD2~>$)Aag|MM4(5LwVzLRT4O#N`%$I^iN~RdyzQ#uN?vNA#d3stp0RhJ
ztyyMc&&woGh2v(ils-3B8`>pMt#<ybwd1x#Ual-x-j>S8-%d{C7Yh3-e|zNP7f*fE
z_wI_l|3P0)R-$|NNSiC_qkAW<(R9ZRSlC+m;G2)HefgQUDCVb(YLSm;qFlJhe$;sT
zlZZ~s#%ZVBN7!DhI%gHXORPr4?{c4#NJrPYD8A%lGF`#LS&J$K-SbgDrsbZfi8ZJ5
zhl>({svEgK>1$4(!J<_^cMjAZ`9#>%4x!dgTR-!JIhmA`UGnh`FFx~51+ptAQd%X}
zK1Qov5YfI~gl#7gqP?aCi5S{f+qylc(y5_n)xVX8Yn1)4B~H;K0#(>QizRsNK&?Nu
z>L*vFejrhi@;$jW<X60F2_H5ZtAH{iY}Zna6{>LDESAcDb=O>I#WLo_0jrZYo%l?v
zpGKX2Gxj@yzpV0`b(~^c53_%iZ>OEOd@h+-8`u3(Kaj|o@iQ;-<2TzkS+pv?T}Q1#
zkxcBMi%g&jN8MtXxT>VKqGo+IGdkG%h<3(WUVg#aT*=2*=Y6lQ0b99P6m@hQkL+}t
z-OZApe0*tER?9&vmcuz_SkZz+$^EhVilsxXGzzT^Hk8!v)Tqz4v<{L8RJpW`<5iaa
z%hKi%K7P$mv?5!|umZnUNUhpPyKlvs(Teqg+(Mc&(B9qXtz}s4pDV1`5+pj_jpvCj
zZ`fv4jMduezM5F2zMsBUB2b0biO$%XqG(ans(;yP=?Ws@axsD5IQEsjm@Rztr(Mfc
zbUixc-6IjG!mCN=g?CJ+E$GmN6;Etq#WBILx<q@0RS#Zgjf#u0x-c(;c9&LO<qEgA
zq6LY!t}*)RE_i%ex*pv-r_)A|506c)B?47-Uw-8GcAjOUdk7!1FNUh$D-LB3cICI8
zpq;Vlc}_6rGx>RBg%7;VmJ_UuJwKn`_l>?PT7Ewr`S6GcRhh?7c6w)iD_W3POHXsw
z2$i*-C43A{va4>i@`^p|BoU~>7Sf5pXG7Hv<RkX)0#>vjF_v}|xA3z}>m__->PmZ%
z?Ypo$TUtv5s^p#rt!k}Soe{vU?AYOrJ;y$|y1eH%P9I^jz6c+CcD7e@(dsT&%x-VA
zAhC8Ct-@*5H@0yG8mo}?t<^H*<7kKN5`n7owDY&h^AKxatN{5KQ=8fE9G}7_bX(~a
zM7v={KOA6#0}JrpKVo?Hss|Y#RDdIGvCONb?<lhOT~~Uc1qs<l*&5HR&nE`57tWW$
z&<E0ErpNGpZU<Sv5YejnnLX^EX>~W^)^snlAQ2S)Qm;svcs3*TymINM)~AyK+3mP$
z;YgtBBkiks-#yI29ta;js^7BhtTKQ_EGTFHmvR|BmQrm@i-P?8hgbZ~4Lh6Os36Z=
zB1*55nX@Ge`DjghMYV}&x2T*QEl6Z+@S4AF8^&U479<~wYb>+1r}d!I?bvW6P<7+=
zbA3H{#xpbd$Xs-WZS9w_>|pta;b=jk`oTAROa7zG`d0L#VV^WM+I?lc`}j!&s&Eu&
zth&yyElD2BZaW_hM+*{PC<k!2;}PZ-DSW)^LaicVW-0<z^62KLv7-G!R)oe1M;Aw7
zJMF8@n16w#oh`=7r|&D9SV!ggQ^SrHB&tt*rmqKkBxj|ua;JT@`ZxX9y2X7Z0#zZ6
zqxs&JS6InS!pE>lPV6+TId451W}o=`iM}#fTspgQkoMJvbi2=*M;7Er(_bGVAMWJi
zBl$oJ61_gZ<lR1AXVZ=dAAv+<A)?|EnLw4?s#D_{v;Lb4v)Oev*)z|2&MWmyU`y&a
z@z<0Kb-xh9(w1=Iw~sy6*J`~h=AfQGE>($*c<RYK=FPIB1&KkFlkGb#n!U^EM6I&K
z)Mnplt@dZpVu?T%jtG5yR;Us?Nj{F`o-2(N5(Tfl;9-$ZSpCnU=Ou|qCSqzT0#!I}
z7K@#FK8SigGgZ&APengQ@k!5rvtFG<Kj!3W%K~Yw_F?OGJ6e#~vG<X_R`a&xq_LVj
zy)n}^6=q7VbrON9H20%;rCt`LWq0A@W(j{5PV1;$rBB#b$3E28WChpcR4RRq<SvtQ
zC^zOgail3S?C!}{c*olk?;f$E1&K~mqqt8%2Ib;#;Ugar)2#8fGpPtv$*oFvVg#!(
zW~0q*>>2wTs=4!8?W*k9>%^VZNIvaHUZwgfCyuS9HzyHwM{l$-BG7`wN!p1Uyf~+#
zEYwH$_z0GB{6^cdF*1QF>=W%9+?mWy?%!+85pc<F?$^w8&87UHowy}c$}88yop|F>
z5A`+9kRRfD#9W@p?jLrsy_kI2jus>eHH_px+7wq-92TwOQ^vANw1WJkT#yJ<VgG17
z7&Vcd-|u2;eC@2%b0mD*MDn>Aiz+n_3Lm+MD1F4m)+ZH#Djao-CHztV^C(+geY^RR
zeHZP%#ZXOR%mF8U%$I)eQ=77n+AjJh>JyEgYeYOMQ(b*W1X_@&Nqdk7{p%<JVWL&Z
z#^~CA4wDH~;iwzCWL?_!3TO7K()B=M5$%$Fa;l<mx;6$ev4<mpD!evS!$SS2MEyui
z)pP7q(GijSP&Z#?-7ewd(#)~UgK8jmFFR{T3licAiW*4qq|x7SYcrf3-M>?<-1xLa
zplXXflGm-(TxmvkzQqzcrw3awC`t8ucGy0ccFBg+>8XTtb>h#aMDf=rIx8>exf9Q(
zsDU&h!(t+e4^C2R5P=pX&eJYg$<u9>L$iesOG$rrhUzRo6+9sksKORf6%zI1$-bRx
zL+S@wkl0VVeE}<5EB6)%9}S7H5z!|VfhxJ@fonY2x^7<D`|PvqYbfg1|1?C2qNv{{
z;W?k!W{?tF+<1S8%1q<^(JDh@7G1lD#;$GD-v*`yiCr_F^K0q)E8FNzM46(@ZP^&A
z%sh5=r$nF%$B<6g$k&*~l8=L<)=FcAL^Y~TxO1VWvQ&@l7xFh|XKEJFI**YFRN<AS
z0|BY$YpLfSQuSQC4a`1mpm&rrRU4Mp-%<Y2wb?JK<*a5|YDWta;yoy8JjKj_c1#v}
zu!`Niv}f8Ji9pqH+KKbNIa;wl5%0mh#w<e%JwD8i79_-6LR4lNGnqcLAGLM1pVsbR
zUx`4~2-?A_d11VARG(#BTYuYjC(2)&7vpYkbNdxvHEgO<mS(Rpw3l`xWRmi9zA=;e
z&&Nyh(UN==J!H&FObZg@8b$NR%L9~d`fO<g5o?GTK&`@-ph|94y^XhRfz&G3cXF$c
z_Wt;aXWBSb8AS7In(uaaWjjNanMtMV+R=i9m;s8aNn;lNjdtSFKKIvZCzO{6RF!Y>
znpbZ<O-ZgUd|anlcsHudEV?i@94$zQxwfd-G-ly@pM}_3mK>*L^tmq)sPdv&c#+#d
zinl%s-^TA*H!Tg+dd{vCo<uuUJtBjZ_7e;6`LwQSe=S()Me7<d*A~^3#)_q8y?fTR
zM68=rNuPzA79`sJe#2u+2P>EFi&?nm*fcf|s<SM&rjbOT3R_5j&x`i%mQz3G+V1OX
z1G9%nWPb97Z%z}exau?g=20QGf<&yXFB7Pedw#iQYy0$_Q?!!p_j_T_vA6wbHF@qv
zu%ggvlGe^|D%umN&T{FG1zu=DLag*eou#p^&D){1J&1f9$i7V?P?e_pJMKRtSlL=s
z_^8>el^XX?fc7J7oA*B2OWRO3NI7{vKW|Sf>>clelu5M0Mw;r#nzT|aD+06^q1(LC
zf<%tL-tmMGs+x5ZK7uZ`wwIz-we7!6UkRJ-MU~vDPcx3H14|FnDwZf^#a5xeiIfQm
zcsEV)rc4O!W*lg*W~1uQW#@N#qXh|(4-nO#M!saom7{7o^3knpZYvU~YF_FiuQX(;
zQc=&Bl%G{h8+O508}mKTDsnxda#7^l%8!cU8%K{-DrC*igK1yw6Cba57ZR;<o0~zq
zLp6|t+&f4Fsze?|)QcLKqKGSh)a8G5)6#ZpYDHCz%yE3`yYb5RV)?mDw7&XB9ZJM}
zBG7`wi{~GCi6((cxSm_8_tmbJq6*Xg5d|dzRX7S3OThd;YDe<XBTIKZQ)G@J5)rf$
zH?jB>W$^&f^SU&;)oFAq(CFgtLX|wa_h|>~5RGoaw?He7D30_5+VkplV3@M}Uy<u`
zX;fCrL{*bPOJ`cqf`rISimFMGRkc`7)85_h`{lLevzJQ*s&3KVUGv{Vl!g()M>Y>%
z?a!@Z+LguY^?ahJjubiMkF;0#sPtdT%tc0C^gkatPg=F@<l_eUz~75Ri#zfB=IX)9
z6Fo1Qmx#?o+)hQHN^aGMD+9F1wpY~cw9|mQ3*9NdzmC2{IYIe-d8eUyo(`H?GK*HY
z={`NPZSFxJafEjJLbvx+Dg}z37wgwu%R_aR6aG0M5vUT`T607!mI6gOXiLaP&+WUU
zu|gu^M*{cF-b;B#xp#}D1reS^%u7X}3dfCBMb(CD-c)DVXr{4mAikUuJ0`d*Blmpl
z!LeF{Zh@-p?@LlYkk~~#jcw92S7z50t-3;^JK67wI+aEje;2B7e}}$AnmJBeR(gc(
zPsU4D+=&@MyJY?SODJ=T=Hv3NOztm}wLjf9SQ~|3vZ4ivVmA``$$e#&YK29sW`_i7
zKks;0Lp&}^1ggyawwhhV&X3rMtJi&lmA}1gMGF!;Qg-6JoQ01YQv<c%cRcLPI$e<n
zREgG#dQoF{sc__E?d7AL_V3e-ewY>{GG9;Rd4p;zL-c-x7nrDhp?Xo@#u0iyOafK%
zzFOqf$=ch<o%Wk$Zs>bO<~2vcH!P7)|Hr0`C?@(*oA&OybPiN~Y3~ky7pibi&tiG_
zyMeZ?V{x|s&TQ-Den~vb!#k{MpF;ds%OqZ-z-{)ke<A+P?F)aA>o!|`(1(1SUT|8S
z|6nj{R6dJ!fO{NY@4T3$33TCaUVP$bdo5%?=D6_hd*k^opM`Ac=z2s{8|ly1Zn$O3
zt8KD3OMJ>FmH5oQv~uH1vOncB4rNjHPIKc$FFw<MK2^w<h%9^BviXH_vUxjCN(8Fh
z(>~*e?!>d4E!>DWSJ0pR!|vFM?cQid)$#C1Ui(Zu3;EK3%f#IqZJFyoIa%zOC3dtR
z(J8}oz2_m98jz2TCH+_yr<^RkvQ#2aRk(R1&%Nswo0M6!N-OBehG(nH_RI~kqXmhX
z*Q5CTe^0P+$BPiLf)!?0zcgkoH!iZH1&Qg8qj<K;Cs_CqL9B|d%R1Dn%&u&oW=9JW
z4OhP4wTqr$-xrF0R5)3f1tc|Qk)t|G1gd__dci-I+swvx7CyeDb!Al>G-YeTy4cZz
zgf=9aU);Wt^=~PB9C?$4C3on+zD6k$fvV4YU+~SlH?sY0gpZ&3;%xOJd$CIYl(sh+
z`&z$$W@l``^InSPqmM0MU7r``NYmezJ^s$-o30N_u3grS79^CrFSt@*0~^vr`1tp2
z7G|SX&3K_m1ghj#4NG*l9r$Mw8}_Dic#f@adEb5^%<n{fUiMuqpC2)aJ?vMXpDG>0
z16xdH1Cw3JN0*j)Y<+uAX5G{F4M)rU8gIBqxnP#RM`4b?$zpjvcChVB#tAHZ%vQ+<
z5_g`z=Dqrdu$jXPlaC$yH{0fp8OgF0ekBp8!ZEa1+P4^F>rFmvnSO?&1&OUsUUS>T
z5VmfF@R4E8Cfnd`BU!%*uO$LiIMS3=`%*;R5Ic#T&e+g<$A@>kTI)det*0w5Qul*C
zRt@sk=M6J_;7M<%v1+BoSS`;|TD?l6`yziMZ?qs$XUZpi)UTWov1IGTTlTIS16jFq
zc_bebmb~MUB`32_qhx<nYmn0~e8_jI1oXM(iN6;K-;wWle1XX<CP1{R){HE5e*c-m
zZmmzMiv+6h`qSTIS<ybc7x{RbHFI6GAaS&J3|~@b61y2Ae8eosV@pqW$<U6ra3oNL
zcaOy~gW~Qgin~QA?qaNUEB=XF`pjV`j--yeKZdMP$Lt%$_8dCrjS(4%y#+t=UVo;u
z(DyFXs&iqR)pvAXjok7`B2Xn?kD&a6)$-XVu)VgO-e^H0*Rc<L*}M>zC5`C$P$DW2
zu|5@nD!dmcUs5biy-AT_dzIqW>Bm0nQRYO2di=uhcpe_NhIOiwy5}u=#;aRr_hKIk
z6}Mu~k?<cE$1~1c%FYcIJwLYZp*ks~KU-bGNg_~%Z##Mhi+E^het5B}5hJa0b0+fe
z$Kh=L?n1nm{WA|Mb%L!6r?=?rBt7oB$BH*+CL;bJqSb|wR<t0Ie*0%$`N1*P`g9>8
zg7>*=ZP)p*S;PBF1gaW%f95v}A7rQR3*ufjH!W>kBUXKW2P<0IT~FXKJ9e|DA5*s~
zUG0Ke*ryh3cZGVA4<x+0CGdiiwy`Z4#aMOA>8kbfZOSI}Xd@A*!s|qD&fht->s$R;
z@kn3k3L>%UZ9Jd1cq1!URQTw;F@ts_YiG8mfR{v|3a=*Bm(WbcwNr66gk~~0dvVK|
z#1ns9V|T}-p2_rB%CtSd%Ch=eh!y8JNW>gS<Vmd~*x<j#=$`yoSL<BAGCOUXC=sZ_
zD{HZQeppBQ-M<Rk-hHApR!F$DOyox%pJG4O3Lk57R@VwNuf;yK87~p2!u!o)ncKUA
z=2AEdbAGbaI<{Rhf4n4?Wvp6=kI0(LYr4N=SCm40e*drfJZN>WxDz)%Y^zyT<YXiE
zF0i5n2^<lNCGKNuZQ5UXSo1Fnq@E-3Ei{RrfBTqCX)XHUQ>2-;I-n3cw{X5hpbBT4
z7R#Uh!?Zp_4%n`*+irb6=ZiicJpaj=$4>gf*AL9B#3nfN(p|sl|K7cq=ts47L$z1c
zkJ*Op+Ga%y5+jCu;m=BDQpzVg6A`_AFjcXtw!fZlv7+UBvoHMW%Jj;wpQ(K~KlIm*
z|GsH!xOTnd1BuxgzVPei{;;&!MbC>A^VbrUJGQ;$)=31aaMY<n=yzYO!;t4Tr}gWk
z>w!dvr^(zc-FG%7zwj}|tB+P-+*?}{UztGFQhPFA?VQX?xC-J(xt?05(uuaPm^D_(
zvL=~-tC7H}l}LS;)D7;c6<%p!)km$8T4e#^^*_mc$XS|&mlQs#5mA<i%Bcuc;T=kK
zmIeIT3)>yr#w?qxM{gKwfDH2~zn-!-sISHG!Io$Gz5Dt>9QoKA;?IiFOh0e;{?<!*
zqV&6=Slf#n>7wV1S^t8KPl)*Yx<7kOK86NowXVKp5I6H2;YhE^_+0m~sOLo@_-B9i
zm583rYkB9$`&{?Y;@WzS^nnP2a4&R(i029ZEIqZV+7fGczMF=RJG16+q^+4~7EWuC
z>DSj2G4Pr{%R$6+zwGwV>;_S1!BCELo%4o|55eMZ#U}>&vy;@S*h&MWH4f6d>5CEJ
zqw0jAL`=%>&ywoju^rAPk1md=JXTTH+cIr=PUarH#EKRqayE+8S4Hi9i0iTCYFn0R
zRZdpzwM?KYIJ>cqx)~;}M?YGzxYCLx=K3@%T97#XC`x~G?r@JMV$}1xtd?(O7JgGE
zP*rM!vBoLzMEJ;`$(2o_6-)cSJ6h3##8p~<h!u<0Uif&P&XvVBY|2W^l?hbU8*Qv{
zg3>%C!k#D2mW$>kf&0o>(SpS3BhmUwrpY|vV??$%+sUY2Z2AG2K-Hj0#@ffZg77iv
zz-HStnvo?RiuOhe5;tjWAl4=KBZQBoyEog~jUCAbAC(DIo!w=uWWqWKAI`7cZ3}1?
zzV%jrZ?qucPHP;o-no}PfrzLmciVX)?%$CKR1J?aR!H76gb(9?Qz<)RnTi%9TF@+9
z_}K0vd;noV0#!*?V`b6psPK{W%3T%xh<VjN94$y}p}D9St8G(+kBBIDRrDjvTbV%B
z#$aRp@$9AW!4GU!gXntv^&mPNEl3=G`ANU#)k1}jzPmT8esn!TAISu&z8y63B|*8L
z5#gC9PR&R6)#rO<>}Ww^M=YHVL-(#4Cwyee7N?$|`|AD!nLt(XP-Euo>?wR~&*-Yn
zr03)8)sA+wAaR&xvLb76xA<owhNg4XzSHwD<c3V3iqALZyCFS<k2^2xYNhEp5BM|9
zjus^TYL%qNlCsT&kL=IuYWe6ncTE!{5vY1z+{i{<nj(CZyxvy3P4UX5<Wf6YkjS(m
zS&xY;h6*3wuC&$CP`vt8N+wX%V4yKu%DPJU$XdW(OG}ZuOS?^Wv>;*5SL)6ZKKA7E
z*WOaxZO}m`P_@6iF_T%gSNP}^Of^MB^zSXd)i4Ij@2Ctl{MdQwdE<(0t!P04qbr?%
zRn?E>rJgsdDif%h*YbsaJ=TvD@4*UIPgb0+V9u^}t!P04qbr?%<>|?)(G|SaQzlUL
z<mF5KzWR5T@KK|+D;q|4;-l3rR<t02(bZyk(A<^%qC2tF2AM$B`4g}7=VSgR;iFqf
zoGm{+QJu$q@<t017+vWb-oQB9etM$zPL>H&T|50of6mKj!pGj<n{B}q8TPc??2Q&A
zFuKy--M7uQ4ip(&{A2=E1><A%c=hP1@DWtAv~3>6s}=Lyz0raM#!8E&YL(J@q)u8S
z6R5J+es9F~U&05(-Kl6n0;8)$Sdc)KGUKD}Lvg!AJ_gn-t<I-@L~n2pM+*`dU1@Dl
zxwLwLh(=pw0#$FW#_40_WfMLo|K6;I(Dhh7W^*`Nkih7wUk|kvU61n<WCB%HekSPG
z{8Lxq<416uT8Qo|<>IGsv><`emGbSA<5V#N7=2wPP*o>Gl78>bnjm~!Y2~WTrRQUM
zq>CLbNMLlOnSOIu?KM3gEnmt6s)|3Nm`JhRcZu-vz}r*HOV7EFy{;WCNMLlOGlc4T
zY992Qzc?)us2V=>s~$_n?G!#HR`=8HQM@{_tF0X^NMLleSXx%~)3Q;#>bqYiP}S@B
zH)Bp6CVb=!@z)fJ)Q6J#+tGrA9Cxn=`D?o=?jHXp6R4`O=excFNV+I|RHAwNH6s3=
zC9fth2Fq)MuH*dJP3pP-)1TgGK?0*I?eLEAV`Zr4-C|?{RX=jS)JOMM39<fYHQtlC
z(G|S;?Ws3fkih6lwa#NaSp~X+D>6Kj2vi;48m-?Y&Xt9ap+T-JnC`@p6;67i1qqC<
zR7pO?mHnhUv0W{hKvmI+ul2jVxK;T0cr(tHg`TMNgBEzB1qqC<l#{t^MC#w8WCB%3
zLf-06ZD=#$BfQ!c+jNQy54Y6wMhg-cT`iV39$RefDKZQ@C=;k!b|hAhKI6LyA6*9;
zk@|d>3tnhJ0%IlB(DyBE6A>=w0GUA5qaQ}3ju|R^V5CM15*S@2!h!^<em41}N9yHM
zg^zLrOY3v$ML`$B(1HX;SBvFEUn5d?Tp$yu;)~<;vC6bq_^?;oqKY-nthjpg2m1cA
zAc4`9X8Imm)RrPr|C9+-6+iP?zvkyR2_Jzs<5U;AuL^`O2uBMN7+q=Je%XlBhtJ6b
zs*YbVB6ase!iQgwt2UmVkI#orhNA@ujIK1_o#Lu}rRQUdT_#XfbmJHO8T3CTd}JB#
zsa2%s{6YA$aI_$S(Un#cV>~r?dd`z0WCB%>Ykt#XNzhf{Bf~g9EsEk*_@iIpXh8y_
zE1hdF+E4qwGAA4LN+wX{KIOX}sk_`0KFVD8*D_F~?(Uk+jus^3xO?xazjlh^u6r?=
zK$X|%A9|$T|5W&hiT7s@iFn#a&f;JUmUA-qR`{`3)bl1|N_(RP35>25%c<pl><{()
z$$XhW)t**Hq%Lz)<b5tK^JGqR1)EmR>x~v9FuKyacCjZbMOSc4Q<*^3vR6i=E_+M(
zu&j1v)96mDlrhl@El6N=rCt4hj7aV6Efc7!7G^~1iFbsLAIV0fZdBCng%%_*y3*NH
zadEbAn)^&`Arq)dbKZ#5dF~4zCz@@si8)+pr)gejK?0*I<=Y!>v9+Pdu(P&IpsHAs
z5vlJ#6h0P*l(vbvXzuT6z0iUL#!8E&_Y`AJea1DNM4)ObRS1b(M%WYmdg!6o$bO&&
z35>3Cq(%Z&S?3y&dS|5Y@pp(Zr!LqiT^L%B!02kR^qf*!&wlh6AQPxsaNCH-^Iixa
z7n^NSr_%Lkw|80?T9Cl#O8W*4x2WQJBwUjTRP9Tbs7LCyuY`|1$ws7(?W=~N1qqC<
z7R$o8I5m{+tA>kY0#$)IlJ!}}+c(0;>s7AW9C|*MxhIFA1qqC<G|TwMh}2Cx$porg
zUK)|wJ68DEvCLB|MbCN2(R|@(K?0*IeYLgNQ*)!|-1DYPpeo&XBT`%63m;cj_-SHh
zS$=5QaI_$S(Unf@UGArSrFiw%OqoE{$kRroj{G2exPJE6oGDWOy}M30T9A<A?)7+o
z?JC9HO{Zi6Rhy3)k-Fd~;bSgE>K8<;3y`zt7=z_p_&SQzcIx@s4;91Ff&@la$~se|
z&Pj9XGuLGTRsZBPB6Ww!BHuoXB6V)Mg0pu!g`))tjIK1g6sg4(44*9%s2V~Q_+sUy
zj1fLAu5x8TbSGZC@G}f8NMLlOR#Bw3G-}H7%#aCGeI9Q_>ZgN*kFgY~3)0-D;_S0w
zXh8y_tHm;iBJ~k^qPDe_2~_P2G9vY`Uc$!;iqs-9<gGS63@u1tbfxMYiqst`GL+0L
z6R6sI$cWV5?S+pZiqs<ek^Mo&Fti|nvC?8Gn-ZzF?vV*pIej<g)JvKOAIAUmNNqt2
z5*S@|{ZvY7i_Eq}psGh>BT}ET2_I7_Qj30Eo1M`MEl6N=r8Q?tq<-8(CQx;8p%JN_
zstX^>DN>6(_4Sn@UT8rAqpQVoH6>F2J3=N<b@h}nr+!sN_!vWx+Li7rpZaIK(1HX;
zSE^^ANPURzt0B2$0#!kmjXCw$BErX|lt|rY$9FHZAc4`9>ftC-i#4bBK$$>Q<_$)q
z&X-^KSU{1w2tDVA+zWc61qqC<R3}4`x{#QWWt0h2J*#0v>Yv$!k3AHruT#A0^0~Y>
zT9Cl#O3xrg>WUPv9^8=$R9OR!NZl`k@bNXlUvsBOJ+G>lH(HR8<L()X)RQRgK5~@_
zRP`QZMCvIP;iKYJe>R_pdM)H#ON_zt9%R3<e(Wms{6cn%9W6*;bfu?uG<_XSJ<pI{
zCQubYryh%%)RkStKIfuwo-8X}!Pm#4!qI{RMpvr$8STkj=n7WZA`_@;9BJgK>(&-N
z&P{V=(<xGK?;IA679=pb($_VCt}LGJME^!IfvO=#j68ML9Ky$|8*#Rr^hEW_uqYfY
zNMLlOH_jzvNAYUnLWw}tal4VHF86E*`Ea7_#|(-L>cIx#Xh8y_E9I6_vLA<6$^@z!
zelYUX4|WS5+5jU`?`d)|3@u1tbfw5Z*$=T3=TTKAP*uBz5vhla6F!Xp8F3daNMLl;
z^;6AAjRdMP1RHtkW<J8l`2oh9`gh5TUT8rAqbudeQnDX~vdRRik}t*S*^lQrgpUT4
z{ScAbr(Xkav><`emA-MO?1#ux?`t6wsG9!G$Wt$TJeYi>qwI&+QT%aup*LEP!02kR
zyu1{r9;ZkhwOJ-mbu+CIsSoTCKAul=)#lUlk^6S2H(HRu=xVVX3Ut-d&`jq2DVac3
z;(a4eJvB)9(8hUc&h(sr_#Ekt79=pb(ihUBJ+=JwoacNY6Q~+H*vL~C>n?mO80)8{
zp}O#&u7AAIf&@laiawP6uu#0ZlU*iIwdkmkr=Fz<AOBwS*X~j!ht;0ViWVf~xI31z
zACD;RE<Gj_s0!X?<f*5X7e1Cuqti%<=v+pw7Qq;dweFN}uja>MDN?V#<Yz|<5*S@A
z7HbthmYsUO<CILG3hU5m<>lqcGSU^?9_ndF3lbPzsrI~%C#ynN@Wy_bKo!=ZQ|(79
zS2mXJ#A=6K?Px&)qbu!yG;?KNC{j<@Arq*=3Ui7KLB@{a-rVuwXh8y_D`ko%#n}$i
z6IJeaoJ61sE3>I8?AK;J`|+gR7O4Uo35>25%jK_|^*OcLP$p0%*Pbt{VMOY+A*H2C
zawITTS}b)c8+q!^V`KtVSkasks8eRhXh8y_s~oA3KowSI)A?{Uj68MH@Y3FBK?0*I
zeS?*<qv+LJCQyYH%@)g}Uz_#phf9?$Qmr!*7+vWUk8hjx?1xtgnLriRCtED(X-CnS
zB6V*qPO8900;8+NQiygG572$pXRl14O0LGON;`^6>G|k2%vGwbMFOL%#Zr`Z6cg$B
z==7INph~WL^`afceDs_*>f|X^u_A%dmCg#I9mR6=oWE@$6R47FQXg0I)9zBd>etjy
zsxU<YqbogwRs6J!6t5=v$ONk7%FN-x{#tdKQ%5fMmueu9kmGJ8+EKhqaku0`nLriR
zs?s?u-+i@Thl{a}o|UYN-+j>MwN-by`HWonkw2&!#qtEY`MmD&iN9@`zy{1NLZ<@v
zZ#P8q_<quMYop!X^>mz`^Nu*{>XWr(y#Dj0M}>SQb&KPtJku+SdKM;P)UW<pt9Ey6
zCvWVqqXmftmE!oL!|`nC^+H5c@aU!0?f=o{zdAx9P$jqO@u!a3u`?N1t9+;JXh8z|
zM>Cl`ZM6V8t*35=?RHeHdi9ZCDSn%kQ49IVL~kOF6X8q*T9Ej9|0AFL^j|jKF8a~<
zP+cueoyyGZ!!n6L)js9Do|7q>vnUaV;%aMm=`5t8l@{7jwWak3ey0(AMYXe#k4*Rw
z(WGQmcEMwz9W6*~tMY-jD|(Fi?GUXR@!CZjS)(aCdVi8cpz8dqSe~Qq4tA}DXw`y1
zC+!HGP1S7CP&-<Xh?@M4-*~@~PP`I6wuHNA@qK9b_1!RuK-Glyv3g!KWPtE-IoL_7
zd%HRNer}*0El8ZJ|BfGNu%4Y;Abh<3_(`pBgDN2Q`$`0=JiUxe(WS$}$FcFR)b(_Z
zSK{(Yc2u1m8^hhUEM$kq7xIybWkhTz;t>&OL1I#g7#{U?9-A~;wCdQPBWm}4!`Q=W
z`6U8XnZCZ}uddBv@wY{*v>waU*B3^!9vg0iqXh})CU5w@7a{CbSK;H(;koMATw~eu
z<f{^as#3pS=`;PKuZ52sEtaX3>9n^AM<0cw1&N@CuX%$LLCm*<@bNyWg?fBP01NWl
zBN3>Ie;Cc*?4HW9CJP@g!_%ly?<cdG<qC(R1&M7LU-5W45iXetAA@qAwKu;V$cn}m
zkO)-m-uIGQA||u^KZTELL^LB}C=qBu;$7?uo;YG6%Va4=M7~C8)FR}u-IBk;(SpRD
zfM`B>??m>sj%ZcS7LUCPyq&@ly@q%pfvOf=pX+-phL5aQDp>c>nSh5g$9SRYV%Q7*
zD_0=fUZRkXOhlv*O|ryzp#_PdPA_<HTp%0iB3k8fz}+@_)g<=mpDx}=peia)q_MZH
z_xxw4_O??>0NZ}%oHwenPKe@7^G|1|G8FQW38&8OZ5k2bM4$zU?x!R9<%KiZ(x2k*
zC@!14*_LV2NLH}P2Z=yc^0O!U9*Z$nVVCW;Ykv=61HYHDqRQU<8PAxokY$K<_K}G_
zMBF5z8xd$h;?Unu`HARd%qvQ?s??QFwk$Ed*m0NY5`n6Dw;t)y$7t2F@fp~BI$yM7
zmOfTgEo$_H=WDfzRlDizBNM-fm`KEIBG7_F_|(UIX4YM-_65<Z%1>OFbDO3tVbef~
zK-J3c5A?Tz(W)jj%d!&{6gIHmJS(bdj(fzdCr+@W6V5&|QHzMnM06$sEl5l}`jFon
za+WpPFIrXjNL}{26;(|>lL=Jq>T_S885pf<<KoNC(wVYv+HbX@1&J@O9`II+Z?kt>
zgpa=0nz6O6&TQHKT@rz+)e-mf8HeHHx`!{zf4dla&}zLEEl8BC`GD_k`<ywg5k49&
z=*XsC&&ZS+dn5u?J8In1>i|MViCEG-4}H<t^OSA!x^QcW4fpif%hQ?8KEFrZ)qft+
z&&}t2*8BY3urx}QdBTT})t~vCzh&E+e9(#(BxE1OnsjHc4t=w!HBU+es>ZCp&)v!<
zu(eBtk4i)wCE^khXh8z|M5n`C?#~K$xMTab`bm4)=SJJ#WgN!LKIP8%iJgqT#}|A}
zuZ&#rk#-BhuP7|}w>$H>|I)tufk8}}MdR1~F3<NMy<$1_sCMr#<KKUsVnobbHH7&r
zJz-0FV7H?M36By6A!y1#+RC%&^o)%Put=@KmY{FC9`A=Smz}$9y*{3kT7?AqqYBf|
z{_J^snj!a7?Px(_&C>h&%(B;%57duB6MD1HJ7aA>-1bWZs@jgb$GhKn!;F3m_|}Gv
zq*-71#C>*D#eKiehgW^eo<4rhWFmlwjznA{0xd{XfA>J2Cq{R9N3FVefGXQ=6=EHd
z)<^`ZroOq)Z@0gc(yEGgYqKphPi$~zg&kE@`aR^iuU}$a|A}QX;Y36j5jBWF3lh^8
zKho!k!;inER^2F7naxbB%cfMCArYurx#b~mQgXjJR{fmVIGQIu-!R#ZszF5_^J%;H
zv(XRVFqvpa#0(-%5rGyY`UO7GXMIDrzM@u@*ph=Sy5+}~Mzxm+RAt)qn6FA$nbNAk
zwO`rx(H!pHMISq=YUY2+tIS-*vLB0PGLgN`E8BD;+FkOoqXmim8=mR2z7gIps8w(3
z-L&1_Ie<O;;UW>J>h|wb-mLrVlvc%LS!OFtGqTXVY3-<L?;Xhpe4oui>pf>O@r?)<
zA|i-D3lckHqVzf3#%0f_RojmT+Sb1u$NHZ=5{?9_BIpD&cAs+D`cs>+WE$HCn#08|
znG}wyN;97GpJS%6MXR4OnRs0yjqM{5$A~}+5>pzz)aO@kt~{bv-5<2u`p0<+3-&o4
zh6Ji6PJh9_)t{Kss>4Mp*$>hDDyn9<Ct8rG`1~c$6*!3{+<!<u+%xnE-|}q=>wPjb
z6bV$Bb33Ewtw&d~PbVKi^@@6;1qu7^SNe>s?2mio<KIUS_St6w*<jat-bkRTWo)!Q
zy2F2!_olBo65FenXny5<c&Rs9kYL`gd8Q%LSiSth$Ep*f)Mv}avnL04O9ZOSHN)3o
zRjd|E?tu1cBKg>)g?gg}iEC-z>T|g9>^AwBQgO37J!B*+e#T-&0#$0gH~PK1rDId_
zG2TU0#T;&S+3Z$SwV&~pmx-Cp_71wmWa4KbReeoF86wbvL_pnGeGb?B$PH>03%;qw
z&mO=wjj1LPsG2Y}Mt{ybUwlWcI!WJcpQIUCV&BGAv>@?hUo3w;bQM#-UMC-~#^lf%
zCHS%9G3_J*RqJUb9Mob5(+*a((HCx0GidwCN8Wbbt!P1Fn9qBC)^~B#Rq~-+%%NS_
z;K!6dLnQ)LvlhJ5qv&w=7UW}HkFwf*n!|;ZnrcOr$F}!8-TeJ*@SQ76CiW9?iHJo+
zpaqG8Iq0l=n)SU}M(+^I?fR9q0|)A|yPFqF1gdWI{Gh*a+?KDTR+aMg)$Y-(Fa7#|
ztY|?ZQ}>Vjz}`!2b^+bTjHcRxoGz^Yt<@5Ns_0c8`I4mP%-8)a`Pf^?m;R=AG1mC+
ztyZ)kk$L_neb#rjas>6`#@VJ?^Poa()U%xufvQ=Q(Gl<S&Ka(ekL(k=Yuo5AR9u>{
z%ZjS6mp<_ax!<x+H!d)lXh+0Gnvtao*kwfv68%oZ>GQ<IHs`5T8^`z7K4pltwV4<$
z5vU5y9jDK=R#<*es}>X*tYxIR=%Q?)R#aVyj^hoZ(koxHoo6!fHxb2%m`em&kT5fB
zb9S7gR)wt^qE%mV!shhQE)l3|*V@SFg+ED4M0^c#hs;&Klq|utu21=0)<wBJ+>PT2
zu`&0a^2DBf755HqwDU7&QDv$}-K|FSac5{j0?)9ezh67KJoCzPN^O~2CQvnR`!l}(
z!ce721>qw$17|-Ql~&WlmtX_@pYXzNT&c3fO*-AU5Pipet&p!$Z;c?{PN~N--}zzx
z%t|n{;OWMAPBQ&%j$xcRhm}^350VK~wU2+olj^ip`p*<T-X%0(`!4^ncPdkqp$g9w
zmWdMey;#LcL)69<N-?w`A)lt3=0|O|YQh|KM?^`9KowpmdVk#aW+(OyQ;!yvuOJe5
zdN0ixh^R=!;Zy{w@M>Bt+y41r>zI&V%lNxI!!uVOPkq6w<eI6J?^=Z8S+jIfVbC4h
zvU@Jtke?n5El6}7@Pc1?I74ymRfI;jTR<*$ba_V2_1}^bfhs&Rms+(a9m_HzyOvKa
z%g};EjWto+H_bF9+Zo~GV`z4kDNj0W{WqCF6`o;CwdWt5S)ZMs)TxI`GqfPFw|5jD
z`+bU1^1ATxcFsoI!qerosTV7<{_*rT1}e{0UOXtw@$A=JD_`@sYvwDrrxYgQ>-k{Y
zkCGl*>HSq0T9A-WJ#ARFl`T)kYTBJqGJz_mrEmDHP79QrO@)ulD?Zq2(-lmU>I&j%
zx_E8qRCyv?iLelX79{ZWUOG!}+<jYOWjF0adYM4gg~8GM_ux6onMBd5dtsrru%r@N
zon#M&79{X|VY=JDZm=C)TTb)HQb{6Eg`-Yi>P-!^Whq=r8@XG)9!TKXzZOgJ;4s?|
z*HT)`R0OK<+K`W<Rq5~B?Nft$mS7mw@Vsa_!tLu>oE=;6OkKXM6hjLVc=9yO$huTu
zncAFIb6hPc5vW?2H<G`09j#o+FXB~?$fB%c)MGV!nlcP6NZ@(cR2voR%qFk<q+Sj!
zEfJ`a@Ae{NO0aozqtxwhN-(q_f#-TtJ+&<dn{hIo=A5~#M4$?vG@6CaIbt1Jucp?%
zYjw7<RV*JhVxe;NxGTrgdy7<l#}5TBR5JZ7PJwcoS;AUpP<8ESn_3JlNXTd7e*ZT*
zyy(yBTFbXJB?48?a(v)b2QN_imJ&WrmR_K?a4Vukr?WCV6}DyJ1YV#1@KfXbE*wvC
zrF*yaZZ)xOPVL7<ABGkr0>a~Y5!YGDu(INuqLFRpspoFGYGFfd5`ii_`;{u_5(CwC
zKZ|Pxj(Rb)AmM%J6Ax-RSE;pJ_{gIau<n~vM;q%=m0@r39AUZVmmkfskG@ewtK6av
zLkkjkZZZ9RgWiwBPybs@o0Yq^M4;;T_z!%W#{wlXhZx<<d1l-57pkJ&O;eYl1qnRE
zn5vMD=T_a?dT8gP>qrEuHt+q!e|DU!RQgBsJaf)!>dc%p6OZv?Xh8zcFs7B)pi%0B
z5k<6%;}nTNl{~sPD^ydL6)CH&e&of_f`oix?}+l%)DuK3N=2XwuPl8Hc=@TiEZa}j
zw;^X6t0(bW;p3EqA%(cFXClA+a0;ELUWntVw{#lflW2A9$2hh2X&;6bJQWsy6Wv$q
zGHTy{omFd$@{xQXf#=K8cPz`&Xt}g&YWq(0Bmz~Zzb5fD+E68^zBu2ff-QrVFzk%l
z`(izY79{Z0TdE41kw$yF=b9ScUnWpBEI66(8SJlgDI<KGX_Q_|=yY1mf4DwF6`t5D
z6J5UK(}J2WQlCGq$IyZVo)%2~Sdd#QTyK@i4%L?kR2^#gg;#FeMJe=KoEtT~PhRa}
z-i2x%-v$gVNXTd7W~`T6b4#;I&Ge<dM4;+J;1|Abc?TtsPPU@28p|wD-xVpMeNPpy
z@H}jcMD&fxLsh-=Zw{^aVjDvX5_qOGtv~u5RQKP@qt(776R7&}&u1R7Fi4qrPF#<I
z^TSk@FT3_=m%`A31fD`|u^ip~Ox=C?r<xEU6R5&FpJsh+-l$ieC#dfSa)uTp<ddMQ
zwtu5`dX}JO8YB~_!smweAg6}du6L=d_3c=R;VcYKu9s(IVPivVv0W=`**jHYXh8x`
z%BQ~}-Mf|TNmw<l&+*C<fvUlgZ+XSG3l;wiVt!R-g0t<@jB48G3Dp@|kiZlF=^Zuj
zh_&3vn%XiCnLri3gXxQrQO>qUPPH`Uab@Z4j0B#{Pp71LxLKQ*uc>ufRYM|Bg>P#5
z8ZfSywlZX>HO~xR*1gwP{jZ!xpK<1R=JJ^;UwOU7MU=wV#NGb1SaEH_lRj4aAYX<S
zB=A&di$y)<s@?cj#kRJIOrR<vKl#q@qWroge4Mf8)n5LdYwNkF0mHvWiKnFDU-z_F
z_HD?awH&+7HsV(Uh8867R5r@omCLI|FPLk4nb%h$P=$ZplXkGC7SQ@{nPf}+-hlZB
zf8n=&W>)6KJO4k%&H}oM<NM<e_uv*Z1Si3gKnQs|yD_X#XpsWNt;MZCDH2?YTY<K?
zLvanfUEJNB;7|w>60FGo-km)7&ZGUEf6t-ko!swd@65`~ox8I$2JYzD`R7+g_hM=F
zB`>%h`}1Y9h7292wJsDT(1L{OWBiZVt-&4XjvuEIs0#b~m67jgN_`ludFODfo07%q
zQE-ZuIW$V31qrMZwW5Lft(nhCYvUrK1YQGN30%D%xroRfUs@YQ1X_?#_cAS-F26NU
zRM7TkQVCS0qpvvzkI0~pe#G_Yu_3=zqfHs@)TKy)79{YzIUL{I%Vqu4yPG!Zxk{kQ
zZ~QA`-r02eU|Nrm_Q=hi%j(~~ua=MyDbRuhURj!TzUiS^yg;0`eL$GNT|9Bu(3N2c
z#ybC<V%9uvcQ0*yXimr*r=2DOElA)#s+1`@dd4jEZE}$z#83!S<+}O8*bo^b@^4}v
zFRJe}xA#sja;(w?T9Ck<S82wUbHCZOLu!#bO_)NU3fCQ_w|!|e^Tzp7!f#R)fqQb|
z9+!V!j5D4W8zJ_+;i#|0y~?g@)hh_EZ-NC{kVr+5{-GyBDcj1i=(~ogD5j>-qgh2E
zLKB`C6DN(Od1T(o4x;pB@o|51!OD_i(H~WnQXz48&{N~|@$n+fd@hyGv|w{-krJXs
zqfmuF748R0YYyzHZhp0(n8>jpRG<Zk5)|oIC_PbBwIlszSAtESs1jmufJ&gMkFw8b
z)jc)LIt6GfSTt0iMImT6`x2cdi?4=rJsPZ@ZXVj1UsTAX5`93W?o2v9ev~<XL?JP;
zeyBhT5)ZuMjT_Y#ihQ}*$AuPC%yWah#qsf)LZAwFkfnLAC6<~Q&t?}nCkufVBsLa~
zH<o2yB${PsA33K@G3zh%7RB0Y3V|xz*Vf^<o^_eIyiE@A!xK%QMIn~Q8|!Jd$hw#O
zd<^|_r#W<Pdg0ekR|s!V;hpbrR6n`iEPOY!*b^rNT97#QBHlPV^Dpt?9{X7P%_ej2
z884yv>I#7>^@)l-lFC|8&eDFRosMyTUtC#L-RpPVbBA^G@DZ(S^$2AbXe0(De`yTw
zcT4mM<5Kwsr?R|<nA+ESR037F*R#X%RhyL7h3vbu?i5p_1&O}RU(&8RkAzP-_OZ$<
zmGx6IQ~T$>N}vjRZTjAzWjgEIck8u%zegzjITCNyzchM2Oc2cqu#XFiGg=cyEY&id
zRtZ#L-%cxxH@IRRPxX(M|7*3~#T9$81$Q{E{`kP`)B2J2wq3Z=wj&|3CmN~y92Yx#
zbEyXAd0;NP_DD-XBQHD_s_@EE1hDnFx#htv?Np9%<(eZA-96FBw(XoK(TaU6%=^Zy
zUHh`upt4G!3a>wXOO|@PGiF(k7&k0H)T1m;*LnlRRm$Svp1fD}heokn14Z03Zg=lq
z_SR0hDvE+d0t8x+z}<Eoj;KMQT7l*j#Oz-xDg>%pPQ7m=o*OEH?7V1zYlN1oU3rl<
zv%kPyZaY4`Ln|{+6klD+Z{W_f^euAGZ`y$ZrA7Ogasn+#G^E*|OIr^YM>}y8zH9Ap
zExMS$*gT}XLZAxwvZX6{DO3x}5g_7S<po-hQ0wtWjS<?06y?Ogv1JtkRq7tO>+XAN
z+cN}-LdVJrv><`!jk0Q;bBQ)<UTd3H6%%{g#Tpgn?-T=%6;O7HT~g<U(Y)pvQOe$-
zVoj04V%Y1;+NO*p1X^&XSln}#*37I?LM-TUKwDe9xI&<+=d$a@mb<q^Ui)29)q9o1
z*zcxm_fHfN51L#vLZ776EA=R7;I5%XvtBd0WlXPcjpn@Q?oy#5{rFZ|Lg}IcElA)l
zr4C2wAwv9`7_9aF*;gS@6+GsuaX7QLUh_}(;lIX5q~3K+`)Y1cfn~>CW7T?$CL;aL
zYg#oT(1L`zCu^pgB}K#AhqT^@d=&y!U#GfmG_M>l+ScY$t&AuyB1SLMjLyXbT9Cj!
zV5!}m7$jP~o~lj$v#3I#3eP%4OEW5p{NJzCw)?5q0||8(*L{zjv=@C_?e=XS<qDz-
zuMNF7&||c2*L_7`sQT36UfB3NQY$KAv}HsXM4$x;+$oyg%1r)EtNNg{7<03%LZGVc
z{yWAGWhaTpw0j7})X%nQb$;{}K0EydT9ClKrRl5Rv&XexM-~=$hLlzaRHdL9#^27K
zFP?wRZ<q4NJl2A*<PbNSml0?|LfzllX!$|w(c4R`8BkgwQ1xi&EyGoFk=W6ceSB3i
zPMdAy6yt7`7HB~N_mieQ4s(9g&ZNjJI_)f_5U6T=C)U_rdaJm(o_*A5{!Gg$@`$S0
zN(fZp4$UeN?3YRGIF?+96D0*&kifm3DJPRZr>J!#QCt4FghHSS+c8=v^-(5~V`mDH
zqels)g+l^&pmsQt5z&)~{2m0Vu(hN0kOxh0RmxI9+)NWJaLkd9_69t$Yoi!VdjqQD
zk9`9sxHKZJ5rGyY)IINu4HB*bA1aF7^D8L?sxD4?WOVy&Abr!oeeK!J6P(59TcrL!
z1PQbtfxR}ZtCqfu^Q2#p$UiPn>Ccg9O*=1UtgucP_Rfm~vz2k4CL*f`fhz3V=}V;e
ztX8@m6U}wYBL!wQanCR{%Q<9Lek-<8keR=Aq(BQ2xJMa9856v%c7YLQ`#ez!fvN}I
zuZ@hQqV$cYczpgcZ9Xe<SAaQYeUv~866!u!PYZZkk;lT#4SiGsRm}>$HYP5Q)c2lb
zA7kEoTbnlrm>G6N3A7-A`)*OT_E=%7MZjX$lY%ONDz6r=jYlN{^_F|s$NeLPEODuu
zYgPAZ0xd}3ZeaA?L{K4XZPD60()X;c5U9fZoWrr=Okt}><{qw{v(?NU61c0G!_oUn
zVJpwXHqI7{R036)#iMiOE5xR>?X@kn3JdI!amQ@6cb@!rxLBI|k~78VA_6T);NIJ`
zPEm4Q%$Zt6TX$Y1P&K&URU=>8{QB{E+}Ab^4j0wEFFH%M@fB!60(S(bHt}SHh!``*
zIq_H#g+SGQan<-~Vp%<A75hm1IZ9;y^QzOTS4f}*33d1E>J1{qXrBnzh%>$lfvQ5`
zSB+b_%Im3ZAE~ENuJS^G9eMT^5okeTva+Z5;ii$|dFx15+vzHSDxB5haBP@bT}=L~
z@QxB*g_QX|NZ=mg4o91*VPZ<Fx2_6peH8*#IQNHgWSO#w8sRgv>&+r8oITF_VmohV
zvv>Z++254K>6c9$Xggi&9voqz1qt4DI%mUFNqc(#`D+T{$a_RP789lrsKPnoyl;34
zu_ezD?I;mwL4tROUY{mj$lbG-E{N62ynL&9pU^Gd)A`p4R|W4CjkCN}qWr>GZB61^
zEgunRK>}x((;P@D)o`lEIw}<ssKV0HTYxp|wF<|wip|3`i+4}HcKxv6-KBAsH<p%i
zGDI{bVj~e~K>}x(QwEZ1zJlse&ZFk2!aC8H7KI0D1LJ%|uZLAF-f#Iqf0y8WoN<;n
zmX_w}7aFLICZZ=1Xh8yJnA5%)RF9`evx*ZQHAfZJiS}?CnL+!#oxjksSFw1<<m&r2
z3f}n{XL)039gg2dWza?wVGw~9Byff~Wmu>lTc{r2dDI+LSSMP^^X#0^=CJ{yRjx`F
z?}hC9VXff3qH&ftmX=n)d^#tz4iTM*KnoH$!<@dBrJB#7dN@65jw-AZt%MMF)U~#3
zkoYlefW^BG*D}@%-jx~WY-4HZ3jTf6wT+0bM4$x;oK;S7;@&x-lc*kn9yLc5)``B=
zzuUs>9#uh9bCkDuAKsrvY!$r!G0woo($XBr+bzt=MARk%ElA)Tahmn=_^4|I)uWe3
z%~6GQqWo3=73Ri>lEN#8zr}kN_y1#$;Qfzr1~!(KzQ-YA6%m<;KnoH$`<pToNj3l4
zqvoi>I?+6`A~(%LoxDY}#-%OZLwI%I8NvHI<9uo?Ew$}FH_g1Ay+s=$(1HZc_;xsI
zQav_MJu-UK9938+TKUT_ofYkqRusBZ!s7jegRk5Zyqhu3r^eFKd<G(J5mA%~v><_V
zxoLih?@e<h)jZUr=BUCt(fYeh3R>qc-PYFaFJ|#Bz%4$$r!@{f2%H^_rKPyNaY3ui
z<=fguBG7^a&flha;Z%=bs2=$}YK|(b6TQKD6Kqw_K3dD)($~Vd$2g0bcl2%gPX;~k
z!8@8&JZ@k)tMsk4+Q=+LEwmtkbE_SWlSE9vxmIiEL7)oH2%X(Q<t#IHt=5JJv><`A
zziHoaI=h?b>@N2>yQsqRMtRZK!PXDCMr%1dYL0cnxz+Sd!`%=ogVjyj*|eyI79@D@
z++@kT?H!isyX_*H)xUZ}&Fg#-g+NuM;m?gl<Fo6LnRu3W)f3@Xc-chfKWU3tXhGul
zN6(Gv1B>e!f7nBWPQ;>eiO$DFpalusFPYwkcZjlhrIgA0eG~#!e58ntRg!$Hom1Uv
z_xMeycDA5}D%>MkCA?BcS*PD5?&y(OmdbrBB-DM8qo^MB%O<+wlIr0mP{n5?aM4#u
z=c*zR6U!yKJ|vwhw*?743+~;IsXxyXYE@m@!z^`No?SPAD!z~7b~V@Kw*dEu7)3-y
zBG7^aUw`-R;10(Ey4x?@Tx*V?dlv~*@m-l>bT?go1#y&!(L{750xd|W`-W$syZzdw
z+vYO5+mS#OKl4xe57OlqBN>ReL&ORq(1HZFF`sv3H>oX|=#$neKy3*UsN&YH){GIl
z{8olrpOHjlCju=<;7;=n#~RsxSQ@pWNT7<_d28-iU4B>eJrQR*d0TafKnoJwul&(w
zkk0)hJs;G6Y>FspasPn?s<?-X37nwIFRDrsv6+ahM4$x;?olVc8lrP#Kt8DF>>X9X
zs!Kg55~$+7{c6Z0U4DI*>0S%7KM_@kKnoHaOUxcUOy`)0*3zSxVO7~6t2f0ANT7<N
z8t1}Ey8KeFEyY)xiD*XzT9Du<s?DWgI!A-F|KQ0vp(A1gEGI=vNT7=2xhowf>hc@K
zpU%w*?M6gBBG7^a$B(n`57jviru8x?PMp%t-wLBR5eZarB)f6;I9-07S&oRmh$u${
zT9Dw#IUpul=MjLzQA<Y1*0&TPBY`T8;Rjb6t;_FHLufS7FV4s6Lj+oo;4wqT-TieQ
z`_Nt~G&V?eEUR^l#s)~BibpTGClA%-7rD_y_z|(42(%!<qot{T_t1INM|o-*6|GEs
zYx>cs2nkg2xXnAfuP(nu-b_T;%eST%5okezM}3a69dtS7oJ-@uE_sibYiK-(1gdz1
z{J2pEU4DhVm54=oj+keXM#63j5<JG;bEQer*!kzm*+iQ5GtAeO<!IYYpo+hD|7LJQ
zoxgXd3`;~d@ubRhbAE>i3oS_SSpD}pwe8V8twusQfEknnxZ#ll!0+gBbWd{!m*y6Y
zn)K3=WsS7Zg2W#)&l_)>rq^?2<5Im`kzXu4P)RH9R0&ko=yk~$Ud>1E@{bo?!S_V`
zLWD07XhEX)hjT{4i~M?*w9m*#&I>-`WX?X$w!2gURfTI^vggT-%9ojZL=aIwb023U
z5okeT%HeZ1QMW1k(1}QstB*_fAW+4nZSc32R1aSwN@wolYL!$fw*?9Ich?!7RFAh*
z^JNDrnMIOn?j}&BUcom+^drK3cHP$&2|jN(&NWE79!XcwbYDR?fhxRvC^ONflGUB^
zK80HP3S2j;%`Z>vOi@sQJYkKt#@TtFe%X0Nhb=#quv$^RWZ$)-3V|wILyBgx64923
z{Y0Pz3BNUu?YvJ&YWCsXr-W6FGDTZG2vp&EQdFv{IjjkkFKKb8xIhaMxP}zHsU~75
z5lx6d3lhUSJhF36*AjD6sqPXHOhiKu0#&$%6n!5x?5$ax@;;|>loDt`0#}5h7LEvC
zB90M(79@`T{m{-iUB1PoYC80-=_2Bm2Z1VF9m?SdZM)xGO8JsPYsv_;Ab~4FQ8ud0
zesc{G{zRY!iC5td?3~k%V_d3B?e?2xiOB0gpbA%nqB%vsjW-8SzNEp3vH~qg;QCIq
ze&WpWW`80gi9iby<p<xhb54b~aH-7c<IQ_SH1Qx%h3h*x9NJJ{a~$PM$_}j{(1HZ6
zy+kqG5MOf?5mkvm3lamD-?4K}tLAd477p_@dvZ?3gFqFo!$g_XqeWfIDPQ6>DNvvV
z30!-L-rXH8>iUz20z{w%iB>0X**T{Sqq$VB14UhPh$!SipbFPvqBp$#=Q+Dj-lzV|
z$^tD&;Mz+L$H;#3oD+!%B?2u-^rwAzIp-ADol8}mh)G0L^&n8yTv^j;L9Iyb5amk-
z4-XM&K?2uaqBn6woFSq=5okdoSIrxC&goqfF4cvak=pftAy9?uFwyMjI<vI(lrISr
zPJtFAaP1{p*O`d@L{udLEl6D5e9g`|U5esT1rc%SUkFs;I!rX$9&uQkLiv*R8-+j%
z61esfy_Fe$STl)eOaxkxX#4F|JLi-)h)eZ7`S_iPMjiyJaP1|U=@grw&8J+(u~UXX
z3lg}JlEcxTh%h295`h*Z9+bLb=bW_ST&m?a60|gwTZ;7{P^GR@G+=55;h?-vzR}?V
zElA*sM-E44BEBOc8xd$h;#JsXJGZpSn@iP`i0VXS^&n7%D>u<Im@KCV$~juAzCA*q
z1qpXN$E!op_<VgX(bMdveU&}x(;7=`L88*)OLi9LTsAJ1ub;QLT&<y2sY;|mpej*2
zZ)b5*3}YWYcMFL~%HqtJ7%9+##N-R->@3cuflL%4!a>9=BG7_FxdxYvX3I<J=e@X8
zGX@r+NX`-c@{~%TijTy36zL-<StTooBII1N)!4_K%i^^^F%F`P*TSmS*807)d;Y!x
zEl5l({oIa_OI_i0?($97t&RsPY5kiPQ3zCRj(=iD$Yp%F=7B^UqzL&3BG7`wmc7sI
z2>I$Q_R*MP(C@PLah9Z*6bV$h^Gtrl*vF4V-16$<%u57XkeK!Qxg8<*zRNy35YZ)T
zA6Fg^0#)prqgq*y=0u$K>f<V&R4TUx3HHYkvaCmGs`)PmE14aVYVIab#b=$PT8>NU
z8(t!|Q-s_%>Fl~KNbq^%2w7f_cdaW~UE5AKOH#ax$3hjyr94)X@$Oq9rV~+w2(%!<
zku#6s<a)1LDc)^NBS?;S6#`ToW%8I)#=A^>mqefikIPXlk89;xtR}^xBWWc3J;kC(
zpo(Kg9y`nEbvqH0h~Rh^El6;T%HwmnvT9N+YH=)z1gba!<Q#yEMNd=o>ZB3<J|fV9
z1V@~lXOOF&rl44q-rZS+DNaNJRUFT8E<;9^t%w*yM0q06f&|BpoG+1UnC753u`lII
z>QK~&1gbbX<D86)6DLtDx|oPiBG7^aM}wUAk?V^dpr~&=<$VGuhC>2X9BXlINk)D1
zDYEQMgiZunkl@&k^H*{u&y^IzEus8Xc8bW5Kov($oFkJlT&E*NT?>iGMFd)q;7E=0
zaB^MFH56a{%$YliuaH0$$3dLylMz{6iuwi-5lIAEkl?tB^NDhm%^(?HS%WCPLIPDB
z)o{*I##bRp#6Tj@f&@oVoEMdAX7;DpXD8)F4T_eKKo!R*Lx1a|%V=p35NJVyV<OJ)
z$`vplQtY#y^1E#*l0gDh9C2_CS;juiWb9*c?1L60IKtsPwOr3~3`H^xDNlWz;u0iK
z#qmSwimh}R$=s$$#zn*(BG7^a$19v~mupS7qbQ@+t+l2%MHxt-ilYI}>C3o;W1pf#
zWG4bGNO1JQ?+wb^YfZ+M%_H6~>0$nGI6@&%#eF-!n~+h)bs|#Jn}#2WKnoHaOYl1j
z8D;oV%#f1am~fPV1gbb17%;kWQp`}0h%h2%5`h*Z)R>`d<|1N#%9lHGrjAkwRJn6b
z4eYpNp;k;py?PTmzInJn3lbQkP+wa+LL4pr-g#8>v9xb*7|+rb(r=bYF#ef*)u>s}
zTW`JonQ_qPh7owEgg&cy0?mzTIZ_v?s+7>a?dNNu1&Kvnt{M|>7St!Lenv!vVKsy(
z=@S}xoxbpgW1*@&{e2e2R}*X>3BObm6-U%|E{-c?p#_QCQCE%K-sSayE7-?RRFB?8
z-#ZU`)MI_O8^#iPC-|tWS|^HLYek4T8{RwXJAEuHI}#ha-!KZF&8w#_$2HIA6E33C
zmDY}xF02r!n)B+aar;O{J*$gL^>v0&VRh`Pl_~9Op#_QXCpU~1GrjbVq3k2Pa}_au
z^>}UA3Lk|))$Eqn49CZmdftQVqvt%QDEzd$wlkNHg%%{5q>eS_b<e23)9iX&s3KD2
zoS@~-s}iURx_-@Yefvt(KF2<i)hI7|_FkoBYg^Pp3li@$#TtH&jQUZ*J`Vm>N?g5c
zY3~z@DFmuQR$ez=y}u<c{mnjtdsP&dO0ChleeGkR1&QQ0VvQ;BA4T?t>_ZfsuT?l+
zMijeH#)^%<W8}U*QJkLo+%Rk3Gwu}JE*kxvU<56^XB<v9QiSb#PQ;AN!?g;T%8I$$
z%UNhaqT<neMzJ?r#hF*^!~b?|t;3b_V!)va3W2Jdv?9>!&|zZvW%l9q;{~l_)j}fP
ztCV$%=6^qKut<b{^V}FjI|$}zazNbOkzgF?bH`}Ac8WMKl8ND8Z`W?q>P%Ta`dMf}
zqIIsjMggzAqUa$m)n5zeYVqeviadGCDFmwUjL<%DnRjR(9~Two4)t6iaql$E16phf
z?Hc=dLBvZUc6bn|!t+LRSke>`t@qu~UeENk@Jj7_9BZUL|3QpxlwjbMrM)v#7ZF7c
z+|WJ}ffgh#CdL|ly+4Sd-*KsmxXOs=%e%EF&x$Ans`h%{Ft*2C5K~_AeN}E~Vd0zR
znsy<1aSJU-+<$)4SZO{KEqbw!ZaKZh8RrYF;I~B;0#zy6#~P;=?i6kE@)g{EDwAl}
zJ0*S5QQSh+okF*a1DWoNsD25CN-R2=NwoSYr5H&BT97DT>y}Y+#2s;G0GDch&Ag(^
zjOVnYXEB99Rnf(<#-9N@MC!s^s!<V{M6q2dM85YWEVLj|tI};Fc+Yu}IGuge>7G&q
zH}w+zM;2EIRK@qaWhCBRBqr8nA5E)1(N>PmDSkFeTWCR|^RU}S@}Xx$**WZEYw~ki
z-RS(HYC}JTKoveWv`RsXCz@kbPB9~AY2}GRB31ltBkIC&@n$*u=+g3uc6nt^G0B5K
z6+T^*3tyJcS*LI%(PvSBHIKfct8|D~<1ZR-ynXx7SX6YKSX(F22<q{-@$<-aqGr=X
z@-ZuVt#d_#AmM1D5~z9^{Kyy{IZ(_CjVIzs!NSf3EdoX6HbE9zkXX?6k#Ya)^}_iR
z`?ys0{f;*G0)_KcphBSPb;dYj^82CUR2TM<`nw6Pfrl!HmJKRfsQNqaV<Y>zjbifX
zL_;NhZ#u!%o`_CFpaqF`k&g|(@J%9MJeMkYt>-)Dbqf%;x>iyMRFxk}UwY>lE`0lQ
zsdDxi=c<*Vg1C|`*g{o!ia4X(t}UX+{6s?~1_y+gBmDft(?yjnv>*|Zmgf7UGDW0|
zOLcu}Rx|G)Ke2ya6@@_6#<fq4l<g*p^BcKT!~YI2dwwV>)+L5mXhGs8%`bVq+7!V%
z*+-c&S<NMl{KU*dRTKhMZ#F$OnnX_&Z8x!x*B1lKEU!w6PVYl3v>?%R!xLkB;oV}y
z3HEXHmmy~S*dn6qO_e~^<~`4iuO`kDOCGb2!$T*SKP}5Ih75OFXhA}(ernXMendq4
z%|14bSZChOlvTtw5ek8-y58|d!?}yZu0-}>-FRRw&y}DBOwq00l@p9~*LI5eWnUN_
zRy{Xzceo>#6@F>N^@ul48}VXu&`Tl~uDfowsQHh!Hr!AMRGp}tXyjRXN=&Wsf{2H|
z-ZSTi$7@F~7#3QP7``mtc$f1ftqR9J_BKjkt>}MTJNHH<Q00@DXgo`QTl8zjKJsVF
zYGrLaOPf46!m1bk%7}WEQlA<9!l+~<7-Q~c)AMwAX*3%A$|#vCoqm5L6VKmevo`gc
zq($tCu+V~p7MWm-ET3H;K{V}=8<yX4)ehIp6DonK8#!Ma-Lrb@+h(v2|6-|W&A~ld
z&xc_amc2%b7lxMOqX>+AX{hzMSv0j}_THm)A_6T)RO<i2i0GP1zgdq<)%;a5E7|d*
z+LT7&3W2KgBVHOS8$1)MJ9DYDkW^Mo$K6`vqu~}>ka)4^g%L6?joz&x`$*KXS#!Ug
ztsUs95~#wnP7!j4>{g*`lQiEJ>h(b4=hO*C_xWD>*_Q0%WBcsZ-0PFHydDIq@Y>Lx
zdO?%SE;kB@bmc-Vyu%OC+6n8&9Tz8GBpT}7-n;T7^ZfM!q6`seK_a)`GvoA)6JpIP
zexhcS-DuvOoK3u&>{JL;o%r*G@%HFu(Z3*{-5m~>x$;6rF>a@@(1OH#$|o+ra#ftk
z#x*}W^16Ar*gx9+rgXQ%u~3E2Cbe+WcbSvJXa)Wwp~^Fegx7%Q#?$0C#gKgL<6!Iq
zb8^lEt*Xa!jw*cSX>Qb>;o3Q)ym;N(-@>T)&nx$h;>|XSy*UyMH9~H<Yq*vzth~tI
z#@|8<5)a?sH_{#4AUfyav%7YG9qk5vMHhFZtU{n_=EDcZwrPVzzYiRjl<b>FYt=76
z6dGO8LJJbBW<4+*)_Re;6#E#`X`ORK%0O{sS)f9o3L^vBJ)(0St#HQ5qUN=-O3Z-7
zm^BZLO83@^#Zl}d*|vPn1{7tq@`y4}g%JnM94Jx5nvtrV>%i1V%Xu@w&XW80dugPx
z5{#aQocf5~FO8{wuZ^RBgz5Qb@qN`eM*(Zk&NAltQIQr}koaYDf)Q|6(|_;9*SyaG
zYOm5%G~ahp2~@4m^4j=5SCn4XZm*696tI3fS;ma-5^13YiEN7#jAA7W-Ri+U+FZ$R
zjm%fkOy5)`P<7?^SH_wp_4RvWxE^yi6|k;{`<W>nkrt|U)lV=EO|GT;|M=2SiNO8Y
zEo0w!Q!I<H(1JvE8Ub%IYU{h(bE#fu&2CNHG}+A6S0zw&On+re3uvl0pk9L3D$bh2
z`Zf6kvqIYl3oS?tN||5;j;*K9vD+&Vp54lOZL)c)rb?jd*y@)?r;Y9Ociq`XmTC9Q
z(Q99tm%HlLH&tllaCWeMhWgqrvz{A!j&{`-7JO;Ez52p9H+YC%uox2sSL`y&md;>x
zJt-`-AaT6ZbECeihrYvZOAhqiW}frTYz02k6arNv3d9@BlaJDKz2pd>L)jvx-mZ+b
z`d}67?%6ow+O7%u*`e{qK8h@cl^Ulnq?l@PnkUBDDbae69g$UBzSrEhA)|Hpk<-HC
zuKMPgaiT+C{pdf5hU%kN+*I?#<a}1!mQD*TNHkCV%+N3O)0b1LO{-Jp+h(qN=w<aU
zBNPHvx6{WP9i5|ep9HQ)tr1hrQZ@5gJ=Zubv>@?2t!MdhWPd$CMoY6snLGLvvdZ=d
zRR~l~Nb$^Avi?_noQr+rxIDvLJ)?jXU!bam79`Tria^;W57N7y;d<N~QP|uxptO~D
zQ;0&K3ePk}8HcKxA=^q?-)s%B(1Juoie5{1h}MhQ(d$n{XhhWYAW)@V!J^}HSWBBv
zFu!{lZsGm<gnIq^i@(#mQm?PxyEPW4w)z#`X-;h$ZlMK<(-fB!JkUgcZpS4Zo~E?Y
zci(T$e;1|@s7gyQ-1ya9^*(kCckuf(R^7)t&F~Fj7Fv*4nCgX5V`EGGCyJbCor!j-
ztTS)v?ayeHK-G7h6OEoVe$w-N%}>;hJ87(WLwA|E%Y|8}`s+ZvG5mZR{j&DbP>E9;
z{x*kRjx)=?G%U0rk*s^XF*s!heW)EFFL`yxeAp(@-1)6apbDRVhhxCI$7X|BPtC+_
zYRiB`rPa@kgBiN&mnkBr5&fITruD~D^M(h3Dr_Yv%Q<ko^PfK|Su@5|v>MY$*lIRO
z_otC?w)r#?zBWwvj!ZPRJ0BWV+fLH!rs2E&*d1@}#_|B`OkhO|El8}UzBcj4VR{<7
zuPwgHsrf|*SS7>CD+H=^%Bt1)W}-gR&Z<>yJX0IKr;N4Yy1(U1tAB3`pcaR6eeEb`
zb*@*mUY>GR5qs|#m0$g;Kc2u5z_Vd7nqPQPYxZG33oS^@&w1BaTX~S4#m=f_YkxvJ
zzqqhfHMq1wplZmrTSlGPqx83p*vHajE^Sfrl2%;rk``K!2#&d9jQM+jUXOZg`W|P~
z2d#2-FKhLX(h7m9{Ir8hfj1-dev~z&7Ve?97W^^DYJR$$h39ARoBPIW-(mWT+=+&I
zt_n>bp*46`&gwqi-$Dx#<0v}YntYhPo1!zC>9pUe75@-m?X=1%1ge%K-ZT6kPtfBI
zaj6deGhCaIp{%uhQaKAPNYtlHYQn`K`guE(+T*vG+ShgbtnStP6#`XwWob>Pv?H}?
z4Juf-)A=da9Eq6`_l#%ZL-b}3`Rq2l5TmWxUDWCxq7taW>+f*<-pflA>YCDO+^e{C
zg0gkTR(94SC|manWdsk`>7;*48Np>g#2PgY57t-MxxSEcxkcMKZ_HNnidtwvVh63(
z^QK`RJ>5IbKrY^2SWGQ+)f}3sxP=xZTrXpd{DoTSv+XSBold1h-Smge-TuA`fvUHZ
zJ+Hf}s~%@(&!Y}k7M1>-Zgw|)toO~Y8UB@;>Q4?lGipD+VRV^WPY<HE3q`YEGa};}
z=!q7WYD0XeSh>Bm`AsQb3oS?_?{&jCP&`VHwBLU$++~PSZ9~kg>kBIcs;u!>jm_Rs
z`m=TH<8|F4Vt4#?GZp1`vFsb-VvT&eTI!1^Bdpe=Y=a^q+x_e2ncsXZv>-A4e5~=;
z$rieQ1HR_JZ7C(X3_ffwjwzxLsH&6tx-sQ?dwuvNE>-^zH1_DY-29<aQ41|dw9FD~
z3@=e%&!n@D7bh!=Q46P=?Kb%+1gh|?)1Ji*0z}KmRp!`y>h(Zk*Q*=G>W$y%U7YMA
zmrD~Xd$u!Qoi40gK~&+jp?ziE#AzK<=CW2lDrI5&kx04Fl`;MFY%3BBwJq^_OM4Fx
zF`o#uAQ3YBwvoC+A3eg()|Oi85DAU4Sh)_APzY2_za48#PoVE{igU{l82Ma_%ahki
z^{SYK79=7{-!}3N>#hGajcYzODyK-(G0`0ScL{|+6+US+5~ip2X_u5%Lwah_g2cy~
zw~P|cyXe>L?D?-ml%?nVdk+Ft`25p%kavVx)1>_-{s^`(Dyoqq&X|;As2;X3(ZD#E
zasa0$xW-qgVC}tES&5L5C_$OjEqjLQ{&ptyNCl@WU+Mts8|rWISg6t{zZ>_}MBQcQ
zcY7b7<eL7bg7vCkWeY7xtf5@*&ku&`V=325cgahqt5n4Rt5)|)3W2Kj;~yDe4JYZ*
zk=&m@TRhE`wSRzha8{6oss>FS8P&%Q(~I^_G*n_$2|wqC&4E^AvLFjBNK~cldA-fU
z^jdcIe9<=(oNLzvSwHj(PzY3E^g%hxttFi~3Rbe>W(O#72@<a;TfhA1FntYW>nTFs
zSkjrDh<FbIRT!gCZ%{11)#*r}_F+$?h1t3|8q2PwH{%y*EURYjE)r4UK%ka!Z={75
zBqFya7@~%ce$*aq_Xx~qEiM<Pt>3H?s9I6rwbA8;xBe@w>Fsdz&7R*1IvS{jpN_Q9
zg2a`W1X|6?N6$w209v2=oR9Tv_dMs!hAM%oZ<@X~PW1NEQ_o=^&+Zns`WNrvJpXHy
zg%%_*|3EAD7Aj)>6dw}0fOeij0#)Uj$u*^eZ6EJ0`&d)WZmxIxA}zEaff);08Sj-4
zKi2MG#*{B)VK4J@>l;Sj84>zW{{%zrapDd|2%l<~UH5wWSZG1wQoS2Soic{Lo#r{v
z%G`0f=-a-Exp=oqplaeTSB)|8;d+|2+<zpbqd61KORgrZidbkt;z5xcMvCE;^)2>%
zhMFIvg!ANR*WDt86#`X%)9NrMJ6F*C?fDFeZL5h@_piB97cFR^1&N9IZWu<gO8V1c
zT#srwBgNUDYC3<vQ$!(9rOuhy(=tl@HmYD~)L|bBEl3oj6=)vjEw2aJ^<bjRgf9tH
z;d~9+m1O%Mi)P9?LPj5P{gmaDoxj?r=LzHABiGl^`S))F=?k|!<@JrF`0OHq7Egj{
zNsNsjXgyv%&-wfP!!9P=79<vioie6uZKg+s^IXnRM4VbP&$+;ZK$W@Xf=#@onUvI@
zuj^~|%Ggc&<H0@`T99~l;gr!%@1bw6$vzGck&%d*9t5ghMO?Ir<r@2#)2Nf>^K_4v
zD*X-@T98<C^t93A{t!K(A^Vs~MCiW|sG3pbl1;Su&c1gmG`7a<P9=(t{mX?GBrbcO
zHOBNEt1s%nJ{%PrTYZQq?m?hx`l!n`(f=3rQGJ791%?$DE%wfKp#_ObG3SiI-c$5e
z1K39$BK(PH<w2loTXFhkl!*LG*~g@A#jGdG!$h)j!(C`WV)VQVM#XtE^_BMSz=MeR
zK*Za!DuJpa8L!(!z-9LFDo-lw&!{Hi)Y|$kv><VD*Ck`vjX(8!_Kwi+iI`2qc@F|r
zr~PAX;+O0kEuDC|+x&i5XK`zPJ{MY$*plU{(Q?at{fA?Gu8tDXjEGnd0#$7W+_H)B
z_1H(%Yh6q&uAhj_WbQx<60-(fH^yaNr1yEuJ_-||6LH3aKvlxSJ2r7^3j64Gd#>wk
z&|tAO`r~%AAW`;RtPy@`kzP9^&+_h<MC|q;P!-tWzD-;`$3A{76lle#3=-jwCc4ZT
zN9~=aH>Hqm3AZ2ImJHc)+Wvdk@~1?MBjQ;Sffj6uu#KTRasCn757QB?Zy)sOdjtL|
z7QbY~??+VvEuO^ZFDHK;f5e$(Wb4g?$p?O4iQjYLSCq77&EO->@cuJ{RuX|0B=|_5
zzhpf)(yoVNng@X@EUn${@;42RkE4#*yG}0`k97B5*!-K%0`8IhB{6b+x-SSk3;&yN
ze}C-$Vnlw6TxH8(yHr{J(UnqRNz}cttNC{q{dV2h)~3=rvrHMeul6Y;op>?!oWb>2
zkhP>}{ipo<>V$H1^x2z#7FO~@RVs{aWugU%_Om2CAZvLdiskrO9Qb&!O10?D3V|xz
z>zmg5ARqPSrwQ51K45=vBsLwBKI*5gO+I?)14W-dqPNXnlv5#4rPjQ1<H4e0stZ*z
zr<|hf0**x8v(m?qDc_Ngf=NV{%qoE@KGW`d!Qr^rteIFRCT|-&&0%#Jan^p;y80i{
z>Um35v%4t;o^^VUv!aXG{&rZE)RCrgJ&;&kQqrqirK3_!Pa;A+2vp&<p_V#-gjhGo
z-1_?0qSl%1XYBIU**-yAIOweX+wZ_Z4NFVy)zYS7`^2@uFMmm))B}lS!zKN?<`LRw
zwBC}YVh0gt2dV_Buucxg;}s=Dfjhr%U((Z1N`)o)Zmlfs3~e0wnDsJT9Ncm}c-gk1
z7Fv+Vv+j(2*2|<}!nve`m@wvM@VdT~Lxy9aYTx<O_F0In9706$x2eUSKabviaYSPa
zEl9jwFA47g<%n3jt*EHjW?YrY^cDauNDSU6+ueD${fQ{^Cbjtf%J?d2M>SRmRE3;7
zWtVEog0s}({xr=YGIn{e?OL;D7Fv)f@f*jC>GVnIHWP90>^^N;^vNpz1v@JQs)kRO
zJ|;ciM#Qp{lE_l1vxOEUR=G~vrOKa05HT}oowo8xmY7cd-7T~rF|pN2S*j&zh*<h#
z4{d9(BV^;jehPuA1}&wJ@AqdVVsvLoj3NRpNcjAA!Y<X?nY5^bWBJ?4+VNsVW5%ER
z#X<`b&-0(KOSN<6=&H1*UhM_Wpu1in*DDNG2vq$-1V87o<?a%3|Bmjgb=oVW+Lpl<
zT9Ekg!*Sb(+y%Tty#-Vo`aYF>Ab~3W%|0YS-K@og{BIRlR#C5iCrKs$9!Om>>ue&L
zf6-0^HX$u4!L*xjL=#1=io+3E?2xgbb8_SF{CmXf&GL7~`=><qz9;OzAD`3P)_o@8
z$L_T)H(t*Y7yj61|Bia_$Cm^hUHZUdA#ruVew!Y%Zh`diiP+j-dha=<n|Pg6l8q%h
zijH07-z!~js}j*@snJ}jQlD!f@JL)={!f+)El4=3OL~rfQ`Lt92~_3tlf=DLjXa2#
zu{-S=mfhf|$Go-d-__2S&^xqWZ~v}(>?>Us$z3WuCw-?MuvJe>t^9wUT_jd@IcU>C
z**ANX3a<yM@LsS><vv%@Si`y*WNrKR`}Y5Nc9H0D@3>v6PJh((C>5SvRCO{X@pxDr
zm59c(i)Xal^<B1)J5lB3*>%^$F}9<;9(+cNHj^s8``mQr<6o&h9B4tJRGZzl55Du2
zbEOcd^7?6yP4IK05YhLK$t#uotdCwTmHf?jNf{cS^RxNsF8Ndsv>=hbki28~ep7rn
zkU-TbANdS^ajv4#awms;&a?Ne`2Q>w5;P~#uE!q%0so^^sB)k6FKez^J|8##BY8cz
zglf%^K-GWVCDHSZ!*+Qu9ZIho&t#i8Ja_j0XU&l))=Sd!E_!>E3a<yM@Lo{sf$c}$
zin1-?I|l2g5@<o<$~e=m-<PFA0##OKN$^=veRR6%vX8Ya<t>r6hE#F?;XcwAPgFEM
z&tjT<wnv55{(rV5NN~@|&&L-&l$IJ**z&3MKnoK8Sq}#isKWkH^??>7zGxYu-Ms<!
z$TJGcyOPf|`c{3Q1qq+Vk}mNv-lO$F0#$g2sy@(yL|j|xW0PNU{l5uR;ghBkc*nIg
z<vqsFqx-!5@0J0H9KTEY%TnR7Q04ynm-iJ~khrl#`uO7PD!l=!@VQZIj!)6{%kqih
z=nQ?U1X_@&KSj0@Uq%2(pbGm(dc&JC$fAEq_si#Ka`vnd#<zoWeTqdtN0$FaaLkE>
z`?rim-_Mk}@J!jyJGXYZU~Ib^sux*X$l%|cv*zFJ+n=`o{w0AHPl9Pl<VX`}y`p+d
zZ1J13mYriyr!PzGWBYLXqa30gx36e4M5lc-h~TW+93s$yB}CtncuvH64+2$}Qy(?X
zmrtKms?#e2#p?Ni!h85o=M>|dF?C0ro`d3DjDzsmq^|+#tCz<61I5U_m0cJWBY{~8
znkREEP&_&uD6X6cccBFd^iAK&{1_;nmktt>+SE}9RH@mIxI=;BH2vGXTO}~Vf~9ph
zvRy7O?raYf*7iasT9CjT5bf!mL_F{yP=zA^x*kN_CLaxnKo#alRN_g!lHwK-mv@dd
z(SihKTj*QMZ%T^GMD(^)0#(Y$!tsWD+#q5z`9KxsNK~TN#C+l!5pP6{i54U<+d}(0
z6LFmghprNeN*UwSn3PYPAfk;k#zYn7eQ>-(a|iFF7qLX-$o9}g3lf-fqIapc(~G-A
zO!gp9g`*7mLV8e~mSsnvD4#5yg%%_*yF=>~{T!#olaKx>R035v7NJ~U-#CryF(hR=
zB~yesAeG2n-qQHqE#*aPzQRZd3Csu4N>gPl?KBa8W>yJQ;dsa4_@%7$v4VV{3Ufdz
zu{Pg0?HTzfTBU@A79=pcL%W&h9j84aVyp*&DvZ=<g}*%Gw0lGxCjwQN15$~yZ%S)?
zC(f@>-a-o!nBAe3@!plzZW7VmgFqEVfb@0E!*<T|L_FUfXkjJ=V>ryb(2mfl+B^A)
zIzR+kkWhVWyVK5jg$TO06arP4bE1~|pVAsX=R>F-Xh8z&<Zw(WL@hP-9|h<=4rlv0
zBjkR&;LbE-8|-k5CxYMOXhdK?fzg>t(3>B@eN+SyXhEWB{fm%6+DpV%B1U@<sKV09
zxa2Mo$x;Pb?raoiwlLzr>!cEB@g$T;KRU_Br>IEAgP*fsSSQ7YP%WQ{T`@8bCu0U?
z+&+*%6`lpkw^Ovl*F$>yd|Y=uu!J(#_iqHAD<<5uj73jP4ix-vWz-~BV%$UfJs_92
zYNiMF?~?v!gjy;$v789BAfaACj`-YB9};eV`5X?z{ac=^fVYjTRo&Ck^>#!j#$B>Y
z!YVvh?!UXw?&mBgTl$@zsLSJirupyuZo73A%8l}&`S|vKXmKCcP45~uUBB??fX+gd
za9cbHejC2F^n!mO+!jxQ-`D<oJv<3kF+C{#@1F=R8UGh8*y67F=ASRywRP8neeiFo
zmH(H7+k!-~c316p^#7YcRrzt(?KkcU5zVDSOXSU1`<?m!zf?%9YjE3s8~(`$9iRVG
z>w&7bm+pSLd!%;l*DXax^QGp#<M>#3SN=DF79{YlRDB?UD!l%ZaNk=z!p^efxz1zq
z{r!*IzdJ2GDtJ`Pe^<tX_Wg?%B+}iG^wyY%NiB%m2NI~_aWwl-#<jK&v>*}sLi)(I
zErqVu0|`{|_?&(4$Xg}Qg2bWC(#Ll{XZs%nsyJW9K9t;&T@SP%(XEX1F?C&G4<AUN
ziZg8NL&<pAKG1?h`3A>qBI6r>4<AUNiZgfYgL86@r2k|Kgcc-%LXO(Rhqx;LgFqGM
zdf5kOhgBbFL1N)8c?BbbBmM`0D$WkG4<(0epDVN=(eyiccFT-QdYeH-lQl;IRh(O9
zA4=BQ_JI~8HZPH-s=MkNk9r`1D$YQ&4<#dP`#=j4{+A`Opi@H+A4sUGy|xb}vu*p}
zY&Lsm%fAsrS2vPAqTS~T3HNVSanAbR>!DhtKPJu;lf<WbeDZ+=syG+^@7Dt@NYre+
z(<VM$k54|3Ko!5OVIN=KS7<?E@lw+!KHXQJd?0};&XKc^FP{&zAkn;l%O*ZOAD?_6
zfhx|VvyU&IbF?6FWZ!n1`1G8A@__`ZIQPyzzHG11g2c%cF*fn3z53(>2~=^0m3@5K
z?xF>W$!E9O#HV)mlMf_N#d%ov@n!#k79=XykUl>3AD?_6fhx|!vX3wOL9`&TFQfGF
zsULLvh(-ccoVjHmpZaq*;Xn%#uL?^aU-akENT7-{!t8@%2?zi8$p>1H2pJ)LaKvE~
z3~}odjRdMVx6D5H4UIxL(1OH@O7gx6^;)MA(MX_*GtlgVbJnU4v>@SMUOpfFVt!MJ
zXe3a@IcxTzWVS8#h884dblhPROWF_d@PP!XI2X=7_+7DD540e0>8iYfBfB<JiD)EH
z#c!0^hcW}gt_NC>s53y;d~qk;!v_+m;&;&OLwQqe`#=j4DV(xY9cKG^_&@?x{057C
zDDSpyA81jCY?3%K&R#XzKEd+dMZ!x_$sVrPY<PdpKBC>dC0qWDs8hp7tp`DPEcu&N
z{D$sd>k+M5fQXa7zo>@;iFi=)448kt9?@t);=^tkEq!r497v#wXOXavFYha~AhCX!
zj4Z#nuN+9AiszcJk1wAOv>;K^SH_}WJRc4uP{p%T*vFU8Ia-kDIQ@uCeDRz+kU$mB
zdSM@5wpVCD;>-ydw|~)I*|VwK$3hjq$K}6&+3unRiH3*d_~VOq*MS78a4c#+PW))t
z&mdZm!0{*T4Y>9%SGiNcF|pYP6D99zjwUgB<-2lF`AlMAGmc(Iq!?n(xD*`om8-9X
zaWvmotO~tcU!iFo`i%Z&xhugTKh_&y;c=1ZcX6LhKhDQdc%>|oaC#7^QcKnD&S^9A
z+2ELOqkgn-1i^PAm+JA|uXQXfeQP;+h1u_Ta7fdZJ(PMN@!i4$Hl3p-k3as4Ko!=B
z<~ldYY;`{o98)}ReGA7<eD89p0vA`;v9$DVV&fZg#>wE2$pc#`^+2M_w})(cS|pFW
zhOd`Iia{!YDy$Rj$5Nz%b?i)Vj5r-^;i!@Cb}rSh+Cs<D()w4l$9lk#;E<C3)s%W5
zQRAwtQ;Rp@RH|R-+g&F1dl0C?IyoG1r)yh9&jrWKt&+#W@iIRjT&mf=fjX9!cGdOM
ztzs90L!SARQtE-koQjg3u$4#K|3#n*>*R3kp3&CIcp*5Z<dAzNW(xR;;!<t>xrC0T
zrLUddH@2SB6--+twNeixrhO&p<;OYCa5ss#5UdiY!aC8)EeCpAT`va5<c^zeVvdBL
zZ7x;Gzw+u>TG|0@OcyKUba2S(`=(M4B)p19y7N@du=tLZM8Z9lKo!=B-VeqNwEm{H
zq<GfkCT52?8^xvS@0&r#($e}qMt^Jknc$Gb?TwUrAn{<8r0e~_xuyRiP=$4(wI=rt
zw$4(^u=Rq!(=#u|rJ6bMwZPKSY;__|T?h^tec9iI7XIxfiaeCR=WgPx+Os5L?m3k}
z71qh&NKZBIN_TtP9gQ?>k@@_vkAJ+b2rMnV8Ktuuel9qqd6wiFT98P7PSQ0_a6YkQ
z645@ZN}vks^y!+%&^4$1wm$bod@pgSM$R#nj3>3!bSL(vR&-w6bfq3h<nJNrt><~f
z(lUvd@K_~Kg>`Z`&eQXefm+e0!KnrImi*jtsitOLB(Svfg)}|2UUaUS4Y{Y(1Btpj
zC7rPmk8w^W5%JL~fhw$%Y)ig78XQBdkH9#A+bAxTRcxG6T55Nxh3j=WIOIl^Jc<R0
z^#>%q+<PXK>c0q7VVxX~tJLn&6BX0fznZ`ZiQ987Rd|tZN@?j$HT4DtwG3aM4puBk
zbe<r4h99o*II5|yB$l622~=U7=!=mJv`PrISBD3-5EvVB-^Zm|b-K1v+D|=a2=$zb
z1&P50WS#o;Z%(C3>TACsP=$5+)St&t1RyXf<~V^%mHQi-*`q|r&F`Kz3tS5h$rtsb
zVnJf`U>R}roMKR^y4;q;I1d6<SSN?W&&%IzeVQVfdIJQG2RL%#Qk|?{Tq&)?F(x^!
zlS(~K7gt}!f<(`qGCFH}#-B<xB&8(Eco3+<IyoF+UjAA#D%CesDjd;qcF<iabre=~
z?O)Cor-DN$vQ)-rNc>GBJ*G3C@TF2+y5jHLyd*e;+FylGRi8&;4#%4{f7xGJ+#w(C
z=#@uwo&@`l<H2-S{ap_Fk6LVnVA`$1vrfBhuKCOLfzB@1L$!P+awkQ|vL00Pe<e_b
z*T%jRHHt;;I}yj^oEPO%@tufg-M)evUvs{KXhCA4*k#l5n$ulk6MUB-fhxQ<_EW35
zpIXdDa3+;Y#ZN7kmcDSieOim6NI#nHcC;YTFWRzc`FxbQD~S>w1gfx3G%xRTVNsm!
z#NpJ!VIGEauUsl_;jpxJ%OEHUw_66ZATjioq(8MK|4N_=>qKjd_|aYvbOo<bZ-5yn
z&en3NxHrJk(mDXX6~uScM;)S86fH<h>#@V8WxGo)wM}qKjRdN&PIk{JF4DQ;o)dF#
zoZsbAanFgRwR;?K^}Ot((1JvrU|FY6ebm1asKPqgQHG#c)Q&PR>&O{lE)_=^SX#Sx
z7Tlk6?~E2C)(KgsPyPA75~#vD*%6s=M`W09<s34XiX$>CtsTh-j(s?iK?@RhCP-Sw
zJ`^q41V>9qpbG0`N3X&iy<(=Be{-ogdd1S(QJ>&Ak)uAeAn~EJq-C5)k)=&=WQhc-
zuugWQFWiwn=Gd9$QgNh@rKQmwwYN<v(m!>{--Q+=uIG}pjH#a{5e?6)1gfx3_NYj>
zM@9H{fzLFTibq9QT6;7h+~W_lAd&Z5Nq-uD{40Sftkb7^H-_$A6W^=weaxle5hRxO
z)AJF+BQLZd5r0jVN{-cNbjMGWJ-R~zRahr`v@OQdSdB;9_(qAJc`g-?wz0JKC{>te
zgF|?fiWVd~Z;*A8<60UC+XRn<kw6vJ$&N+2g^QsU&cb(T+}d%eI5UBzrQJ5E-5o?d
z&SA;{paqH6$7G#8<p6Agvj#|@3hVT#|FE+--0E{qkKaymU&5v0EDn~|&VC4Y_5&?Q
zZ1I(}%$F26Q`jcLC|`mEs<2KD2W7l8cgBl*NG=t>m*sw!OT`&4EUld>(m1!onIg0x
zF?E&f+huNvvQaj{*(fAXg>|yCgPJ=#h;NQL;^0zob`VSZDfY4RaA-kd+4nLI`jm&`
zXz2?ARahs71EM}l%^S)XPQI7_oc*NzSSS`viW4n&Wa(CMJ@_}ryZl?`MJbc&ob)f5
zR8-*^p_QPs_-mXOtx8!=v>-9M#BO;t?Yt;uQf-1WsYsv-&l|1sPdhtSSr=%H8dOen
zskPrYxW1isee6=L%iM#;slGz%yevk;sNdn(xxbQGi-=!|Knq5!cqH02G<zRcO(KHU
z1u8y}z}T1KcG|;T5E0=)sH(lj9~FCQDQnHA@95uW>*ER}f=VVlReTL(bnihp-2`93
z&&T>4x2xj>DwWe+DkM-fb>ps2=g_XX(_M2^@wMSn@mNhI=<I6lvx^oaFe10Fpys}U
zNT6zJOY76sr19XPN?L6?S54^(q6G;xrat@67;VkHK<n`@B@_Zx*PpwL7A5m(J|~aT
z^|)zF(@JKoWYvD}E6{=j#_+Uu!taZ;VqaCVHXSIW5U47gNBU@T`2qR3-DbMRSMXO+
zOrVNeB0jr3{!oc3d5_rV%2(u4EJ$DsPisIBp^=Yr9t5glytmsmAKHg@$94D<LHDiY
zO$4gA)#g(1_(LTI)9&?AL`;92T(Ka5F+7bqi3ld5s|SIqi_N#$rK-NDK9wr!<y$S1
zh)P7DihDRN6^}nuq7?03uM?4X<pm8bNMH<4HBTb4c@U`5o^P>B)vEFsDpeUG_=(C#
z1gbb1;8OAULnT(y?)6Muuf9-23lbQ^I~>!9;F{;Hp%SR-adop@s+Obpt^OP$z9Ql@
z`9Kv%PFyM;f2c&acK$Z8;K%wJT9CjPp4Rsvg6pyP2bDlohmx{XlOs=3siqOZ^(a9E
zsxb0ai2<~GeK-->BDXrxf&|9!w0<HH>|?A4fvT@BZ?ex-Seutrs-KDAdW?(O>O>Vr
z-YT(%cCU95@pX-tJJ5mz#_$dY6QM-JdJw4UkRVI-pp6&h+m{j%Mnt7LFL$5{BX5-$
zPP^AL@$>0CCR&id7@ndfA`Bw_@E}n2^e1@*EBNv3&rwA1xf(zOsxb0aiA}V7J=gqn
z)lnu|kiZz8b{`^w+menR1ggq5mCs;#2Y-2ghzPEEO(IZ*k+(`5q}}WJF6my%G|_?t
z#_%-8A)*Em)jbGQ{rcxt`@Z`9dwxH7Ey+h2B2a~qw@OT--Rs%My*W=!v><^oJneQv
zM0Fzm_8?HTGa$w;RouaPR4Uq6*1qO3M4$>IZ<W|e``vSIa5;A-3oS@s4DWC>A)+!7
zS@Wm_stRP=VVCOh<z`f>6BlpGww(x6VdSk6D{1$7E>*gE1ue87fiXON)kp-Fs*(qR
zs@T$|U8>zxI#8*G-CV2j^=L>0sxb0aiA_s;Xw`_A@UFCl79=o+rwk+!eDD6@L7?il
zt~>2gHJ{goO0|awZhdAFfhvrORpL_VL}v&QXLeMy(1HZU*VML`O?1{HVyOp#s_92}
z+of7~qdS%AO!-77Uyo%(pb8^>m3aD3VrZUcfmTZThZZE<IcqsCanOH7CI(ms`qIwn
ziuccBoK6Azpj74FCGK$hz+>SENhPL~Pjqq1!1X{25;#Z0K36XHxk3U}KTbXXSCFoU
z%Y8jig)=Kug08vgzUF8_0_SMh_m%0suaH1h;d6)VQpvlW?p@P;@1hE4R;UC$AEx{H
zKnoH$N5g&wP4_d11gdVw9kEL#TLya0P4{z-Dx6uN64aKMd<82}TY?rOaE=D84@bLN
z)5y-s;6b2DKYGkAm25@t62U(9Q=5n?oLQj~vwYH89LYSPb{8#3;2aHF&yoo42b0fL
z2~_>m`h;C7+2c_EVY&McRN>4Dm7qS#;(Bl&g%%`mj)vV2+CI1+L;_W(7oD_AC3|P;
zYi%Fg*P;q%R;UE^=a#!aM+*`-N5hU8>~qC20}`mpI`))ZDjCU8Tw=N75>(;L3YDPP
z$8yI$Xh8z!XxQ<U<&LkAK-KIFr|nY7sE;BtyXG9jp$cbKsKm;$K^Bj3s#Slv11(74
z91U7gjtIUJ&r>Xl1gh2-lckaoGDWXeRU*Q_ez^lxII}_}D5kd0701+QK?3J!&<e3c
z@HH>!L7-|Dt+~wOb2*wAMg(8MycFr93TIZR#O!wdmOT=t@dsLvz&RSUMk5hi^Y$JD
zswVl$Qpu4QjiW3cdGR<3RXDRkC1|W>6FgQ!3lca-gL)hy_*_+?@gNeY+U+HuK{-mD
zK?L6=rHDWk&a6-g8rRxakjJ%XK?3J!I2-{)aH(FcPzh9(oPXTDf^tM(j0kSwc(jcw
zoLQj~U0%MmGk5tY2Y?nNaE^wZXE5D)1|(1wb@!-UDw+MDT!!h+WuOXYR;UE!OYA<1
z^Cf6O0_SMhIT_QPlR*MivG)(#rIMK<%KO+^PR{$F1qpSQ#hi1C&2_YwaJScm6#`Yh
zUebrmc&*T<nZ+pM^&4fp(1HZc>Y#7+6ULZVjs;n*h89-{RAC;L)<|hL-R?O9DdU9}
zB-D8sl<PCyxjrONg;`vV66w0r*WSD)z=vLP_1`Y-3(`8&f7ol`@b6`T=Z(s{pNrwW
z3en&9rWw8AKB+&_Kh^S?VEST(Sdqq2m<ayw2&wa>`jT*~em`&?h?qTT#5*F&_kF63
z7#?qzB>heAut&6WJrl2<<_k-cmG+jURZpD`Z}PE<2wHDI2qMseMC`j)Hr>1;6LrO5
z?af+R>t%E<(R0!h+mdxq!LZK1%ipc~7Yw`C;;HfA>v-|w*aAc(I1g*BDdT*a2(%#K
zdiLBt(*CAQBofh<h!Y+Jss=QBX6y_}sZVa1p9sC*Tg_M#C?d<G5NJWd>#g+hZ6o#(
z9{9Ir+@#&JtE5*5RDHkenSHJf?8!$&;JbI))-x4FcyvmE79{Yz(f(>Z93uCXKyi1<
zM-2&7;dOF2;?o6)EKdSOjn0={dp~3dd;3?cc#~|T@m>0iVSEL9w;yRdNiBabtuoS}
zHD%KVh(S*S#jp;SU1*t?T&l_wjYpytVs8YBJLIFomTZa-Bpi+;AGBT-?NWI^P>iD$
zl)hS_5~#ZVG(%XPO1H#Po8Y^g?{>O{qdT-uAI5iFkmDJx$sm8<={$svD}C_a=`JBP
zuboip#F!0eL1N{S^kJc^Q|YUZF&#wr?Rp|ctQ;7KmU=}qgsocoj~KdZsE3b@qz)h|
za(}js=mUuxO)`YNI+q~k*BnMPKO4N3#kt`r0+2vevtKiW1@3<$rd?%XArTQogq}FE
zSv@D8&*+hh8Nzzxxhv-8;<H<uh*?C~&%0vzOrURvqZ|=ih^QVJy<R=m=QG-4Q-(0t
zu!o{XpW)=A1*u07RkKd}jjH7{q1L1ALAu`bZ_SVOT<&WiuheIv#<>jkUFkpR8ePE#
zq;5+8?srrPR3!>|{r!KqK}6aV6+~kquD{M_q6LXG4W*A6Lyr)Viiq!tc<e!-s>`u-
z_Wic2<Ow3CjVooB>Q?D!6D>&G8lK*+$HmGqL~J4=f_!ZBAW&5?tMsvErbWc-aRo(n
zB2KPaW1<C#%I(wHKB6+NAmTU?t%-Q+L7=Ka=CpP_vSwIEL~kvNXhlT15m!vKAVFu;
z_ED+f??j9yg0D#t4+2%kj;6MK%sIA@h%M9`aF15M?^Dy^cxSiBrS)WFd1tqS)e`vI
zdGw(YX!%U2J{<HPuPDdsy`(FYHjH;#@N(=l_&2XRclqcJBOoBzr@yoQGl3RQ!c99I
z?KAdsKBV5@7X3pN`s;U0`Yv?KqUWPVhJMa_q`vP#plbanS;D(9JBXMc9IV|X_3;kn
z1X_?d)+e1^kAN}kqdyUMh&b&*pz5nQ>0|5&_VIqi4DB`%1wR%QXh9-(uJpE#Tdzza
zQjDBo`^fJ>pz8WpeDBuKo0MfAHO3sZi7k6_3bY`>tt(%rE*06wC?XzFsb+Z)sQPoE
z^bxydI}vrKywmv1b}f-ypaltTgW1O{%|%37BCZiJ*MmS+vZvC=v|{Wd{EuwnDiQU6
zIj5lo32x!o$0%Q}c~2sq5HX{_N}%eTAGcREbk{F2M08qGM8pwc{y0xV3liKOvyTA}
znfR878$>kks1m5E*;M+dYi%Q9@>74o_f><hYinphf};WUv2+#_zZ3C-h_rQ70#&Jg
zmOf4<ZYAP85g&;7wq|V&ReyQQ<G!JpZ7MOBh|5IyQ>oB`#GJ*_$D{*W$VUhf&x!cz
z+u9nc3i(POuIF0~l{iS}itnr1Kg`q6f<(_Mk}mff*JBb9T&n(bJ&-_Eoky}%ajP~H
zadvSL@s^1Do#tt%I$uK`cT4@PhDr>fyW}Ymo#-w>3ld+ok@Q|KE>&Y99uV=ugFsb=
z>KW|&s?_RDM8y4`O}rxFF5SDR`hK81Zdp2`DzS~84<?G0NG{NVM96QF{%0CrkB^hz
zX@3(j*@Hlp&o)`AEvGjUk(GRKD>{}4RF&Hyj~h{Yi=h&wMjzF<&CS0zr$7r5@6Skj
zmmilZKeZ+N3~r~k1PN5>RWsV>Dwz+LYD-dkHH8RN{hTtB{Y;Ggd$XYu;na$9scKT2
zh!!M#^GJHuMZQb66T$6ODGvfwe;k&jsxoH-5rW!Xe$I0cfvSS_<#BJ$-)yMFq@ZB!
zA`zK?C@0W@M8?*Vo;;gN^?~{i?xPM+|A7RmQnblrpQ{SA1s3%<)DLpa`6@abUiSIv
z-JXx-Wvh&U4MxHm>7#sa{=1c4_Je%?s+P}$>SJG;eopSy_$nfSszb}9k52Tam(Eoc
z*$?icdY}aftP{=Ba|K#;U4df%tTr^CEK5>7VvO0dvfB0N-9E-x|0c8j_lW)6CN?Fa
zJrU<8wsE2b31fn!3q&!Ixn_B*D-ru@l+utu)$@DOM=EL`DHbK7B@s1imD13H#Nf`-
z#|=Mj8R`u#VNuCM$30^e0#y|cN*|M_Gx2Q_(TWJPAW<Sn`dH?}PgJ()-d02Mk?ALw
zLZGVh9O+|XM)pyVh$cjw?d{Ugg2ZnRv)E@kV;R1Jy|1RTniDZ%z$1k~Rr-$7N6RT(
zs#ZiaCc+{DEl8~VRr)CKHMfby20k*sC!*rjbOH%f#rwIh2m8oL1lOY~5okeTV*%+S
zYAUxS*?)4`KGIG1RtQw}d?25jEa$oAGkd$tdgLRN2(%#4enDpYTor%E&tUZKvF0~K
zj2m1+Ay5@ONBWpDlYP7;g71<ah(HSxNAgP_eaG8AYL>F=k*j8Tg+NuFy3$AHUhHE9
z5zWX)HX_i1gx@6j%*WSYAMIwhaq%_hdkYCwg>B55-`cpoBXtY<hpmq%!SNNhMAX93
zI*<=(Tp(k9`J88R?D+JY^KX3q|DE90!2O&f&3{+h5>&a5%S4^j(ziB`{bB2a1gfsi
zmd{}B!c3H;mVvMNM`}yZf<)%L(#L>Mj(3OFC~x&5V){2KfvP{}NFR*^`)HWdGSs7%
z0WC-zuPl8$JIOx2CxV}kDjo!?_AHV<(l%os*p{FLi9@ZVkNCzsHt03Y+v-3*&h>F=
zNT90ZU(!d{e(VF=60{)ka=P^4bC!Knzn0GWihLaD|42guRWr9pAJ-?bkM{!}*-um?
zwG3!M!t0Ftdhl57zX(*F+#`Ls7PF5?YD@TudNa*ipaqEuxwG1RRL@E5<1)1+t%%4;
zZ3z;n8g@$h7`>T&^r4o4pQgdoGN1*CgRP{Gr^nbw%003zY41Uxs%fnBadtQRh=#TV
zEl50AlT?ov>?4t0)V8Kl(OoZ)K-E7_rH=-O*$1{IXhDMRKKop8Zh*d(`Lm6SdxHk_
z4+&M3&2D!&gFrQ>Sb^KCM)Z$WpR)s>kDI5i{N2;8N92q)PWHi95eZbK$|8>>>oK@y
zDUE&PpqirviQqZXhrAvitC!NaO|0NSplWd;=|f(RzPrcTKBDOgq6LYb50dI(-&Y@r
z;Oo)CgFw~5veJjVufi!-;Cj5KdlxN8#QSBpug8E;zUDV6R^UF$o9<mCP*ovR`jF2D
zJyABn&mdZmNZ(QVkk9#l5vcm1y7VER^PlP1e0Il^FSH<0d5-iU+pCJ#(us~lETXmq
z2~=JDM*5KLRVJ!2-z912oS_AYiU*|++3t>|vs#OY=hP-5fhuQH=|i@=)V2#gyWF;;
z1&QbP+}DHK_NGK|se(NSRJCm-eaQZ!0NsInrzcV$g%%{%zmYy<Ke)9<c~O;!!_-G1
zfvTeIqz~B-QqL*eaXVU&a5!?<_m%A1|BFCXhxXEkBq(MONijq8XVq}yvx@WI=mQ7}
zG(KC9`25>$uRhm<a^Y_8c--MM{*dSDS_^&)0QFD^RJqSc%2+12^-PKxOtc{3zBY6B
z@S6>a8AMXdpb)5XU#Go0*$3QLCR&hi-(zLUu@8zFL{iM45U6tBq1hL*4~iM=7?H*w
zCR&hiKP#n{@OvDJ8AMXdpb)5XKR17kVjmPU2yU-v{9&R63HLMqwha5Am_a1P3<`lN
z_w(=U#y+6+vCx8qyX~60C;ER7sB*V_&6}_fiW#(|n888|67Dv5c{lb!F@u&AGbjYA
z-0kty8tj8&1}!OOu+V~pyD#yp$UZ1$uv==1859Cl?w+WclYLOkpmFO%;|~ihNVxmN
z<r&!r#SC^I#gQ@+sB-tH`-9j=D(cVqTv7XOp#=$dG?2-`K6L8Od3;XePK8ia@@X~#
z*hhOB<FF4J<5=zpKw4z~%ExubD6$^KC@x_i)XFIYs@(C4tOvymW>U;xp#=$dtR=4p
z#SCUr%%Bjca>rfrdQi+@`=FS?LJJb^m{HzW6f@W{9K{R@fhu>zDeo(a8EhXEGgxRr
z!X5j{=YwJfI|`?mK_O7(j)Ud%0a3Vx79`v;ynN38i$Ilo1R$StiW#h=n88E~67I2x
zY_BM0u##d1g+P^iTq4^miW#h=n88E~67DgTY<DSUu##d1g+P^id?njm7!R6gLBc&Y
zl>G<A40fp~W>5%Jxkr|=|Dc$`N{Sgwv>@Rg<H~-JVg@TIW>5%Jxkt#dAB54i3oS@|
z9;<U7{9gpBK9Ad(__sU*&s%V-<QxV$9?azUFXI2|IumFq$}5jQmbkElD1sXrF)Bd;
z4G@Elbiaq9BH^hcM@J@ZaYaFA#JDhuB%-ot3>p}57`J$g3nnVUQSntpal>UCF<=G}
zjUl2KWN{;kI(MmC{i`a&Ih<4H-TUiXUETFn)&2heuQfs<ww*X%#uDw7$nlbq!TTb=
zoik0Udsk(}OV_nTAEnFn`uBUKU!va<x${elkp>aHlfDbD6M|z231&qHY1-LZ<NoaF
zuDg7ajF5;P&|Md54UQ!wm=&F{&iiT&9ZN>b`#4{|UyP85Ue+fav_@|kOIn4HC*cCY
ztmx?VTs~EZU&&aa{lp&%!3c@y$t@c<Lx?_EcW|(r?<ANNea1!OwMKU#^e+5hAs8VM
zy~VE{oGt{%5)#ac4(p7Mt`*`Gd2Rj7AD25BMo2`DwA(U0x*SVLFe^I6)6dl!z2z9`
zQ}F9@%orgNz1|6{^qr$mT_Bhh9q*pYRfQCN>YvJ3!U&1zSs(J6?$sXISh8$H-vYs`
z=)=EmN~bL{mgu<KGO};N2#M&ufAyH|)d)G0#tHG8Ij6UgC}#P2?&th@Lg-n$_J-5j
zV*Jnui8#-lz#L2AJde4M4`%46);NO;b1X)9XX3hiCPs;v3t9V+o*$TFN%^`ld-CA)
zGJ!dkl&?i1=2)hmse6dor2@gMn00#RG~FxAV5Q888LWd(o|eyfIe}TSl&?i1X3u`!
zNB0UdaRq`|F{ii7TY8>jwl8H?%=XRfF)g1TbOJMqDPN03%ruU9P0tU^S{4Xq#cbvo
z{dKP}Gnz6hW=3CscxpbE>I7zAQ@$37n3dh*Jl!kI@D>PW#a!{GV|Bd3EON@Mm_=SU
zWNJR|>;z`26TTLSn87|_qn_uO4KEPPih1<`$LVK|8TW))G2?#5{nzGm^iE(_KjCYU
zh}r%R&e6Ssa-cvkD-;FO<tP+16G><$RE-&Gh>@MHZ3&&jp38Lffo39Mgha6hG!q4a
zS)qnF`P=$FpqWS*A;I?~>K)N#Y>>Iy5l4?oxF>v1p*3-R;yfX2R=>4KFe{WQFE;Bt
z|C#7Alz49J?Fl0!LNnv4$-{)uy=pzTNH8lDHz!X~)#MOSS*V_2_<t-*7$FhbA6J52
zEriavKRB^SFe{Wp*R0UHzJC=3gwE<;)Te#Q2#L@zxhD0~Ol2{<L@+B9PzN8WH4YU$
zgU-*-U)&>QghXhu4%$Y088d~@qkBh*U{)x(o_tlGYgI?4bM&GkOBo>%nzHvU)@Ntc
zk*V@*w-UjuP^8VAs5S1))NQYvy?@FGiO|Mv*-dL)n&}z-w?r^2lywIV*BWC*&!D;t
z(MP3>kO+;R_W%wPU7vnS<h>LKW`#n~pY(O^G1Diep*Gal(rurqyvnqSs=x9YB>1{z
zB4}BYL-f>BL{B{+*?wqfgnf3>wY9n(YV5UNsn%evXto!NW_!h1MS@wO^4`-3=)#9G
zLL&6y7nx=P+VcXzEFC3OhwjQVsEP-NLV4?^_QOJ9ymZ>47Cj$T9qpPsRe0-vIcB*o
z{6{w>(ydjM*0#+`>o;Fj-mW$bCHXHq4jjk`3D#~Xu(d`+^oV}bk=A;0r!UIrKgwQR
zb?KIYL1=`8j$NwRc3mG7*ad=FJPHLR`FtLeP?BG^Ks(KTbbYU&Rxcb~5;_v8*4<T;
zP{il@c6}{o@fbEWU6E;o54rk{TIh7gT+>;OiEDX}nAK%iD2%U8I?3NBWjf^UC4yO@
zPriTEwnDrkT4z-*KRWOCHAYB;QhNKxwh>~D5QhuV^MNA4tk79+?xMuKqS+oU#KwIm
z*BBuYitj}?Y$e2PLa37bHzk5up%?#T7bUh5?YZjPS8m?5#t4Z}u5Z)YQHapDuP+hI
z3f=oQ-IX{&UVn`IzisTXLm44a{Fa1HfAhITf?36L1)6PHAINpuOD6Y_>aO_i{I?y4
z6~7CQHgw^oZ%KpTH^xS|G#laC_GsU(Ih-Nwq%G^?$JH%c&-=Qr+v-rU5iZR}xB|hf
z=esvGha<+EFKIYm7$GryPp{!#85!ZyaMzGv)+djAWqYOfcIKN%!#5H8t}ciT_jGIy
zcf|omZQb1Pf5_;T|ML6Ib9QdlQBB=0v8{CLtRBq`AB&7|sd{B(gnO6~60B__T&f-u
zz4AmvpGLpwNV{i4Mz}N^;T{e`BP2#nXy2?OoZt1y2$zP(gaosA6l{b`!z;sMvfV#-
zY7R#YU#Y1{Mz}QmIE;|^@bRwA4L6UBaA|mcNHB}Xu&L?C(qYj~(MIX8^yzVueI84u
z-`d>mi=*tD*mlLN=HaUku<iR6-__h8)|Uuo)ovMXuk`4Mc|v?wIxJd4J1mTl=&)v2
ztFhuQ3xwE12%YU)Um}>*x^SS?xP1O1Atp&T?KmM8Nq3DA62H8*i`6*c!sms!ObDI%
znO!27b<W#+S&emPy(C0e>B;Ea#D~%)WQ4@ZeL7f;eLsIgh@FMdd9{<ICqsf+i!bP9
zHJ<+bO(C?yGD?W6q}#~|34XFoP3H)qv&i)l!7QFDa`!4t7WJ1%M*7M7YpnY02Yy|D
zf8{FM_ZK&vTIYA6NH9Wz-<YPRw%Mn*>0asH{q&UW%pap3SKZc8O@EDew>P)7?UkqR
zD7w|VqzfhQzJ64RVAgqWcCuIcaL}7FHvd?Ts&>4-kj@t)B=(=)-fG-%T2CQ52%(>O
zXZc)6Fl*wJj#gvI7hA~)a;AJcbO!4e@@-*+#H7BT*>M{^{<peULTHa{W{F_do`2tB
zNBvJ94Uiho$hTZ)k@u2sJtHK>9J|(Pocp`&g?LH`ot4?AL@?`|*Ed>?QP-R)L`Uh?
z>N$9robQZ~;HUYI31;!z(`5fL53haZ@j3JJmnYNw^Dh#NlnK2`xI<c)$>EQ>tXoaq
zp?jiqTc0^p4|Vogv-7`ujUX5)6G2-KAkBIJwclN^lf9NYL-g7gz7iehb=&WEr3a8^
zJ%9qite=eB#a_vMEYbroLV5r-Mo8#YLTmW5f%E`uucQZ1Aegma;BHpK{W#JCNV6V5
zjS&)hWzZUahb%pSH0uEr2xhJC*4t{huSj|TN!A0XGeSbII9kJ>SfmG#=w3+=pg=II
z-?MvL4fjV$4<N~U0Ch%4%(-=UtKmK`=>a5J51>FWYp;R(Sq=AjNe>{&dH{7sNbG;p
z_pOHe)uacIWIcca!K@Mc{lIFtUrl-dRzrFKbw)@`{r(`U;l4ZR0VL{akRCvRVAfx!
z{K#s!?@oFEZCMYX&Ik#9^P8Ha2hf)F015=NbUV&8^G&qr(bdo7^RH7oC)77Fx!nu4
ztzHTJyFbyZa#?&6ZTddcH^B&rdvANq2=``4ProgE6U<uwuGdhnM3Io5z8zilO)x@Y
zM)I2NVeS~QqpOY)63m)3?_Jv~_pwM%KM7X~vyQxcnZ2(1Sc-)7^zHmm=L;hw?)hS+
z(Yd=O33m+%W_|phn{BV$^CLZd`?jlthgqxs?Jav<_52hG>FL|CQkM`TBu<<BSEF+$
zQW8!i63p5(zN39h+#e-9ecLN_J29*8#P{rV)gM(Pq^ED^xjL#CA@ST!>x|A_TQ-)c
zYl{T4TCePEd*xm->FFoo3}e=`(Hrb_)k{_+q^F;T`-~A17tj94=-lC!<_<ShXI9^l
z+u2^Z?@oI9X}IW^b;L8D+Uu(Cu1H8vKMkiIBP5=Db+ggA8!!zwAPHveb9WEhEB7dh
z4>AoOB(HtECSGvg7OSD2NbBia4fR1XLZVnhdirVjAW1N*-`p>(hI%5cr=Nxok`WSo
zPfbmtH5i&{4GQBGN1`vcEU+5x{}8Q#X`OX`n-LN>eg1%*gYN&J)|mvex*jyoYPgR@
zv<9XM6Rkm=5fTrdHP>pmkA+%i63qIajdxlN_v5J6Inx@{86nX+e}>g?KaOY(YMIuc
zKrrj^({8aE-`ZDwMWQvRWm<zeBP812bg9*FUy*1HYI?sbT7v??tY?!Ot%m!fL~CH0
zJJA}{86mM>kCUv1`=h9JCc&(o4!X{2xX(+p2Br}ftwD_u60Nrkw;JyAqSl!Nv!4C?
zHCDs@YN9nT#l1WU*BBvj^1^{u!~JTaH88ESdg4eh>o2{p%03T02SsaOglG+FjF33>
z?Y*pq`|d<*U|MI<8Wad-J-%eJ)o}lyXbnskE?R>cBP14G(91s$^AC#Fpq^<BhLT`b
zyC$#Uy?%Wb%(MnW86k1coSm(P6I3ooL{-p1>vsJ89}^lO5!+6P2GVqvx@X&|u{C@C
z&~3fP)#s1STkT-m?wb$|r0Fd6X_y4F4s6%aUa9JvV1&fquJ2<ts=f&l%sTM>t*u7Y
zH^B&rvAquV_fhdpkYLt`+d5l~s&9f362CfRq}8bUCP*-A_b%P6M%6dL2#JZm7-Kc6
zz6lb{+GUsRtwz;1!3c?E*Pm@Qs=f&l%-XbI2dh!_O)x@YVwVf8M%6b#f?1<p>1j2p
zz6nN1G(T}!_IZ?j6C{}R#=q=jHLAV|Mo8Q^Zj#lg`X)#)Yx9wQo>zSnjF5=4w(6T8
z!K@e=aw7LsFMR2xnx5w#k>Bo=^IW%Ye{{(|>2}ozNrG8D&wtrosp^Adgv2qIK7WYT
zxV++nB*Cm>T3@jmRUafHB&H5IWvJGu`XEU#Yusr|twz-c$q0$_XD+rHetysgNrG9u
zf4$slRDF<)koexGJ!<+ssy;{(%v$>58&;$0gJgunlCH;D4Ii(dr>>J=)(dO?Y&EJr
zNJdBuer|@<sQMsDFl)k-?^%ti50ViQ16Dt1HL5;H63n`}{|2j3^+7U1V#7zT`}?T)
zAW1Om<}W|98h#xVPlNdlwA0B530`;2(_nrBy&omPEM9|)TIa@DtICr&&!@CB{;qS-
zR7V#h4WdD3UQ6?ai^?>O>Z+!Qy;7Y-yeIcfh}Y7z&Z>?k!K`?HRo?_7B;vEF`X)#)
zD?X>HZ-NmL@g1xBCP*+VzHe3E1S2HkT&emdNH8nTo2qYu5fX9ESA7#Cm=))L)i=Qi
zi5R=8z6lb{igB#!n_z@QjKNjk1PNxvcwF^OFhU}(B~{-931-E0rRtktghX5utG)>m
z%!=z{)i=QiiN;y0=RbWDB$(AW|1%=|oNbM}i79xRn9>sWDE>a^gCxPMxL>LIAQ>SM
z_gYmSBnf84eOJ{7$q0$KXRP`lNiZw!AFDn{Mo7fHZ`B7$f?07NT=hXRLL%<rt3F5)
z%!>Q@st=M867eij^+A$gRy>zfeUOZhh-a#*50V74;`yrTgJgt6JR4ShkR+HD&xutZ
zBqJo^8Mo?#B*CnB-u3ICtes%%8p!i`$_NQwcWvzi>-EXn2?c^#yawAHKzOQ~;;dDD
zNjy#HcKki}M^y-okce$3I5I?pudCb9M{)m$_A0YAo!S_QJy9ZhC+`1{HJ$3&nobD`
zW<>|deJrx3Q$1VLDPe>}^nl#Qg8o&3U{>_C+>aCeD_PSiVT45VvfPhDPc;c<MSsqH
zMY5)o`L<<Er-Ts_(UWsu5k1u;m=%3S_eaT^PU@}IHJuVhNJMYZ{ZX=}lXZk;O{bIu
zv!cW5J}+6*$vUaBrc=rYiRh8K&r8;HvKq3cQ-NSsbc)@tCTlv?vNfGjMo2`j*Zpd;
zrc*6j)2To(EBe>&yOTAYtiLO3I;D(|h@Q3k?&zr|!K~=RyMIvDbTT)&tm%|8LLz$a
z?jPh>LV{U3BcRWm?p>5MordbuifBwyM#_YD4b>%tIhG{mSX5gVb0O-Lh}jeMP!#4^
z5=KbGT!?!!FvpTGD`rpBD^VoGHxY9z2_qz8j^%@JjKu6xfnZk5I_0jEn88Yz6*E}s
zV<{4tB}*6~5wmBxyC!Dh3IwxSvl+VF!4tE63A19hPdz_H0yBy!BP3#`F?S-xtYv{<
zR?KGRZl{<TO_>!lqw0?;5}18W86gp~vbk$3W_Sw(vts5qcZS6*a>}fjMOH6ak-$uK
z$_R;=!Ok6SF&kbWm=&|+xr;7l+*4-7jJx{oiUel$Q$|R{Y=7<s4CO$9U{)v!+@mNy
z$k0p_MuwPCRKIiR9NZHL%|yxwiDC_CCJF?zLJgswNLy<%G!rQ!B>0|e?dUeueTe=e
z4ONKtGD0n)y^PSBxQ|8FjyCOwXc`IxvqGujJ{DO!I?2|KP8lH)ni==w$lB5NK4k6a
z0>P|M+_)b{^*-6!(J3P&Li^*sBGvn-B1P7YE)dKL<&gV|WbJ4pWbNpb5fY(ca(|Sp
z9i3!rM;8cYg#ya`QL=WlogcDxbjk>c&|<mIOV*A~vbCcN1hYcP<vuT2J37tQj!qaM
z5t=ghtI68YX|{HBfnZiB(%i2mYe%Qq+R+IkBtjeK3T#<BI?dLOE)dKLWu5!(WbNoQ
zTRS>ogaog_wsv%ytsPw;n8j<b_68dMD4r8MS5$?l_Y75k6eDHA)l^r>Sqq*1(9r3t
zt4a6D-2;!cgl6BpOX7A4FThYn!V91-D!!8a3Pzg!3Pzy@iFTP=!DmM0S1{7-S1<|$
zvqDerL@4|9n1w=F{W!6$&ZnT=^Yd}$9*|$b7{mw({pL6PQBcG`!iau%!x_X^DyZ%U
zGeRO1`0h%QU%?1v|9le6((iG@=Ow>_VGafP6^sLUOoG<qqu<Jgqe^}SBaL6dV1z_$
z`>}#UVc<6rniUQOb)psA9D^C*>lWWfXwN6heQ$gQ`nn`Sx&HiQb?}6~{m>G@tkAtL
zXjVd3RZ&I!S91T(2#HYOFWzWQBq3DgJyO&OB$yRy`~xN^agjWCsIq^)JclqsBAf&_
z9;&XbDMF~<;I<OMtneY+I!!%TduN`8Rq{N=2#Ih++<dlr%ycCneS%z5BA69^iscup
z`wVW58Y3h^r+@r0U4<Bx`9C&@>V*WeLh=8|fG$G7Jx~uV_^``+4GS&!9b<MKM!HBa
zLZVcop;oUmi}gaeK6-)vUJ>-|1%g?jd;fT>{wC71nTB3ImpUUPLV-W%A^q*DKV&-n
zGQq6S@7E5~y&5N809{*Tx@dA3ArVf3d1Li=u!d)TgQ+EgS>Z$2eYMs&UOWxjlhNJ`
zBP7BRF?fa6*ew1PRo8qiDjpKd3U|ca!}XotD)Uieg*aONGeRPq9scWF&&%AM>d3Ss
zMS@wO^7mf`)2l%I0$6wf{I!OdA49W9Ykq?$Mv8>G2fW4=UHgkeLq@t|FR%AK{i&Ak
z+`X~+@b~7{zx}htw*A)TIktW0xb`i&Ev~Is`inP3j@i>!79u3{cWw2RCfuTgWuNrl
zi|St&31)4Y{&Y*D#?i0zm(^6fMlsTOUH!Y(@Vz>rYyU)vQ{{b-VAkt%pRpSH{=_*6
zf{`*2M?^eWH{NG8hM)THbrQNASu5{+)@n?9=uW9Yf{`+zv=g%){=3!aFzJ*!3EhsY
zOJ+T1HP-jNUuuwGq)aI7MC)sNq<XA+_dlXeLboGp-uUOO#t*wMlo})$DHBRNF{EF!
z)p)sg-#Q81j;!H(FR>bHdo7k4Bp4|ZN;|Rm%M-1}jt6a3C!yPswRxe}=(6TjsX>B~
zGNH5+-KLMX8spa_H4?fVS+jS4!QRI`9p8}}Bp4|ZN;}cLWun#S^27->61p8(y-)NS
zeZJl#HApa0CX{yKqo=R58Xqn1Ka_-SN7lMCyvBll?VFpLNH9_+ly>5PbysMO$)A0v
zeL_OFBkPV9ukn9NI!O%@jFbtbof!GtMOI_bx>*Sc-Hxo54gQ%=*|EFSAi+qPP}+%i
zW}jg-7EOLPA)(umwf6+Car>Wkks2fzDHBRNF?Z=GtFgnuJEbIaJF?ci?B`(nKlYXy
zBp4|ZN;~oPo<Fb}doLZ5lF;qQI^tVi<A~+@OI;)wDHBRNamAQ!R%6J{qf-*P9a){e
z>*Ljc`Te8@2}a6<(oQ_FdZ~_ylMg$5Y)V46BkR@PKJKnQ`~ayzf{`+zv=jY0{M>5%
zr0tTFgl<RH>K*+0(fyKvQiB8|WkP8uj{p4wdR3eJZucuw61v^U^6TK-L4%|Q3B6kC
z6;dN*Lg}2atFzW15!YJH>h-}>_DcC)<wP;!*ViB#dnoU`Chwz3j}-~sj;#GxJ!v)a
zqni_qlnJGsn7MkX5v}r>lhEzR`t<ETSPlP{kYJ=tDDA|}W4hJ#ee5IOT@tz-S&x67
zS`GiUlVGGwD4m~CRzuH061p8(I}h|4`B|G2jFbtb^O3;_9ZN{)c4WPAU1IMeAANFy
zkusrlKEfHHV<HLNj;yqs*T_fFoM5C(D4mbgM(Eg1LboI9)TGVcM}9TP2}a6<()ks~
z2)#y;(Cx_D;lI2_epSl}M#_ZJ`IXZMz1EV@?Z|rTZm*GFopXYbGNE*S2VjKWGmy~j
z$U5)OUL(KD$O%Tugwpw)j1hY8LqfMBYnu`Nndf&)Il)MoP}+%=U!G{hx*=QDN$7TD
zEn49<{H~7#BV|HqCwA@E>^0<Gl!R_a*617k9Q3<a5{#4yrSm&vtD*PQBy>Bnrl0HM
zRel$q6O5DzrSm&|8x!@}fP`*G)?O$1xSKys<OCySLh1a8#Rz@IA)(umrO%0aCGzJe
ZdB({JM#_ZJPL!WH<F(4qpN;3i{|DwfF9`qu

literal 0
HcmV?d00001

-- 
GitLab


From b94eab7dd1b3c637d1f7303d7cb06e99c9759c27 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 13 Feb 2019 17:26:25 +0100
Subject: [PATCH 83/87] Default controller compiles and is tested. Once
 remaining discrepancy is that the default controller switches into integrator
 mode too early

---
 .../flyingAgentGUI/include/controllertabs.h   |   3 +
 .../include/defaultcontrollertab.h            |   3 +
 .../flyingAgentGUI/src/controllertabs.cpp     |  17 +-
 .../src/defaultcontrollertab.cpp              |  18 +-
 .../include/nodes/DefaultControllerService.h  |  21 +-
 .../include/nodes/FlyingAgentClient.h         |   2 +-
 .../include/nodes/StudentControllerService.h  |   7 +-
 .../dfall_pkg/param/DefaultController.yaml    |  12 +-
 .../param/FlyingAgentClientConfig.yaml        |   2 +-
 .../src/nodes/DefaultControllerService.cpp    | 208 +++++++++++-------
 .../dfall_pkg/src/nodes/FlyingAgentClient.cpp |  46 +++-
 .../src/nodes/StudentControllerService.cpp    |  60 +++--
 12 files changed, 263 insertions(+), 136 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
index 51c29e93..eca925ea 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/controllertabs.h
@@ -60,6 +60,9 @@
 #include "dfall_pkg/CrazyflieContext.h"
 #include "dfall_pkg/CMQuery.h"
 
+// Include the DFALL service types
+#include "dfall_pkg/IntIntService.h"
+
 // Include the shared definitions
 //#include "nodes/Constants.h"
 
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
index 148335ac..64f315c4 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/include/defaultcontrollertab.h
@@ -133,6 +133,9 @@ private:
     bool m_shouldCoordinateAll = true;
     QMutex m_agentIDs_toCoordinate_mutex;
 
+    // Mutex for the current state label
+    QMutex m_label_current_state_mutex;
+
 
 
 #ifdef CATKIN_MAKE
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 899ab673..3ee513c9 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
@@ -511,8 +511,23 @@ void ControllerTabs::setAgentIDsToCoordinate(QVector<int> agentIDs , bool should
         QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
         ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());
 
+        
+        // > Request the current instant controller
+        ros::ServiceClient getInstantControllerService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("FlyingAgentClient/getInstantController", false);
+        dfall_pkg::IntIntService getInstantControllerCall;
+        getInstantControllerCall.request.data = 0;
+        getInstantControllerService.waitForExistence(ros::Duration(2.0));
+        if(getInstantControllerService.call(getInstantControllerCall))
+        {
+            setControllerEnabled(getInstantControllerCall.response.data);
+        }
+        else
+        {
+            //setControllerEnabled(CONTROLLER_UNKNOWN);
+        }
+
         // SUBSCRIBERS
-        // > For receiving message that the setpoint was changed
+        // > For receiving message that the instant controller was changed
         controllerUsedSubscriber = agent_base_nodeHandle.subscribe("FlyingAgentClient/controllerUsed", 1, &ControllerTabs::controllerUsedChangedCallback, this);
     }
     else
diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
index 4dab1f6b..4170841a 100644
--- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
+++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/defaultcontrollertab.cpp
@@ -255,28 +255,39 @@ void DefaultControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWith
 
     // UPDATE THE CURRENT STATE LABEL
     int current_state = newSetpoint.buttonID;
+    m_label_current_state_mutex.lock();
     switch (current_state)
     {
+    case DEFAULT_CONTROLLER_STATE_NORMAL:
+    {
+        ui->label_current_state->setText("normal");
+        break;
+    }
     case DEFAULT_CONTROLLER_STATE_STANDBY:
     {
         ui->label_current_state->setText("standby");
         break;
     }
-    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS:
+    case DEFAULT_CONTROLLER_STATE_TAKEOFF_SPIN_MOTORS:
     {
         ui->label_current_state->setText("Take-off, spinning motors");
         break;
     }
-    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_MOVE_UP:
+    case DEFAULT_CONTROLLER_STATE_TAKEOFF_MOVE_UP:
     {
         ui->label_current_state->setText("Take-off, moving up");
         break;
     }
-    case DEFAULT_CONTROLLER_STATE_TAKE_OFF_GOTO_SETPOINT:
+    case DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT:
     {
         ui->label_current_state->setText("Take-off, goto setpoint");
         break;
     }
+    case DEFAULT_CONTROLLER_STATE_TAKEOFF_INTEGRATOR_ON:
+    {
+        ui->label_current_state->setText("Take-off, integrator on");
+        break;
+    }
     case DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN:
     {
         ui->label_current_state->setText("Landing, move down");
@@ -298,6 +309,7 @@ void DefaultControllerTab::setpointChangedCallback(const dfall_pkg::SetpointWith
         break;
     }
     }
+    m_label_current_state_mutex.unlock();
 }
 #endif
 
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 1fc29bdb..370936b3 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -175,8 +175,8 @@ float m_time_in_seconds = 0.0;
 // PARAMETERS FROM THE YAML FILE
 
 // Max setpoint change per second
-float yaml_max_setpoint_change_per_second_horizontal = 0.1;
-float yaml_max_setpoint_change_per_second_vertical = 0.1;
+float yaml_max_setpoint_change_per_second_horizontal = 0.80;
+float yaml_max_setpoint_change_per_second_vertical   = 0.30;
 
 // Max error for z
 float yaml_max_setpoint_error_z = 0.4;
@@ -203,11 +203,11 @@ float yaml_takoff_spin_motors_time = 0.8;
 float yaml_takeoff_move_up_start_height = 0.1;
 float yaml_takeoff_move_up_end_height   = 0.4;
 // The time for: take off spin motors
-float yaml_takoff_move_up_time = 1.2;
+float yaml_takoff_move_up_time = 2.0;
 
 // Minimum and maximum allowed time for: take off goto setpoint
-float yaml_takoff_goto_setpoint_min_time = 1.2;
-float yaml_takoff_goto_setpoint_max_time = 2.0;
+float yaml_takoff_goto_setpoint_nearby_time = 1.0;
+float yaml_takoff_goto_setpoint_max_time    = 4.0;
 
 // Box within which to keep the integrator on
 // > Units of [meters]
@@ -215,7 +215,7 @@ float yaml_takoff_goto_setpoint_max_time = 2.0;
 float yaml_takoff_integrator_on_box_horizontal = 0.25;
 float yaml_takoff_integrator_on_box_vertical   = 0.15;
 // The time for: take off integrator-on
-float yaml_takoff_integrator_on_time = 1.5;
+float yaml_takoff_integrator_on_time = 2.0;
 
 
 // Height change for the landing move-down
@@ -227,7 +227,7 @@ float yaml_landing_move_down_time_max = 2.0;
 // The thrust for landing spin motors
 float yaml_landing_spin_motors_thrust = 10000;
 // The time for: landing spin motors
-float yaml_landing_spin_motors_time = 1.0;
+float yaml_landing_spin_motors_time = 1.5;
 
 
 
@@ -270,7 +270,7 @@ std::string m_namespace_to_coordinator_parameter_service;
 // > the mass of the crazyflie, in [grams]
 float yaml_cf_mass_in_grams = 25.0;
 // > the weight of the Crazyflie in Newtons, i.e., mg
-float m_cf_weight_in_newtons = 0.0;
+float m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81 / 1000.0;
 
 // > the frequency at which the controller is running
 float yaml_control_frequency = 200.0;
@@ -300,7 +300,7 @@ bool yaml_shouldDisplayDebugInfo = false;
 // VARIABLES FOR THE CONTROLLER
 
 // > A flag for which controller to use:
-int yaml_controller_method = CONTROLLER_METHOD_RATE_ANGLE_NESTED;
+int yaml_controller_method = CONTROLLER_METHOD_RATES;
 
 // The LQR Controller parameters for z-height
 std::vector<float> yaml_gainMatrixThrust_2StateVector     =  { 0.98, 0.25};
@@ -419,7 +419,7 @@ void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)
 
 // > This function constructs the error in the body frame
 //   before calling the appropriate control function
-void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response)
+void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response);
 // > The various functions that implement an LQR controller
 void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controller::Response &response);
 
@@ -457,5 +457,6 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 void publish_motors_off_to_flying_agent_client();
 
 // LOADING OF YAML PARAMETERS
+void timerCallback_initial_load_yaml(const ros::TimerEvent&);
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg);
 void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 215f13f2..4f9190d3 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -134,7 +134,7 @@ bool m_isAvailable_mocap_data = false;
 bool m_isOcculded_mocap_data = false;
 // > Number of consecutive occulsions that trigger the
 //   "m_isOcculded_mocap_data" variable to be "true"
-int yaml_consecutive_occulsions_threshold = 10;
+int yaml_consecutive_occulsions_threshold = 30;
 // > Timer that when triggered determines that the
 //   "m_isAvailable_mocap_data" variable becomes true
 ros::Timer m_timer_mocap_timeout_check;
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
index e7263ac2..91d6b3e8 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
@@ -164,6 +164,9 @@ std::string m_namespace_to_coordinator_parameter_service;
 // > the mass of the crazyflie, in [grams]
 float yaml_cf_mass_in_grams = 25.0;
 
+// The weight of the Crazyflie in Newtons, i.e., mg
+float m_cf_weight_in_newtons = yaml_cf_mass_in_grams * 9.81 / 1000.0;
+
 // > the coefficients of the 16-bit command to thrust conversion
 //std::vector<float> yaml_motorPoly(3);
 std::vector<float> yaml_motorPoly = {5.484560e-4, 1.032633e-6, 2.130295e-11};
@@ -177,8 +180,7 @@ std::vector<float> yaml_default_setpoint = {0.0,0.0,0.4,0.0};
 
 
 
-// The weight of the Crazyflie in Newtons, i.e., mg
-float m_cf_weight_in_newtons = 0.0;
+
 
 // The location error of the Crazyflie at the "previous" time step
 float m_previous_stateErrorInertial[9];
@@ -250,5 +252,6 @@ bool getCurrentSetpointCallback(GetSetpointService::Request &request, GetSetpoin
 void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived);
 
 // FOR LOADING THE YAML PARAMETERS
+void timerCallback_initial_load_yaml(const ros::TimerEvent&);
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg);
 void fetchStudentControllerYamlParameters(ros::NodeHandle& nodeHandle);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index d5b432c5..0fd3f461 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -2,7 +2,7 @@
 # PARAMTERS FOR THE TAKE-OFF AND LANDING MANOEUVRES
 
 # Max setpoint change per second
-max_setpoint_change_per_second_horizontal  :  0.50 # [meters]
+max_setpoint_change_per_second_horizontal  :  0.80 # [meters]
 max_setpoint_change_per_second_vertical    :  0.30 # [meters]
 
 # Max error for z
@@ -27,11 +27,11 @@ takoff_spin_motors_time: 0.8
 takeoff_move_up_start_height: 0.1
 takeoff_move_up_end_height:   0.4
 # The time for: take off move-up
-takoff_move_up_time: 1.2
+takoff_move_up_time: 2.0
 
 # Minimum and maximum allowed time for: take off goto setpoint
-takoff_goto_setpoint_min_time: 1.0
-takoff_goto_setpoint_max_time: 2.0
+takoff_goto_setpoint_nearby_time: 1.0
+takoff_goto_setpoint_max_time: 4.0
 
 # Box within which to keep the integrator on
 # > Units of [meters]
@@ -39,7 +39,7 @@ takoff_goto_setpoint_max_time: 2.0
 takoff_integrator_on_box_horizontal: 0.25
 takoff_integrator_on_box_vertical:   0.15
 # The time for: take off integrator-on
-takoff_integrator_on_time: 1.5
+takoff_integrator_on_time: 2.0
 
 
 # Height change for the landing move-down
@@ -51,7 +51,7 @@ landing_move_down_time_max: 2.0
 # The thrust for landing spin motors
 landing_spin_motors_thrust: 10000
 # The time for: landing spin motors
-landing_spin_motors_time: 1.0
+landing_spin_motors_time: 1.5
 
 
 # IMPORTANT NOTE: the times above should NOT be set
diff --git a/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml b/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
index cf56b8e1..76f0d0b0 100755
--- a/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
+++ b/dfall_ws/src/dfall_pkg/param/FlyingAgentClientConfig.yaml
@@ -17,7 +17,7 @@ maxTiltAngle_for_strictSafety_degrees: 70
 
 # Number of consecutive occulsions that will deem the
 # object as "long-term" occuled
-consecutive_occulsions_threshold: 10
+consecutive_occulsions_threshold: 30
 
 # Time out duration after which Mocap is considered unavailable
 mocap_timeout_duration: 2.0
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index c5e0188e..ae9e6dd6 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -82,22 +82,23 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 	// Switch between the possible manoeuvres
 	switch (requestedManoeuvre)
 	{
-		case DEFAULT_CONTROLLER_REQUEST_TAKE_OFF:
+		case DEFAULT_CONTROLLER_REQUEST_TAKEOFF:
 		{
 			// Inform the user
-			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform take-off manoeuvre.");
+			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform take-off manoeuvre. Switch to state: take-off spin motors");
 			// Reset the time variable
 			m_time_in_seconds = 0.0;
 			// Update the state accordingly
-			m_current_state = DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS;
+			m_current_state = DEFAULT_CONTROLLER_STATE_TAKEOFF_SPIN_MOTORS;
 			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
-			response.data = 1000 *
-				int(
-					+ yaml_takoff_spin_motors_time
-					+ yaml_takoff_move_up_time
-					+ yaml_takoff_goto_setpoint_max_time
-					+ yaml_takoff_integrator_on_time
+			response.data = int(
+					1000.0 * (
+						+ yaml_takoff_spin_motors_time
+						+ yaml_takoff_move_up_time
+						+ yaml_takoff_goto_setpoint_max_time
+						+ yaml_takoff_integrator_on_time
+					)
 				);
 			break;
 		}
@@ -105,17 +106,18 @@ bool requestManoeuvreCallback(IntIntService::Request &request, IntIntService::Re
 		case DEFAULT_CONTROLLER_REQUEST_LANDING:
 		{
 			// Inform the user
-			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform landing manoeuvre.");
+			ROS_INFO("[DEFAULT CONTROLLER] Received request to perform landing manoeuvre. Switch to state: landing move down");
 			// Reset the time variable
 			m_time_in_seconds = 0.0;
 			// Update the state accordingly
 			m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_MOVE_DOWN;
 			m_current_state_changed = true;
 			// Fill in the response duration in milliseconds
-			response.data = 1000 *
-				int(
-					+ yaml_landing_move_down_time_max
-					+ yaml_landing_spin_motors_time
+			response.data = int(
+					1000 * (
+						+ yaml_landing_move_down_time_max
+						+ yaml_landing_spin_motors_time
+					)
 				);
 			break;
 		}
@@ -189,7 +191,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 			computeResponse_for_normal(response);
 			break;
 
-		case DEFAULT_CONTROLLER_STATE_TAKE_OFF_SPIN_MOTORS:
+		case DEFAULT_CONTROLLER_STATE_TAKEOFF_SPIN_MOTORS:
 			computeResponse_for_takeoff_spin_motors(response);
 			break;
 
@@ -303,6 +305,8 @@ void computeResponse_for_normal(Controller::Response &response)
 		m_setpoint_for_controller[3] = m_current_stateInertialEstimate[8];
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"normal\" started with \"m_setpoint_for_controller\" (x,y,z,yaw) =  ( " << m_setpoint_for_controller[0] << ", " << m_setpoint_for_controller[1] << ", " << m_setpoint_for_controller[2] << ", " << m_setpoint_for_controller[3] << ")");
 	}
 
 	// Smooth out any setpoint changes
@@ -382,12 +386,17 @@ void computeResponse_for_takeoff_move_up(Controller::Response &response)
 		// Store the current (z,yaw)
 		initial_height = m_current_stateInertialEstimate[2];
 		initial_yaw = m_current_stateInertialEstimate[8];
+		// Put these back into the setpoint
+		m_setpoint_for_controller[2] = initial_height + yaml_takeoff_move_up_start_height;
+		m_setpoint_for_controller[3] = initial_yaw;
 		// Compute the yaw "start-to-end-difference" unwrapped
 		yaw_start_to_end_diff = m_setpoint[3] - initial_yaw;
 		while(yaw_start_to_end_diff > PI) {yaw_start_to_end_diff -= 2 * PI;}
 		while(yaw_start_to_end_diff < -PI) {yaw_start_to_end_diff += 2 * PI;}
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"take-off move-up\" started with \"m_setpoint_for_controller\" (x,y,z,yaw) =  ( " << m_setpoint_for_controller[0] << ", " << m_setpoint_for_controller[1] << ", " << m_setpoint_for_controller[2] << ", " << m_setpoint_for_controller[3] << ")");
 	}
 
 	// Compute the time elapsed as a proportion
@@ -421,13 +430,25 @@ void computeResponse_for_takeoff_move_up(Controller::Response &response)
 
 void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 {
+	// Initialise a static variable for the time
+	// to switch after entering the "box" around
+	// the setpoint
+	static float time_to_switch = 10.0;
+	static bool box_reached = false;
+
 	// Check if the state "just recently" changed
 	if (m_current_state_changed)
 	{
 		// PERFORM "ONE-OFF" OPERATIONS HERE
-		// Nothing to perform for this state
+		// Initialise the time to switch as greater than the 
+		// max time
+		time_to_switch = yaml_takoff_goto_setpoint_max_time + yaml_takoff_goto_setpoint_nearby_time;
+		// Initialise the bool for whether the box was reached
+		box_reached = false;
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"take-off goto-setpoint\" started with \"m_setpoint\" (x,y,z,yaw) =  ( " << m_setpoint[0] << ", " << m_setpoint[1] << ", " << m_setpoint[2] << ", " << m_setpoint[3] << ")");
 	}
 
 	// Smooth out any setpoint changes
@@ -436,23 +457,33 @@ void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 	// Call the LQR control function
 	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
 
-	// If minimum time is passed,
-	// then check if near to the setpoint
-	if (m_time_in_seconds > yaml_takoff_goto_setpoint_min_time)
+	// Check if within the "integrator on" box of the setpoint
+	// > First, compute the current errors
+	float error_x = m_setpoint[0] - m_current_stateInertialEstimate[0];
+	float error_y = m_setpoint[1] - m_current_stateInertialEstimate[1];
+	float error_z = m_setpoint[2] - m_current_stateInertialEstimate[2];
+	// > Then perform the check
+	if (
+		(!box_reached)
+		&&
+		((error_x) < yaml_takoff_integrator_on_box_horizontal)
+		&&
+		((-error_x) < yaml_takoff_integrator_on_box_horizontal)
+		&&
+		(abs(error_y) < yaml_takoff_integrator_on_box_horizontal)
+		&&
+		(abs(error_z) < yaml_takoff_integrator_on_box_vertical)
+	)
+	{
+		// Give it another "yaml_takoff_goto_setpoint_nearby_time"
+		// seconds before changing to the integrator
+		time_to_switch = m_time_in_seconds + yaml_takoff_goto_setpoint_nearby_time;
+		// Set the bool that the box was reached
+		box_reached = true;
+	}
+
+	if (m_time_in_seconds > time_to_switch)
 	{
-		// Compute the current errors
-		float error_x = m_setpoint[0] - m_current_stateInertialEstimate[0];
-		float error_y = m_setpoint[1] - m_current_stateInertialEstimate[1];
-		float error_z = m_setpoint[2] - m_current_stateInertialEstimate[2];
-		// Check if within the "integrator on" box
-		// of the setpoint
-		if (
-			(abs(error_x) < yaml_takoff_integrator_on_box_horizontal)
-			and
-			(abs(error_y) < yaml_takoff_integrator_on_box_horizontal)
-			and
-			(abs(error_z) < yaml_takoff_integrator_on_box_vertical)
-		)
 		// Inform the user
 		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: take-off integrator on");
 		// Reset the time variable
@@ -477,7 +508,7 @@ void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 
 
 
-void computeResponse_for_integrator_on(Controller::Response &response)
+void computeResponse_for_takeoff_integrator_on(Controller::Response &response)
 {
 	// Check if the state "just recently" changed
 	if (m_current_state_changed)
@@ -491,6 +522,8 @@ void computeResponse_for_integrator_on(Controller::Response &response)
 		m_setpoint_for_controller[3] = m_setpoint[3];
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"take-off integrator-on\" started with \"m_setpoint\" (x,y,z,yaw) =  ( " << m_setpoint[0] << ", " << m_setpoint[1] << ", " << m_setpoint[2] << ", " << m_setpoint[3] << ")");
 	}
 
 	// Call the LQR control function
@@ -530,6 +563,8 @@ void computeResponse_for_landing_move_down(Controller::Response &response)
 		initial_height = m_current_stateInertialEstimate[2];
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"landing move-down\" started with \"m_setpoint_for_controller\" (x,y,z,yaw) =  ( " << m_setpoint_for_controller[0] << ", " << m_setpoint_for_controller[1] << ", " << m_setpoint_for_controller[2] << ", " << m_setpoint_for_controller[3] << ")");
 	}
 
 	// Compute the time elapsed as a proportion
@@ -543,20 +578,20 @@ void computeResponse_for_landing_move_down(Controller::Response &response)
 	// Call the LQR control function
 	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
 
-	// Check if within the threshold of zero
-	if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
-	{
-		// Inform the user
-		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: landing spin motors");
-		// Reset the time variable
-		m_time_in_seconds = 0.0;
-		// Update the state accordingly
-		m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
-		m_current_state_changed = true;
-	}
+	// // Check if within the threshold of zero
+	// if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
+	// {
+	// 	// Inform the user
+	// 	ROS_INFO("[DEFAULT CONTROLLER] Switch to state: landing spin motors");
+	// 	// Reset the time variable
+	// 	m_time_in_seconds = 0.0;
+	// 	// Update the state accordingly
+	// 	m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
+	// 	m_current_state_changed = true;
+	// }
 
 	// Change to landing spin motors if the timeout is reached
-	if (m_time_in_seconds > yaml_landing_move_down_time_max)
+	if ( m_time_in_seconds > yaml_landing_move_down_time_max )
 	{
 		// Inform the user
 		ROS_INFO("[DEFAULT CONTROLLER] Did not reached the setpoint within the \"landing move down\" allowed time. Switch to state: landing spin motors");
@@ -579,6 +614,8 @@ void computeResponse_for_landing_spin_motors(Controller::Response &response)
 		m_setpoint_for_controller[2] = yaml_landing_move_down_end_height_setpoint;
 		// Set the change flag back to false
 		m_current_state_changed = false;
+		// Inform the user
+		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"landing spin motors\" started with \"m_setpoint_for_controller\" (x,y,z,yaw) =  ( " << m_setpoint_for_controller[0] << ", " << m_setpoint_for_controller[1] << ", " << m_setpoint_for_controller[2] << ", " << m_setpoint_for_controller[3] << ")");
 	}
 
 	// Compute the time elapsed as a proportion
@@ -619,7 +656,7 @@ void computeResponse_for_landing_spin_motors(Controller::Response &response)
 		response.controlOutput.onboardControllerType = CF_COMMAND_TYPE_MOTORS;
 
 		// Change to next state after specified time
-		if (m_time_in_seconds > yaml_landing_spin_motors_time)
+		if ( m_time_in_seconds > (0.7*yaml_landing_spin_motors_time) )
 		{
 			// Inform the user
 			ROS_INFO("[DEFAULT CONTROLLER] Switch to state: standby");
@@ -652,7 +689,7 @@ void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)
 {
 	// SMOOTH THE Z-COORIDINATE
 	// > Compute the max allowed change
-	float max_for_z = yaml_max_setpoint_change_per_second_vertical  yaml_control_frequency;
+	float max_for_z = yaml_max_setpoint_change_per_second_vertical / yaml_control_frequency;
 	// > Compute the current difference
 	float diff_for_z = target_setpoint[2] - current_setpoint[2];
 	// > Clip the difference to the maximum
@@ -665,11 +702,11 @@ void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)
 
 	// SMOOTH THE X-Y-COORIDINATES
 	// > Compute the max allowed change
-	float max_for_xy = yaml_max_setpoint_change_per_second_horizontal  yaml_control_frequency;
+	float max_for_xy = yaml_max_setpoint_change_per_second_horizontal / yaml_control_frequency;
 	// > Compute the current difference
 	float diff_for_x  = target_setpoint[0] - current_setpoint[0];
 	float diff_for_y  = target_setpoint[1] - current_setpoint[1];
-	float diff_for_xy = sqrt( diff_for_x^2 + diff_for_y^2 );
+	float diff_for_xy = sqrt( diff_for_x*diff_for_x + diff_for_y*diff_for_y );
 	// > Clip the difference to the maximum
 	if (diff_for_xy > max_for_xy)
 	{
@@ -1362,6 +1399,36 @@ void publish_motors_off_to_flying_agent_client()
 //    ----------------------------------------------------------------------------------
 
 
+// TIMER CALLBACK FOR SENDING THE LOAD YAML REQUEST
+void timerCallback_initial_load_yaml(const ros::TimerEvent&)
+{
+	// Create a node handle to the selected parameter service
+	ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyDefaultControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+	// Inform the user
+		ROS_ERROR("[DEFAULT CONTROLLER] The request load yaml file service call failed.");
+	}
+}
+
+
 // LOADING OF YAML PARAMETERS
 void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg)
 {
@@ -1429,7 +1496,7 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	yaml_max_setpoint_change_per_second_vertical = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_change_per_second_vertical");
 	
 	// Max error for z
-	yaml_max_setpoint_error_z = = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_z");
+	yaml_max_setpoint_error_z = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_z");
 
 	// Max error for yaw angle
 	yaml_max_setpoint_error_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_yaw_degrees");
@@ -1447,13 +1514,14 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	yaml_takoff_spin_motors_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_spin_motors_time");
 
 	// Height change for the take off move-up
-	yaml_takeoff_move_up_height = getParameterFloat(nodeHandle_for_paramaters , "takeoff_move_up_height");
+	yaml_takeoff_move_up_start_height = getParameterFloat(nodeHandle_for_paramaters , "takeoff_move_up_start_height");
+	yaml_takeoff_move_up_end_height = getParameterFloat(nodeHandle_for_paramaters , "takeoff_move_up_end_height");
 	// The time for the take off spin motors
 	yaml_takoff_move_up_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_move_up_time");
 
 	// Minimum and maximum allowed time for: take off goto setpoint
-	yaml_takoff_goto_setpoint_min_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_min_time");
-	yaml_takoff_goto_setpoint_max_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_max_time");
+	yaml_takoff_goto_setpoint_nearby_time = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_nearby_time");
+	yaml_takoff_goto_setpoint_max_time    = getParameterFloat(nodeHandle_for_paramaters , "takoff_goto_setpoint_max_time");
 
 	// Box within which to keep the integrator on
 	// > Units of [meters]
@@ -1531,11 +1599,6 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_positions",  yaml_PMKF_Ahat_row1_for_positions,  2);
 	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_positions",  yaml_PMKF_Ahat_row2_for_positions,  2);
 	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_positions"     ,  yaml_PMKF_Kinf_for_positions     ,  2);
-	// > For the (roll,pitch,yaw) angles
-	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row1_for_angles",  yaml_PMKF_Ahat_row1_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Ahat_row2_for_angles",  yaml_PMKF_Ahat_row2_for_angles,  2);
-	getParameterFloatVector(nodeHandle_for_paramaters, "PMKF_Kinf_for_angles"     ,  yaml_PMKF_Kinf_for_angles     ,  2);
-
 
 
 
@@ -1686,29 +1749,14 @@ int main(int argc, char* argv[])
 	// > NOTE IMPORTANTLY that by using a serice client
 	//   we stall the availability of this node until the
 	//   paramter service is ready
+	// > NOTE FURTHER that calling on the service directly from here
+	//   often means the yaml file is not actually loaded. So we
+	//   instead use a timer to delay the loading
 
-	// Create the service client as a local variable
-	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
-	// Create the service call as a local variable
-	LoadYamlFromFilename loadYamlFromFilenameCall;
-	// Specify the Yaml filename as a string
-	loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController";
-	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
-	// Wait until the serivce exists
-	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
-	// Make the service call
-	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
-	{
-		// Nothing to do in this case.
-		// The "isReadyDefaultControllerYamlCallback" function
-		// will be called once the YAML file is loaded
-	}
-	else
-	{
-	// Inform the user
-		ROS_ERROR("[DEFAULT CONTROLLER] The request load yaml file service call failed.");
-	}
+	// Create a single-shot timer
+	ros::Timer timer_initial_load_yaml = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_initial_load_yaml, true);
+	timer_initial_load_yaml.start();
+	
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index d55fd3dc..2a3996ac 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -290,16 +290,20 @@ int getPoseDataForObjectNameWithExpectedIndex(const ViconData& viconData, std::s
 
 void coordinatesToLocal(CrazyflieData& cf)
 {
+	// Get the area into a local variable
     AreaBounds area = m_context.localArea;
+
+    // Shift the X-Y coordinates
     float originX = (area.xmin + area.xmax) / 2.0;
     float originY = (area.ymin + area.ymax) / 2.0;
-    // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
-    float originZ = 0.0;
-    // float originZ = (area.zmin + area.zmax) / 2.0;
-
     cf.x -= originX;
     cf.y -= originY;
-    cf.z -= originZ;
+
+    // Shift the Z coordinate
+    // change Z origin to zero, i.e., to the table height, zero of global coordinates, instead of middle of the box
+    //float originZ = 0.0;
+    // float originZ = (area.zmin + area.zmax) / 2.0;
+    //cf.z -= originZ;
 }
 
 
@@ -501,7 +505,7 @@ void requestChangeFlyingStateToTakeOff()
 				// Call the service offered by the default
 				// controller for how long a take-off will take
 				dfall_pkg::IntIntService requestManoeurveCall;
-				requestManoeurveCall.request.data = DEFAULT_CONTROLLER_REQUEST_TAKE_OFF;
+				requestManoeurveCall.request.data = DEFAULT_CONTROLLER_REQUEST_TAKEOFF;
 				if(m_defaultController_requestManoeuvre.call(requestManoeurveCall))
 				{
 					// Extract the duration
@@ -517,6 +521,8 @@ void requestChangeFlyingStateToTakeOff()
 					ROS_INFO_STREAM("[FLYING AGENT CLIENT] Changed state to STATE_TAKE_OFF for a duration of " << take_off_duration << " seconds.");
 					// Update the class variable
 					m_flying_state = STATE_TAKE_OFF;
+					// Set the Default controller as the instant controller
+					setInstantController(DEFAULT_CONTROLLER);
 				}
 				else
 				{
@@ -590,14 +596,16 @@ void requestChangeFlyingStateToLand()
 				// > Start the timer
 				m_timer_land_complete.start();
 				// Inform the user
-				ROS_INFO_STREAM("[FLYING AGENT CLIENT] Changed state to STATE_TAKE_OFF for a duration of " << land_duration << " seconds.");
+				ROS_INFO_STREAM("[FLYING AGENT CLIENT] Changed state to STATE_LAND for a duration of " << land_duration << " seconds.");
 				// Update the class variable
 				m_flying_state = STATE_LAND;
+				// Set the Default controller as the instant controller
+				setInstantController(DEFAULT_CONTROLLER);
 			}
 			else
 			{
 				// Inform the user
-				ROS_INFO("[FLYING AGENT CLIENT] Failed to get take-off duration from Default controller. Switching to MOTORS-OFF.");
+				ROS_INFO("[FLYING AGENT CLIENT] Failed to get land duration from Default controller. Switching to MOTORS-OFF.");
 				// Update the class variable
 				m_flying_state = STATE_MOTORS_OFF;
 			}
@@ -628,6 +636,8 @@ void timerCallback_takeoff_complete(const ros::TimerEvent&)
 		std_msgs::Int32 flying_state_msg;
 		flying_state_msg.data = m_flying_state;
 		m_flyingStatePublisher.publish(flying_state_msg);
+		// Change back to the nominal controller
+		setInstantController( m_controller_nominally_selected );
 	}
 	else
 	{
@@ -649,6 +659,8 @@ void timerCallback_land_complete(const ros::TimerEvent&)
 		std_msgs::Int32 flying_state_msg;
 		flying_state_msg.data = m_flying_state;
 		m_flyingStatePublisher.publish(flying_state_msg);
+		// Change back to the nominal controller
+		setInstantController( m_controller_nominally_selected );
 	}
 	else
 	{
@@ -923,6 +935,14 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn
 }
 
 
+bool getInstantControllerServiceCallback(IntIntService::Request &request, IntIntService::Response &response)
+{
+    // Put the flying state into the response variable
+    response.data = getInstantController();
+    // Return
+    return true;
+}
+
 
 
 
@@ -1385,7 +1405,7 @@ int main(int argc, char* argv[])
 	// > And stop it immediately
 	m_timer_takeoff_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
 	m_timer_takeoff_complete.stop();
-	m_timer_land_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_takeoff_complete, true);
+	m_timer_land_complete = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_land_complete, true);
 	m_timer_land_complete.stop();
 
 
@@ -1475,7 +1495,7 @@ int main(int argc, char* argv[])
 	// crazyradio status. Connected, connecting or disconnected
 	std::string namespace_to_crazy_radio = m_namespace + "/CrazyRadio";
 	ros::NodeHandle nodeHandle_to_crazy_radio(namespace_to_crazy_radio);
-	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle_to_crazy_radio.subscribe("CrazyRadio/CrazyRadioStatus", 1, crazyRadioStatusCallback);
+	ros::Subscriber crazyRadioStatusSubscriber = nodeHandle_to_crazy_radio.subscribe("CrazyRadioStatus", 1, crazyRadioStatusCallback);
 
 
 	// SUBSCRIBER FOR BATTERY STATE CHANGES
@@ -1492,6 +1512,12 @@ int main(int argc, char* argv[])
 	ros::ServiceServer getCurrentFlyingStateService = nodeHandle.advertiseService("getCurrentFlyingState", getCurrentFlyingStateServiceCallback);
 
 
+	// SERVICE SERVER FOR OTHERS TO GET THE INSTANT CONTROLLER
+	// Advertise the service that return the "m_instant_controller"
+	// variable when called upon
+	ros::ServiceServer getInstantControllerService = nodeHandle.advertiseService("getInstantcontroller", getInstantControllerServiceCallback);
+
+
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index a1bbba1a..5a901340 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -711,6 +711,37 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 //    ----------------------------------------------------------------------------------
 
 
+// TIMER CALLBACK FOR SENDING THE LOAD YAML REQUEST
+// This function does NOT need to be edited
+void timerCallback_initial_load_yaml(const ros::TimerEvent&)
+{
+	// Create a node handle to the selected parameter service
+	ros::NodeHandle nodeHandle_to_own_agent_parameter_service(m_namespace_to_own_agent_parameter_service);
+	// Create the service client as a local variable
+	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
+	// Create the service call as a local variable
+	LoadYamlFromFilename loadYamlFromFilenameCall;
+	// Specify the Yaml filename as a string
+	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
+	// Set for whom this applies to
+	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
+	// Wait until the serivce exists
+	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
+	// Make the service call
+	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
+	{
+		// Nothing to do in this case.
+		// The "isReadyStudentControllerYamlCallback" function
+		// will be called once the YAML file is loaded
+	}
+	else
+	{
+		// Inform the user
+		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
+	}
+}
+
+
 // LOADING OF YAML PARAMETERS
 // This function does NOT need to be edited 
 void isReadyStudentControllerYamlCallback(const IntWithHeader & msg)
@@ -942,29 +973,14 @@ int main(int argc, char* argv[]) {
 	// > NOTE IMPORTANTLY that by using a serice client
 	//   we stall the availability of this node until the
 	//   paramter service is ready
+	// > NOTE FURTHER that calling on the service directly from here
+	//   often means the yaml file is not actually loaded. So we
+	//   instead use a timer to delay the loading
+
+	// Create a single-shot timer
+	ros::Timer timer_initial_load_yaml = nodeHandle.createTimer(ros::Duration(1.0), timerCallback_initial_load_yaml, true);
+	timer_initial_load_yaml.start();
 
-	// Create the service client as a local variable
-	ros::ServiceClient requestLoadYamlFilenameServiceClient = nodeHandle_to_own_agent_parameter_service.serviceClient<LoadYamlFromFilename>("requestLoadYamlFilename", false);
-	// Create the service call as a local variable
-	LoadYamlFromFilename loadYamlFromFilenameCall;
-	// Specify the Yaml filename as a string
-	loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController";
-	// Set for whom this applies to
-	loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false;
-	// Wait until the serivce exists
-	requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1));
-	// Make the service call
-	if(requestLoadYamlFilenameServiceClient.call(loadYamlFromFilenameCall))
-	{
-		// Nothing to do in this case.
-		// The "isReadyStudentControllerYamlCallback" function
-		// will be called once the YAML file is loaded
-	}
-	else
-	{
-		// Inform the user
-		ROS_ERROR("[STUDENT CONTROLLER] The request load yaml file service call failed.");
-	}
 
 
 
-- 
GitLab


From c4a2676395c122faca84435566ccbf125ce63735 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Wed, 13 Feb 2019 23:43:04 +0100
Subject: [PATCH 84/87] Fixed abs() int casting causing errors for default
 controller state changes. Added integrator to default controller. Needs
 testing and adding buttons to GUI for run integrator and reset integrator.

---
 .../include/nodes/DefaultControllerService.h  |  15 ++-
 .../dfall_pkg/param/DefaultController.yaml    |   4 +
 .../src/nodes/DefaultControllerService.cpp    | 110 ++++++++++++------
 3 files changed, 91 insertions(+), 38 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 370936b3..c20633f2 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -144,7 +144,10 @@ using namespace dfall_pkg;
 #define ESTIMATOR_METHOD_POINT_MASS_PER_DIMENSION   2   // (DEFAULT)
 
 
-
+// These constants deine the behaviour of the intergrator
+#define INTEGRATOR_FLAG_ON       1
+#define INTEGRATOR_FLAG_OFF      2
+#define INTEGRATOR_FLAG_RESET    3
 
 
 
@@ -247,7 +250,6 @@ bool m_shouldSmoothSetpointChanges = true;
 
 
 
-
 // ------------------------------------------------------
 // VARIABLES THAT ARE STANDARD FOR A "CONTROLLER SERVICE"
 
@@ -314,6 +316,10 @@ float yaml_gainRollRate_fromAngle   =  4.00;
 float yaml_gainPitchRate_fromAngle  =  4.00;
 // The LQR Controller parameters for yaw
 float yaml_gainYawRate_fromAngle    =  2.30;
+// Integrator gains
+float yaml_integratorGain_forThrust = 0.0;
+float yaml_integratorGain_forTauXY  = 0.0;
+float yaml_integratorGain_forTauYaw = 0.0;
 
 
 // VARIABLES FOR THE ESTIMATOR
@@ -413,15 +419,14 @@ void computeResponse_for_takeoff_integrator_on(Controller::Response &response);
 void computeResponse_for_landing_move_down(Controller::Response &response);
 void computeResponse_for_landing_spin_motors(Controller::Response &response);
 
-
 // SMOOTHING SETPOINT CHANGES
 void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)[4] );
 
 // > This function constructs the error in the body frame
 //   before calling the appropriate control function
-void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response);
+void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[9], Controller::Response &response, int integrator_flag);
 // > The various functions that implement an LQR controller
-void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controller::Response &response);
+void calculateControlOutput_viaLQR_givenError(float stateErrorBody[9], Controller::Response &response, int integrator_flag);
 
 // ESTIMATOR COMPUTATIONS
 void performEstimatorUpdate_forStateInterial(Controller::Request &request);
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index 0fd3f461..3a5105d6 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -102,6 +102,10 @@ gainRollRate_fromAngle   :  4.00
 gainPitchRate_fromAngle  :  4.00
 # The LQR Controller parameters for yaw
 gainYawRate_fromAngle    :  2.30
+# Integrator gains
+integratorGain_forThrust  :  0.01
+integratorGain_forTauXY   :  0.01
+integratorGain_forTauYaw  :  0.01
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index ae9e6dd6..47463df7 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -226,9 +226,13 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 	// Change to standby state if the {roll,pitch}
 	// angles exceed the threshold
 	if (
-		(abs(m_current_stateInertialEstimate[6]) > yaml_threshold_roll_pitch_for_turn_off_radians)
+		(m_current_stateInertialEstimate[6] >  yaml_threshold_roll_pitch_for_turn_off_radians)
 		or
-		(abs(m_current_stateInertialEstimate[7]) > yaml_threshold_roll_pitch_for_turn_off_radians)
+		(m_current_stateInertialEstimate[6] < -yaml_threshold_roll_pitch_for_turn_off_radians)
+		or
+		(m_current_stateInertialEstimate[7] > yaml_threshold_roll_pitch_for_turn_off_radians)
+		or
+		(m_current_stateInertialEstimate[7] < -yaml_threshold_roll_pitch_for_turn_off_radians)
 	)
 	{
 		// Inform the user
@@ -313,7 +317,7 @@ void computeResponse_for_normal(Controller::Response &response)
 	smoothSetpointChanges( m_setpoint , m_setpoint_for_controller );
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
 }
 
@@ -411,7 +415,7 @@ void computeResponse_for_takeoff_move_up(Controller::Response &response)
 	m_setpoint_for_controller[3] = initial_yaw + time_elapsed_proportion * yaw_start_to_end_diff;
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
 	// Change to next state after specified time
 	if (m_time_in_seconds > yaml_takoff_move_up_time)
@@ -455,24 +459,25 @@ void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 	smoothSetpointChanges( m_setpoint , m_setpoint_for_controller );
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
 	// Check if within the "integrator on" box of the setpoint
 	// > First, compute the current errors
-	float error_x = m_setpoint[0] - m_current_stateInertialEstimate[0];
-	float error_y = m_setpoint[1] - m_current_stateInertialEstimate[1];
-	float error_z = m_setpoint[2] - m_current_stateInertialEstimate[2];
+	float abs_error_x = m_setpoint[0] - m_current_stateInertialEstimate[0];
+	float abs_error_y = m_setpoint[1] - m_current_stateInertialEstimate[1];
+	float abs_error_z = m_setpoint[2] - m_current_stateInertialEstimate[2];
+	if (abs_error_x<0.0){abs_error_x=-abs_error_x;}
+	if (abs_error_y<0.0){abs_error_y=-abs_error_y;}
+	if (abs_error_z<0.0){abs_error_z=-abs_error_z;}
 	// > Then perform the check
 	if (
 		(!box_reached)
-		&&
-		((error_x) < yaml_takoff_integrator_on_box_horizontal)
-		&&
-		((-error_x) < yaml_takoff_integrator_on_box_horizontal)
-		&&
-		(abs(error_y) < yaml_takoff_integrator_on_box_horizontal)
-		&&
-		(abs(error_z) < yaml_takoff_integrator_on_box_vertical)
+		and
+		(abs_error_x < yaml_takoff_integrator_on_box_horizontal)
+		and
+		(abs_error_y < yaml_takoff_integrator_on_box_horizontal)
+		and
+		(abs_error_z < yaml_takoff_integrator_on_box_vertical)
 	)
 	{
 		// Give it another "yaml_takoff_goto_setpoint_nearby_time"
@@ -482,6 +487,8 @@ void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 		box_reached = true;
 	}
 
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] time = " << m_time_in_seconds << ", switch at = " << time_to_switch << " abs error (x,y,z) = ( " << abs_error_x << ", " << abs_error_y << ", " << abs_error_z << ")" );
+
 	if (m_time_in_seconds > time_to_switch)
 	{
 		// Inform the user
@@ -527,7 +534,7 @@ void computeResponse_for_takeoff_integrator_on(Controller::Response &response)
 	}
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response , INTEGRATOR_FLAG_ON);
 
 	// Change to next state after specified time
 	if (m_time_in_seconds > yaml_takoff_integrator_on_time)
@@ -576,7 +583,7 @@ void computeResponse_for_landing_move_down(Controller::Response &response)
 	m_setpoint_for_controller[2] = initial_height + time_elapsed_proportion * (yaml_landing_move_down_end_height_setpoint-initial_height);
 
 	// Call the LQR control function
-	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
 	// // Check if within the threshold of zero
 	// if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
@@ -628,7 +635,7 @@ void computeResponse_for_landing_spin_motors(Controller::Response &response)
 	if (time_elapsed_proportion<0.5)
 	{
 		// Call the LQR control function
-		calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response);
+		calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 		// Compute the desired "spinning" thrust
 		float thrust_for_spinning =
 			(1.0-time_elapsed_proportion)
@@ -670,6 +677,9 @@ void computeResponse_for_landing_spin_motors(Controller::Response &response)
 }
 
 
+
+
+
 //    ------------------------------------------------------------------------------
 //     SSSS  M   M   OOO    OOO   TTTTT  H   H
 //    S      MM MM  O   O  O   O    T    H   H
@@ -875,7 +885,7 @@ void performEstimatorUpdate_forStateInterial_viaPointMassKalmanFilter()
 
 // > This function constructs the error in the body frame
 //   before calling the appropriate control function
-void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[12], Controller::Response &response)
+void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateInertial[9], Controller::Response &response, int integrator_flag )
 {
 	// Store the current YAW in a local variable
 	float temp_stateInertial_yaw = stateInertial[8];
@@ -915,13 +925,20 @@ void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateI
 	// the Inertial frame into the Body frame
 	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
 
-	calculateControlOutput_viaLQR_givenError(bodyFrameError, response);
+	calculateControlOutput_viaLQR_givenError(bodyFrameError, response, integrator_flag);
 }
 
-void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controller::Response &response)
+void calculateControlOutput_viaLQR_givenError(float stateErrorBody[9], Controller::Response &response, int integrator_flag)
 {
 	// PERFORM THE "u=Kx" LQR CONTROLLER COMPUTATION
 
+	// Initialise static variables for the integral
+	static float newtons_int = 0.0;
+	static float tau_x = 0.0;
+	static float tau_y = 0.0;
+	static float tau_z = 0.0;
+	
+
 	// Compute the Z-CONTROLLER
 	// > provides the total thrust adjustment
 	float thrustAdjustment =
@@ -1003,6 +1020,21 @@ void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controll
 	}
 
 
+	// PERFORM THE INTEGRATOR COMPUTATIONS
+	if (integrator_flag == INTEGRATOR_FLAG_ON)
+	{
+		newtons_int -= yaml_integratorGain_forThrust * stateErrorBody[2] / yaml_control_frequency;
+		tau_x       += yaml_integratorGain_forTauXY  * stateErrorBody[1] / yaml_control_frequency;
+		tau_y       -= yaml_integratorGain_forTauXY  * stateErrorBody[0] / yaml_control_frequency;
+		tau_z       -= yaml_integratorGain_forTauYaw * stateErrorBody[8] / yaml_control_frequency;
+	}
+	else if (integrator_flag == INTEGRATOR_FLAG_RESET)
+	{
+		newtons_int = 0.0;
+		tau_x       = 0.0;
+		tau_y       = 0.0;
+		tau_z	    = 0.0;
+	}
 
 	// UPDATE THE "RETURN" THE VARIABLE NAMED "response"
 
@@ -1017,12 +1049,12 @@ void calculateControlOutput_viaLQR_givenError(float stateErrorBody[12], Controll
 	//         controller needed to be divided by 4 or not.
 	thrustAdjustment = thrustAdjustment / 4.0;
 	// > Compute the feed-forward force
-	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0;
+	float feed_forward_thrust_per_motor = m_cf_weight_in_newtons / 4.0 + newtons_int;
 	// > Put in the per motor commands
-	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
-	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
-	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
-	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor);
+	response.controlOutput.motorCmd1 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor - tau_x - tau_y - tau_z);
+	response.controlOutput.motorCmd2 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor - tau_x + tau_y + tau_z);
+	response.controlOutput.motorCmd3 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor + tau_x + tau_y - tau_z);
+	response.controlOutput.motorCmd4 = computeMotorPolyBackward(thrustAdjustment + feed_forward_thrust_per_motor + tau_x - tau_y + tau_z);
 
 	
 	// Specify that this controller is a rate controller
@@ -1325,10 +1357,13 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			// > FOR CUSTOM BUTTON 1
 			case 1:
 			{
-				// Let the user know that this part of the code was triggered
-				ROS_INFO("[DEFAULT CONTROLLER] Button 1 received in controller.");
-				// Code here to respond to custom button 1
-				
+				// Inform the user
+				ROS_INFO("[DEFAULT CONTROLLER] Received request to run integrator. Switch to state: take-off goto-setpoint");
+				// Reset the time variable
+				m_time_in_seconds = 0.0;
+				// Update the state accordingly
+				m_current_state = DEFAULT_CONTROLLER_STATE_TAKEOFF_GOTO_SETPOINT;
+				m_current_state_changed = true;
 				break;
 			}
 
@@ -1336,8 +1371,11 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived
 			case 2:
 			{
 				// Let the user know that this part of the code was triggered
-				ROS_INFO("[DEFAULT CONTROLLER] Button 2 received in controller.");
-				// Code here to respond to custom button 2
+				ROS_INFO("[DEFAULT CONTROLLER] Received request to reset the integrator.");
+				// Call the controller function with the reset flag
+				float tempStateBodyError[9];
+				Controller::Response temp_response;
+				calculateControlOutput_viaLQR_givenError(tempStateBodyError, temp_response, INTEGRATOR_FLAG_RESET);
 
 				break;
 			}
@@ -1590,6 +1628,11 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	yaml_gainPitchRate_fromAngle = getParameterFloat(nodeHandle_for_paramaters, "gainPitchRate_fromAngle");
 	// The LQR Controller parameters for yaw
 	yaml_gainYawRate_fromAngle = getParameterFloat(nodeHandle_for_paramaters, "gainYawRate_fromAngle");
+	// Integrator gains
+	yaml_integratorGain_forThrust = getParameterFloat(nodeHandle_for_paramaters, "integratorGain_forThrust");
+	yaml_integratorGain_forTauXY  = getParameterFloat(nodeHandle_for_paramaters, "integratorGain_forTauXY");
+	yaml_integratorGain_forTauYaw = getParameterFloat(nodeHandle_for_paramaters, "integratorGain_forTauYaw");
+
 	
 	// A flag for which estimator to use:
 	yaml_estimator_method = getParameterInt( nodeHandle_for_paramaters , "estimator_method" );
@@ -1760,6 +1803,7 @@ int main(int argc, char* argv[])
 
 
 
+
 	// PUBLISHERS AND SUBSCRIBERS
 
 	// Instantiate the class variable "m_debugPublisher" to be a
-- 
GitLab


From 60e963960e3ef9094c659176f8cf06e48d9c2407 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 14 Feb 2019 00:19:52 +0100
Subject: [PATCH 85/87] Adjusted landing move down function of default
 controller to make the landing smoother

---
 .../include/nodes/DefaultControllerService.h  |  2 +-
 .../dfall_pkg/param/DefaultController.yaml    |  4 +-
 .../src/nodes/DefaultControllerService.cpp    | 46 ++++++++++---------
 3 files changed, 27 insertions(+), 25 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index c20633f2..7ba8f80a 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -178,7 +178,7 @@ float m_time_in_seconds = 0.0;
 // PARAMETERS FROM THE YAML FILE
 
 // Max setpoint change per second
-float yaml_max_setpoint_change_per_second_horizontal = 0.80;
+float yaml_max_setpoint_change_per_second_horizontal = 0.60;
 float yaml_max_setpoint_change_per_second_vertical   = 0.30;
 
 // Max error for z
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index 3a5105d6..38e728fc 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -2,7 +2,7 @@
 # PARAMTERS FOR THE TAKE-OFF AND LANDING MANOEUVRES
 
 # Max setpoint change per second
-max_setpoint_change_per_second_horizontal  :  0.80 # [meters]
+max_setpoint_change_per_second_horizontal  :  0.60 # [meters]
 max_setpoint_change_per_second_vertical    :  0.30 # [meters]
 
 # Max error for z
@@ -46,7 +46,7 @@ takoff_integrator_on_time: 2.0
 landing_move_down_end_height_setpoint:  0.05
 landing_move_down_end_height_threshold: 0.10
 # The time for: landing move-down
-landing_move_down_time_max: 2.0
+landing_move_down_time_max: 4.0
 
 # The thrust for landing spin motors
 landing_spin_motors_thrust: 10000
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index 47463df7..b7d42b07 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -556,46 +556,48 @@ void computeResponse_for_takeoff_integrator_on(Controller::Response &response)
 void computeResponse_for_landing_move_down(Controller::Response &response)
 {
 	// Initialise a static variable for the starting height and yaw
-	static float initial_height = 0.4;
+	static float target_landing_setpoint[4] = {0.0,0.0,0.4,0.0};
 
 	// Check if the state "just recently" changed
 	if (m_current_state_changed)
 	{
 		// PERFORM "ONE-OFF" OPERATIONS HERE
-		// Set the current (x,y,yaw) location as the setpoint
+		// Set the current (x,y,z,yaw) location as the setpoint
 		m_setpoint_for_controller[0] = m_current_stateInertialEstimate[0];
 		m_setpoint_for_controller[1] = m_current_stateInertialEstimate[1];
+		m_setpoint_for_controller[2] = m_current_stateInertialEstimate[2];
 		m_setpoint_for_controller[3] = m_current_stateInertialEstimate[8];
-		// Store the current z
-		initial_height = m_current_stateInertialEstimate[2];
+		// Make the target setpoint the same for (x,y,yaw)
+		target_landing_setpoint[0] = m_setpoint_for_controller[0];
+		target_landing_setpoint[1] = m_setpoint_for_controller[1];
+		target_landing_setpoint[3] = m_setpoint_for_controller[3];
+		// Set the target height
+		target_landing_setpoint[2] = yaml_landing_move_down_end_height_setpoint;
 		// Set the change flag back to false
 		m_current_state_changed = false;
 		// Inform the user
 		ROS_INFO_STREAM("[DEFAULT CONTROLLER] state \"landing move-down\" started with \"m_setpoint_for_controller\" (x,y,z,yaw) =  ( " << m_setpoint_for_controller[0] << ", " << m_setpoint_for_controller[1] << ", " << m_setpoint_for_controller[2] << ", " << m_setpoint_for_controller[3] << ")");
 	}
 
-	// Compute the time elapsed as a proportion
-	float time_elapsed_proportion = m_time_in_seconds / (0.8*yaml_landing_move_down_time_max);
-	if (time_elapsed_proportion > 1.0)
-		time_elapsed_proportion = 1.0;
-
-	// Compute the z-height setpoint
-	m_setpoint_for_controller[2] = initial_height + time_elapsed_proportion * (yaml_landing_move_down_end_height_setpoint-initial_height);
+	// Smooth out any setpoint changes
+	smoothSetpointChanges( target_landing_setpoint , m_setpoint_for_controller );
 
 	// Call the LQR control function
 	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
-	// // Check if within the threshold of zero
-	// if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
-	// {
-	// 	// Inform the user
-	// 	ROS_INFO("[DEFAULT CONTROLLER] Switch to state: landing spin motors");
-	// 	// Reset the time variable
-	// 	m_time_in_seconds = 0.0;
-	// 	// Update the state accordingly
-	// 	m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
-	// 	m_current_state_changed = true;
-	// }
+	ROS_INFO_STREAM("[DEFAULT CONTROLLER] m_current_stateInertialEstimate[2] = " << m_current_stateInertialEstimate[2] );
+
+	// Check if within the threshold of zero
+	if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
+	{
+		// Inform the user
+		ROS_INFO("[DEFAULT CONTROLLER] Switch to state: landing spin motors");
+		// Reset the time variable
+		m_time_in_seconds = 0.0;
+		// Update the state accordingly
+		m_current_state = DEFAULT_CONTROLLER_STATE_LANDING_SPIN_MOTORS;
+		m_current_state_changed = true;
+	}
 
 	// Change to landing spin motors if the timeout is reached
 	if ( m_time_in_seconds > yaml_landing_move_down_time_max )
-- 
GitLab


From d4e2a9d8b1bc8988a7dcf0903655dde82cef2964 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Thu, 14 Feb 2019 10:41:44 +0100
Subject: [PATCH 86/87] Fixed small bugs in Default controller. Now (almost)
 fully tested and working smoothly.

---
 .../include/nodes/DefaultControllerService.h  | 15 +++--
 .../dfall_pkg/param/DefaultController.yaml    | 19 +++---
 .../src/nodes/DefaultControllerService.cpp    | 60 ++++++++++++++-----
 3 files changed, 64 insertions(+), 30 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
index 7ba8f80a..b415d987 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/DefaultControllerService.h
@@ -179,19 +179,22 @@ float m_time_in_seconds = 0.0;
 
 // Max setpoint change per second
 float yaml_max_setpoint_change_per_second_horizontal = 0.60;
-float yaml_max_setpoint_change_per_second_vertical   = 0.30;
+float yaml_max_setpoint_change_per_second_vertical   = 0.40;
 
 // Max error for z
 float yaml_max_setpoint_error_z = 0.4;
 
-// Max error for yaw angle
-float yaml_max_setpoint_error_yaw_degrees = 60.0;
-float yaml_max_setpoint_error_yaw_radians = 60.0 * DEG2RAD;
+// Max error for xy
+float yaml_max_setpoint_error_xy = 0.3;
 
 // Max {roll,pitch} angle request
 float yaml_max_roll_pitch_request_degrees = 30.0;
 float yaml_max_roll_pitch_request_radians = 30.0 * DEG2RAD;
 
+// Max error for yaw angle
+float yaml_max_setpoint_error_yaw_degrees = 60.0;
+float yaml_max_setpoint_error_yaw_radians = 60.0 * DEG2RAD;
+
 // Theshold for {roll,pitch} angle beyond
 // which the motors are turned off
 float yaml_threshold_roll_pitch_for_turn_off_degrees = 70.0;
@@ -225,7 +228,7 @@ float yaml_takoff_integrator_on_time = 2.0;
 float yaml_landing_move_down_end_height_setpoint  = 0.05;
 float yaml_landing_move_down_end_height_threshold = 0.10;
 // The time for: landing move-down
-float yaml_landing_move_down_time_max = 2.0;
+float yaml_landing_move_down_time_max = 5.0;
 
 // The thrust for landing spin motors
 float yaml_landing_spin_motors_thrust = 10000;
@@ -302,7 +305,7 @@ bool yaml_shouldDisplayDebugInfo = false;
 // VARIABLES FOR THE CONTROLLER
 
 // > A flag for which controller to use:
-int yaml_controller_method = CONTROLLER_METHOD_RATES;
+int yaml_controller_method = CONTROLLER_METHOD_RATE_ANGLE_NESTED;
 
 // The LQR Controller parameters for z-height
 std::vector<float> yaml_gainMatrixThrust_2StateVector     =  { 0.98, 0.25};
diff --git a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
index 38e728fc..64d77b13 100644
--- a/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
+++ b/dfall_ws/src/dfall_pkg/param/DefaultController.yaml
@@ -3,17 +3,20 @@
 
 # Max setpoint change per second
 max_setpoint_change_per_second_horizontal  :  0.60 # [meters]
-max_setpoint_change_per_second_vertical    :  0.30 # [meters]
+max_setpoint_change_per_second_vertical    :  0.40 # [meters]
 
 # Max error for z
 max_setpoint_error_z: 0.4
 
-# Max error for yaw angle
-max_setpoint_error_yaw_degrees: 60
+# Max error for xy
+max_setpoint_error_xy: 0.3
 
 # Max {roll,pitch} angle request
 max_roll_pitch_request_degrees: 30
 
+# Max error for yaw angle
+max_setpoint_error_yaw_degrees: 60
+
 # Theshold for {roll,pitch} angle beyond
 # which the motors are turned off
 threshold_roll_pitch_for_turn_off_degrees: 70
@@ -46,7 +49,7 @@ takoff_integrator_on_time: 2.0
 landing_move_down_end_height_setpoint:  0.05
 landing_move_down_end_height_threshold: 0.10
 # The time for: landing move-down
-landing_move_down_time_max: 4.0
+landing_move_down_time_max: 5.0
 
 # The thrust for landing spin motors
 landing_spin_motors_thrust: 10000
@@ -88,7 +91,7 @@ shouldDisplayDebugInfo : false
 # A flag for which controller to use, defined as:
 # 1  -  Rate controller
 # 2  -  Angle-Rate nested controller
-controller_method : 1
+controller_method : 2
 
 # The LQR Controller parameters for z-height
 gainMatrixThrust_2StateVector     :  [ 0.98, 0.25]
@@ -103,9 +106,9 @@ gainPitchRate_fromAngle  :  4.00
 # The LQR Controller parameters for yaw
 gainYawRate_fromAngle    :  2.30
 # Integrator gains
-integratorGain_forThrust  :  0.01
-integratorGain_forTauXY   :  0.01
-integratorGain_forTauYaw  :  0.01
+integratorGain_forThrust  :  0.00
+integratorGain_forTauXY   :  0.00
+integratorGain_forTauYaw  :  0.00
 
 
 
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
index b7d42b07..d19321f1 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp
@@ -487,8 +487,6 @@ void computeResponse_for_takeoff_goto_setpoint(Controller::Response &response)
 		box_reached = true;
 	}
 
-	ROS_INFO_STREAM("[DEFAULT CONTROLLER] time = " << m_time_in_seconds << ", switch at = " << time_to_switch << " abs error (x,y,z) = ( " << abs_error_x << ", " << abs_error_y << ", " << abs_error_z << ")" );
-
 	if (m_time_in_seconds > time_to_switch)
 	{
 		// Inform the user
@@ -585,8 +583,6 @@ void computeResponse_for_landing_move_down(Controller::Response &response)
 	// Call the LQR control function
 	calculateControlOutput_viaLQR_givenSetpoint(m_setpoint_for_controller, m_current_stateInertialEstimate, response, INTEGRATOR_FLAG_OFF);
 
-	ROS_INFO_STREAM("[DEFAULT CONTROLLER] m_current_stateInertialEstimate[2] = " << m_current_stateInertialEstimate[2] );
-
 	// Check if within the threshold of zero
 	if (m_current_stateInertialEstimate[2] < yaml_landing_move_down_end_height_threshold)
 	{
@@ -699,6 +695,10 @@ void computeResponse_for_landing_spin_motors(Controller::Response &response)
 
 void smoothSetpointChanges( float target_setpoint[4] , float (&current_setpoint)[4] )
 {
+	// NO SMOOTHING IS APPLIED TO THE YAW-COORDINATE
+	// > Hence copy it across directly
+	current_setpoint[3] = target_setpoint[3];
+
 	// SMOOTH THE Z-COORIDINATE
 	// > Compute the max allowed change
 	float max_for_z = yaml_max_setpoint_change_per_second_vertical / yaml_control_frequency;
@@ -892,16 +892,41 @@ void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateI
 	// Store the current YAW in a local variable
 	float temp_stateInertial_yaw = stateInertial[8];
 
+	// Initialise an array for the state error in the inertial frame
+	float stateInertialError[9];
+
 	// Adjust the INERTIAL (x,y,z) position for the setpoint
-	stateInertial[0] = stateInertial[0] - setpoint[0];
-	stateInertial[1] = stateInertial[1] - setpoint[1];
-	stateInertial[2] = stateInertial[2] - setpoint[2];
+	stateInertialError[0] = stateInertial[0] - setpoint[0];
+	stateInertialError[1] = stateInertial[1] - setpoint[1];
+	stateInertialError[2] = stateInertial[2] - setpoint[2];
+
+	// The linear velocities can be directly copied across
+	stateInertialError[3] = stateInertial[3];
+	stateInertialError[4] = stateInertial[4];
+	stateInertialError[5] = stateInertial[5];
+
+	// The angular velocities for {roll,pitch} can be directly
+	// copied across
+	stateInertialError[6] = stateInertial[6];
+	stateInertialError[7] = stateInertial[7];
+
+	// Clip the x-coordination to within the specified bounds
+	if (stateInertialError[0] > yaml_max_setpoint_error_xy)
+		stateInertialError[0] = yaml_max_setpoint_error_xy;
+	else if (stateInertialError[0] < -yaml_max_setpoint_error_xy)
+		stateInertialError[0] = -yaml_max_setpoint_error_xy;
+
+	// Clip the y-coordination to within the specified bounds
+	if (stateInertialError[1] > yaml_max_setpoint_error_xy)
+		stateInertialError[1] = yaml_max_setpoint_error_xy;
+	else if (stateInertialError[1] < -yaml_max_setpoint_error_xy)
+		stateInertialError[1] = -yaml_max_setpoint_error_xy;
 
 	// Clip the z-coordination to within the specified bounds
-	if (stateInertial[2] > yaml_max_setpoint_error_z)
-		stateInertial[2] = yaml_max_setpoint_error_z;
-	else if (stateInertial[2] < -yaml_max_setpoint_error_z)
-		stateInertial[2] = -yaml_max_setpoint_error_z;
+	if (stateInertialError[2] > yaml_max_setpoint_error_z)
+		stateInertialError[2] = yaml_max_setpoint_error_z;
+	else if (stateInertialError[2] < -yaml_max_setpoint_error_z)
+		stateInertialError[2] = -yaml_max_setpoint_error_z;
 
 	// Fill in the yaw angle error
 	// > This error should be "unwrapped" to be in the range
@@ -918,14 +943,14 @@ void calculateControlOutput_viaLQR_givenSetpoint(float setpoint[4], float stateI
 		yawError = -yaml_max_setpoint_error_yaw_radians;
 
 	// > Finally, put the "yawError" into the "stateError" variable
-	stateInertial[8] = yawError;
+	stateInertialError[8] = yawError;
 
 	// CONVERSION INTO BODY FRAME
 	// Initialise a variable for the body frame error
 	float bodyFrameError[9];
 	// Call the function to convert the state erorr from
 	// the Inertial frame into the Body frame
-	convertIntoBodyFrame(stateInertial, bodyFrameError, temp_stateInertial_yaw);
+	convertIntoBodyFrame(stateInertialError, bodyFrameError, temp_stateInertial_yaw);
 
 	calculateControlOutput_viaLQR_givenError(bodyFrameError, response, integrator_flag);
 }
@@ -1538,12 +1563,15 @@ void fetchDefaultControllerYamlParameters(ros::NodeHandle& nodeHandle)
 	// Max error for z
 	yaml_max_setpoint_error_z = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_z");
 
-	// Max error for yaw angle
-	yaml_max_setpoint_error_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_yaw_degrees");
-
+	// Max error for xy
+	yaml_max_setpoint_error_xy = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_xy");
+	
 	// Max {roll,pitch} angle request
 	yaml_max_roll_pitch_request_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_roll_pitch_request_degrees");
 
+	// Max error for yaw angle
+	yaml_max_setpoint_error_yaw_degrees = getParameterFloat(nodeHandle_for_paramaters , "max_setpoint_error_yaw_degrees");
+
 	// Theshold for {roll,pitch} angle beyond
 	// which the motors are turned off
 	yaml_threshold_roll_pitch_for_turn_off_degrees = getParameterFloat(nodeHandle_for_paramaters , "threshold_roll_pitch_for_turn_off_degrees");
-- 
GitLab


From fbade28c49d249f71303a79569cadbdbabaea3a6 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Thu, 14 Feb 2019 10:50:50 +0100
Subject: [PATCH 87/87] Adjusted Flying Agent Client header to have correct
 copyright details

---
 dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h | 1 +
 dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp   | 3 ++-
 2 files changed, 3 insertions(+), 1 deletion(-)

diff --git a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
index 4f9190d3..2491524e 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/FlyingAgentClient.h
@@ -1,3 +1,4 @@
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
 //    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
 //
 //    This file is part of D-FaLL-System.
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
index 2a3996ac..14c80a6a 100755
--- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp
@@ -1,4 +1,5 @@
-//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
+//    Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
+//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat, Angel Romero, Cyrill Burgener, Marco Mueller, Philipp Friedli
 //
 //    This file is part of D-FaLL-System.
 //    
-- 
GitLab