From e9be5ad9fa287aa0017a8f4d3412992f9d43ee2c Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Wed, 25 Apr 2018 11:22:17 +0200
Subject: [PATCH] Added and connected setpoint changes for demo,student,mpc
 controllers

---
 .../GUI_Qt/studentGUI/include/MainWindow.h    |  47 +-
 .../GUI_Qt/studentGUI/src/MainWindow.cpp      | 293 ++++++--
 .../GUI_Qt/studentGUI/src/MainWindow.ui       | 694 ++++++++++++++++--
 .../src/d_fall_pps/include/nodes/PPSClient.h  |   4 +-
 4 files changed, 911 insertions(+), 127 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
index 1f6f40b4..22eeb488 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/include/MainWindow.h
@@ -46,10 +46,10 @@
 
 
 // Types of controllers being used:
-#define SAFE_CONTROLLER    0
-#define DEMO_CONTROLLER  1
-#define STUDENT_CONTROLLER 2
-#define MPC_CONTROLLER     3
+#define SAFE_CONTROLLER    1
+#define DEMO_CONTROLLER    2
+#define STUDENT_CONTROLLER 3
+#define MPC_CONTROLLER     4
 
 
 // Commands for CrazyRadio
@@ -126,8 +126,10 @@ private slots:
     void on_motors_OFF_button_clicked();
 
     // # Setpoint
-    void on_set_setpoint_button_clicked();
-    void on_set_setpoint_button_2_clicked();
+    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();
@@ -167,7 +169,9 @@ private:
     CrazyflieContext m_context;
 
     Setpoint m_safe_setpoint;
-    Setpoint m_custom_setpoint;
+    Setpoint m_demo_setpoint;
+    Setpoint m_student_setpoint;
+    Setpoint m_mpc_setpoint;
 
     int m_battery_state;
 
@@ -181,8 +185,18 @@ private:
     ros::Publisher controllerSetpointPublisher;
     ros::Subscriber safeSetpointSubscriber;
 
-    ros::Publisher customSetpointPublisher;
-    ros::Subscriber customSetpointSubscriber;
+    // SUBSCRIBERS AND PUBLISHERS FOR THE SETPOINTS:
+    // > For the Demo Controller
+    ros::Publisher  demoSetpointPublisher;
+    ros::Subscriber demoSetpointSubscriber;
+    // > For the Student Controller
+    ros::Publisher  studentSetpointPublisher;
+    ros::Subscriber studentSetpointSubscriber;
+    // > For the MPC Controller
+    ros::Publisher  mpcSetpointPublisher;
+    ros::Subscriber mpcSetpointSubscriber;
+
+
 
     ros::Publisher PPSClientStudentCustomButtonPublisher;
 
@@ -209,8 +223,12 @@ private:
     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 customSetpointCallback(const Setpoint& newSetpoint);
+    void demoSetpointCallback(const Setpoint& newSetpoint);
+    void studentSetpointCallback(const Setpoint& newSetpoint);
+    void mpcSetpointCallback(const Setpoint& newSetpoint);
+
     void DBChangedCallback(const std_msgs::Int32& msg);
 
     // # Load Yaml when acting as the GUI for an Agent
@@ -230,13 +248,18 @@ private:
     void setCrazyRadioStatus(int radio_status);
     void loadCrazyflieContext();
     void coordinatesToLocal(CrazyflieData& cf);
-    void initialize_custom_setpoint();
+
+    void initialize_demo_setpoint();
+    void initialize_student_setpoint();
+    void initialize_mpc_setpoint();
 
 
     void disableGUI();
     void enableGUI();
     void highlightSafeControllerTab();
-    void highlightCustomControllerTab();
+    void highlightDemoControllerTab();
+    void highlightStudentControllerTab();
+    void highlightMpcControllerTab();
 
     bool setpointInsideBox(Setpoint setpoint, CrazyflieContext context);
     Setpoint correctSetpointBox(Setpoint setpoint, CrazyflieContext context);
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 cb03f56d..f93c6358 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
@@ -65,8 +65,17 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
 
     ros::NodeHandle nodeHandle(m_ros_namespace);
 
-    customSetpointPublisher = nodeHandle.advertise<Setpoint>("CustomControllerService/Setpoint", 1);
-    customSetpointSubscriber = nodeHandle.subscribe("CustomControllerService/Setpoint", 1, &MainWindow::customSetpointCallback, this);
+
+    // SUBSCRIBERS AND PUBLISHERS FOR THE SETPOINTS:
+    // > For the Demo Controller
+    demoSetpointPublisher  = nodeHandle.advertise<Setpoint>("DemoControllerService/Setpoint", 1);
+    demoSetpointSubscriber = nodeHandle.subscribe("DemoControllerService/Setpoint", 1, &MainWindow::demoSetpointCallback, this);
+    // > For the Student Controller
+    studentSetpointPublisher  = nodeHandle.advertise<Setpoint>("StudentControllerService/Setpoint", 1);
+    studentSetpointSubscriber = nodeHandle.subscribe("StudentControllerService/Setpoint", 1, &MainWindow::studentSetpointCallback, this);
+    // > For the MPC Controller
+    mpcSetpointPublisher  = nodeHandle.advertise<Setpoint>("MpcControllerService/Setpoint", 1);
+    mpcSetpointSubscriber = nodeHandle.subscribe("MpcControllerService/Setpoint", 1, &MainWindow::mpcSetpointCallback, this);
 
     // subscribers
     crazyRadioStatusSubscriber = nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &MainWindow::crazyRadioStatusCallback, this);
@@ -131,10 +140,10 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     }
 
     // Copy the default setpoint into respective text fields of the GUI
-    ui->current_setpoint_x->setText(QString::number(default_setpoint[0]));
-    ui->current_setpoint_y->setText(QString::number(default_setpoint[1]));
-    ui->current_setpoint_z->setText(QString::number(default_setpoint[2]));
-    ui->current_setpoint_yaw->setText(QString::number(default_setpoint[3]));
+    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();
@@ -145,7 +154,9 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) :
     ui->error_label->setStyleSheet("QLabel { color : red; }");
     ui->error_label->clear();
 
-    initialize_custom_setpoint();
+    initialize_demo_setpoint();
+    initialize_student_setpoint();
+    initialize_mpc_setpoint();
 }
 
 
@@ -175,11 +186,29 @@ 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);
 }
-void MainWindow::highlightCustomControllerTab()
+void MainWindow::highlightDemoControllerTab()
 {
     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);
+}
+void MainWindow::highlightStudentControllerTab()
+{
+    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);
+}
+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::green);
 }
 
 void MainWindow::DBChangedCallback(const std_msgs::Int32& msg)
@@ -196,7 +225,13 @@ void MainWindow::controllerUsedChangedCallback(const std_msgs::Int32& msg)
             highlightSafeControllerTab();
             break;
         case DEMO_CONTROLLER:
-            highlightCustomControllerTab();
+            highlightDemoControllerTab();
+            break;
+        case STUDENT_CONTROLLER:
+            highlightStudentControllerTab();
+            break;
+        case MPC_CONTROLLER:
+            highlightMpcControllerTab();
             break;
         default:
             break;
@@ -207,20 +242,40 @@ 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->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
+    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::customSetpointCallback(const Setpoint& newSetpoint)
+void MainWindow::mpcSetpointCallback(const Setpoint& newSetpoint)
 {
-    m_custom_setpoint = newSetpoint;
+    m_mpc_setpoint = newSetpoint;
     // here we get the new setpoint, need to update it in GUI
-    ui->current_setpoint_x_2->setText(QString::number(newSetpoint.x, 'f', 3));
-    ui->current_setpoint_y_2->setText(QString::number(newSetpoint.y, 'f', 3));
-    ui->current_setpoint_z_2->setText(QString::number(newSetpoint.z, 'f', 3));
-    ui->current_setpoint_yaw_2->setText(QString::number(newSetpoint.yaw * RAD2DEG, 'f', 1));
+    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::flyingStateChangedCallback(const std_msgs::Int32& msg)
@@ -404,30 +459,30 @@ void MainWindow::updateNewViconData(const ptrToMessage& p_msg) //connected to ne
             coordinatesToLocal(local);
 
             // now we have the local coordinates, put them in the labels
-            ui->current_x->setText(QString::number(local.x, 'f', 3));
-            ui->current_y->setText(QString::number(local.y, 'f', 3));
-            ui->current_z->setText(QString::number(local.z, 'f', 3));
-            ui->current_yaw->setText(QString::number(local.yaw * RAD2DEG, 'f', 1));
-            ui->current_pitch->setText(QString::number(local.pitch * RAD2DEG, 'f', 1));
-            ui->current_roll->setText(QString::number(local.roll * RAD2DEG, 'f', 1));
-
-            ui->current_x_2->setText(QString::number(local.x, 'f', 3));
-            ui->current_y_2->setText(QString::number(local.y, 'f', 3));
-            ui->current_z_2->setText(QString::number(local.z, 'f', 3));
-            ui->current_yaw_2->setText(QString::number(local.yaw * RAD2DEG, 'f', 1));
-            ui->current_pitch_2->setText(QString::number(local.pitch * RAD2DEG, 'f', 1));
-            ui->current_roll_2->setText(QString::number(local.roll * RAD2DEG, 'f', 1));
+            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));
 
             // also update diff
-            ui->diff_x->setText(QString::number(m_safe_setpoint.x - local.x, 'f', 3));
-            ui->diff_y->setText(QString::number(m_safe_setpoint.y - local.y, 'f', 3));
-            ui->diff_z->setText(QString::number(m_safe_setpoint.z - local.z, 'f', 3));
-            ui->diff_yaw->setText(QString::number((m_safe_setpoint.yaw - local.yaw) * RAD2DEG, 'f', 1));
-
-            ui->diff_x_2->setText(QString::number(m_custom_setpoint.x - local.x, 'f', 3));
-            ui->diff_y_2->setText(QString::number(m_custom_setpoint.y - local.y, 'f', 3));
-            ui->diff_z_2->setText(QString::number(m_custom_setpoint.z - local.z, 'f', 3));
-            ui->diff_yaw_2->setText(QString::number((m_custom_setpoint.yaw - local.yaw) * RAD2DEG, 'f', 1));
+            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));
         }
     }
 }
@@ -481,28 +536,28 @@ void MainWindow::on_motors_OFF_button_clicked()
 
 //    ----------------------------------------------------------------------------------
 // # Setpoint
-void MainWindow::on_set_setpoint_button_clicked()
+void MainWindow::on_set_setpoint_button_safe_clicked()
 {
     Setpoint msg_setpoint;
 
     // initialize setpoint to previous one
 
-    msg_setpoint.x = (ui->current_setpoint_x->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw->text()).toFloat();
+    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->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x->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->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y->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->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z->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->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw->text()).toFloat() * DEG2RAD;
+    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))
@@ -523,7 +578,29 @@ void MainWindow::on_set_setpoint_button_clicked()
     ROS_INFO_STREAM("Setpoint change clicked with:" << msg_setpoint.x << ", "<< msg_setpoint.y << ", "<< msg_setpoint.z << ", "<< msg_setpoint.yaw);
 }
 
-void MainWindow::initialize_custom_setpoint()
+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;
@@ -531,33 +608,77 @@ void MainWindow::initialize_custom_setpoint()
     msg_setpoint.z = 0.4;
     msg_setpoint.yaw = 0;
 
-    this->customSetpointPublisher.publish(msg_setpoint);
+    this->mpcSetpointPublisher.publish(msg_setpoint);
 }
 
-void MainWindow::on_set_setpoint_button_2_clicked()
+void MainWindow::on_set_setpoint_button_demo_clicked()
 {
     Setpoint msg_setpoint;
 
-    msg_setpoint.x = (ui->current_setpoint_x_2->text()).toFloat();
-    msg_setpoint.y = (ui->current_setpoint_y_2->text()).toFloat();
-    msg_setpoint.z = (ui->current_setpoint_z_2->text()).toFloat();
-    msg_setpoint.yaw = (ui->current_setpoint_yaw_2->text()).toFloat();
+    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_2->text().isEmpty())
-        msg_setpoint.x = (ui->new_setpoint_x_2->text()).toFloat();
-    if(!ui->new_setpoint_y_2->text().isEmpty())
-        msg_setpoint.y = (ui->new_setpoint_y_2->text()).toFloat();
-    if(!ui->new_setpoint_z_2->text().isEmpty())
-        msg_setpoint.z = (ui->new_setpoint_z_2->text()).toFloat();
-    if(!ui->new_setpoint_yaw_2->text().isEmpty())
-        msg_setpoint.yaw = (ui->new_setpoint_yaw_2->text()).toFloat() * DEG2RAD;
+    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->customSetpointPublisher.publish(msg_setpoint);
+    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);
+}
 
 
 //    ----------------------------------------------------------------------------------
@@ -711,7 +832,7 @@ void MainWindow::requestLoadControllerYaml_from_my_GUI_Callback(const std_msgs::
 
         case LOAD_YAML_DEMO_CONTROLLER_AGENT:
         case LOAD_YAML_DEMO_CONTROLLER_COORDINATOR:
-            // Set the "load custom yaml" button to be disabled
+            // 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
@@ -724,6 +845,36 @@ void MainWindow::requestLoadControllerYaml_from_my_GUI_Callback(const std_msgs::
 
             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;
+
         default:
             ROS_INFO("Unknown 'all controllers to load yaml' command, thus nothing will be disabled");
             break;
diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
index 0d579ba4..4df49805 100644
--- a/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
+++ b/pps_ws/src/d_fall_pps/GUI_Qt/studentGUI/src/MainWindow.ui
@@ -6,7 +6,7 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>1331</width>
+    <width>1333</width>
     <height>721</height>
    </rect>
   </property>
@@ -377,7 +377,7 @@
           <property name="tabsClosable">
            <bool>false</bool>
           </property>
-          <widget class="QWidget" name="tab_3">
+          <widget class="QWidget" name="tab_safe">
            <property name="font">
             <font>
              <pointsize>14</pointsize>
@@ -394,7 +394,7 @@
               </property>
               <layout class="QGridLayout" name="gridLayout_3">
                <item row="6" column="1">
-                <widget class="QLineEdit" name="current_roll">
+                <widget class="QLineEdit" name="current_roll_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -412,7 +412,7 @@
                 </widget>
                </item>
                <item row="2" column="1">
-                <widget class="QLineEdit" name="current_y">
+                <widget class="QLineEdit" name="current_y_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -430,7 +430,7 @@
                 </widget>
                </item>
                <item row="4" column="1">
-                <widget class="QLineEdit" name="current_yaw">
+                <widget class="QLineEdit" name="current_yaw_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -448,7 +448,7 @@
                 </widget>
                </item>
                <item row="3" column="1">
-                <widget class="QLineEdit" name="current_z">
+                <widget class="QLineEdit" name="current_z_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -538,7 +538,7 @@
                 </widget>
                </item>
                <item row="1" column="1">
-                <widget class="QLineEdit" name="current_x">
+                <widget class="QLineEdit" name="current_x_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -592,7 +592,7 @@
                 </widget>
                </item>
                <item row="5" column="1">
-                <widget class="QLineEdit" name="current_pitch">
+                <widget class="QLineEdit" name="current_pitch_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -631,7 +631,7 @@
                 </widget>
                </item>
                <item row="1" column="2">
-                <widget class="QLineEdit" name="diff_x">
+                <widget class="QLineEdit" name="diff_x_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -649,7 +649,7 @@
                 </widget>
                </item>
                <item row="2" column="2">
-                <widget class="QLineEdit" name="diff_y">
+                <widget class="QLineEdit" name="diff_y_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -667,7 +667,7 @@
                 </widget>
                </item>
                <item row="3" column="2">
-                <widget class="QLineEdit" name="diff_z">
+                <widget class="QLineEdit" name="diff_z_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -685,7 +685,7 @@
                 </widget>
                </item>
                <item row="4" column="2">
-                <widget class="QLineEdit" name="diff_yaw">
+                <widget class="QLineEdit" name="diff_yaw_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -733,7 +733,7 @@
               </property>
               <layout class="QGridLayout" name="gridLayout_4">
                <item row="2" column="2">
-                <widget class="QLineEdit" name="new_setpoint_y">
+                <widget class="QLineEdit" name="new_setpoint_y_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -748,7 +748,7 @@
                 </widget>
                </item>
                <item row="4" column="2">
-                <widget class="QLineEdit" name="new_setpoint_yaw">
+                <widget class="QLineEdit" name="new_setpoint_yaw_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -763,7 +763,7 @@
                 </widget>
                </item>
                <item row="1" column="2">
-                <widget class="QLineEdit" name="new_setpoint_x">
+                <widget class="QLineEdit" name="new_setpoint_x_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -778,7 +778,7 @@
                 </widget>
                </item>
                <item row="2" column="1">
-                <widget class="QLineEdit" name="current_setpoint_y">
+                <widget class="QLineEdit" name="current_setpoint_y_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -796,7 +796,7 @@
                 </widget>
                </item>
                <item row="1" column="1">
-                <widget class="QLineEdit" name="current_setpoint_x">
+                <widget class="QLineEdit" name="current_setpoint_x_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -871,7 +871,7 @@
                 </widget>
                </item>
                <item row="3" column="1">
-                <widget class="QLineEdit" name="current_setpoint_z">
+                <widget class="QLineEdit" name="current_setpoint_z_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -925,7 +925,7 @@
                 </widget>
                </item>
                <item row="4" column="1">
-                <widget class="QLineEdit" name="current_setpoint_yaw">
+                <widget class="QLineEdit" name="current_setpoint_yaw_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -943,7 +943,7 @@
                 </widget>
                </item>
                <item row="5" column="2">
-                <widget class="QPushButton" name="set_setpoint_button">
+                <widget class="QPushButton" name="set_setpoint_button_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -961,7 +961,7 @@
                 </widget>
                </item>
                <item row="3" column="2">
-                <widget class="QLineEdit" name="new_setpoint_z">
+                <widget class="QLineEdit" name="new_setpoint_z_safe">
                  <property name="sizePolicy">
                   <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                    <horstretch>0</horstretch>
@@ -1026,7 +1026,7 @@
             </item>
            </layout>
           </widget>
-          <widget class="QWidget" name="tab_4">
+          <widget class="QWidget" name="tab_demo">
            <attribute name="title">
             <string>  Demo  </string>
            </attribute>
@@ -1066,7 +1066,7 @@
                   </property>
                   <layout class="QGridLayout" name="gridLayout_7">
                    <item row="1" column="2">
-                    <widget class="QLineEdit" name="diff_x_2">
+                    <widget class="QLineEdit" name="diff_x_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1084,7 +1084,7 @@
                     </widget>
                    </item>
                    <item row="6" column="1">
-                    <widget class="QLineEdit" name="current_roll_2">
+                    <widget class="QLineEdit" name="current_roll_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1102,7 +1102,7 @@
                     </widget>
                    </item>
                    <item row="2" column="1">
-                    <widget class="QLineEdit" name="current_y_2">
+                    <widget class="QLineEdit" name="current_y_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1120,7 +1120,7 @@
                     </widget>
                    </item>
                    <item row="4" column="1">
-                    <widget class="QLineEdit" name="current_yaw_2">
+                    <widget class="QLineEdit" name="current_yaw_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1138,7 +1138,7 @@
                     </widget>
                    </item>
                    <item row="3" column="1">
-                    <widget class="QLineEdit" name="current_z_2">
+                    <widget class="QLineEdit" name="current_z_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1192,7 +1192,7 @@
                     </widget>
                    </item>
                    <item row="1" column="1">
-                    <widget class="QLineEdit" name="current_x_2">
+                    <widget class="QLineEdit" name="current_x_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1240,7 +1240,7 @@
                     </widget>
                    </item>
                    <item row="5" column="1">
-                    <widget class="QLineEdit" name="current_pitch_2">
+                    <widget class="QLineEdit" name="current_pitch_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1315,7 +1315,7 @@
                     </widget>
                    </item>
                    <item row="3" column="2">
-                    <widget class="QLineEdit" name="diff_z_2">
+                    <widget class="QLineEdit" name="diff_z_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1333,7 +1333,7 @@
                     </widget>
                    </item>
                    <item row="2" column="2">
-                    <widget class="QLineEdit" name="diff_y_2">
+                    <widget class="QLineEdit" name="diff_y_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1351,7 +1351,7 @@
                     </widget>
                    </item>
                    <item row="4" column="2">
-                    <widget class="QLineEdit" name="diff_yaw_2">
+                    <widget class="QLineEdit" name="diff_yaw_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1399,7 +1399,7 @@
                   </property>
                   <layout class="QGridLayout" name="gridLayout_8">
                    <item row="2" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_y_2">
+                    <widget class="QLineEdit" name="new_setpoint_y_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1414,7 +1414,7 @@
                     </widget>
                    </item>
                    <item row="4" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_yaw_2">
+                    <widget class="QLineEdit" name="new_setpoint_yaw_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1429,7 +1429,7 @@
                     </widget>
                    </item>
                    <item row="1" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_x_2">
+                    <widget class="QLineEdit" name="new_setpoint_x_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1444,7 +1444,7 @@
                     </widget>
                    </item>
                    <item row="2" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_y_2">
+                    <widget class="QLineEdit" name="current_setpoint_y_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1462,7 +1462,7 @@
                     </widget>
                    </item>
                    <item row="1" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_x_2">
+                    <widget class="QLineEdit" name="current_setpoint_x_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1573,7 +1573,7 @@
                     </widget>
                    </item>
                    <item row="3" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_z_2">
+                    <widget class="QLineEdit" name="current_setpoint_z_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1591,7 +1591,7 @@
                     </widget>
                    </item>
                    <item row="5" column="2">
-                    <widget class="QPushButton" name="set_setpoint_button_2">
+                    <widget class="QPushButton" name="set_setpoint_button_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1609,7 +1609,7 @@
                     </widget>
                    </item>
                    <item row="4" column="1">
-                    <widget class="QLineEdit" name="current_setpoint_yaw_2">
+                    <widget class="QLineEdit" name="current_setpoint_yaw_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1627,7 +1627,7 @@
                     </widget>
                    </item>
                    <item row="3" column="2">
-                    <widget class="QLineEdit" name="new_setpoint_z_2">
+                    <widget class="QLineEdit" name="new_setpoint_z_demo">
                      <property name="sizePolicy">
                       <sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
                        <horstretch>0</horstretch>
@@ -1768,6 +1768,616 @@
             </item>
            </layout>
           </widget>
+          <widget class="QWidget" name="tab_student">
+           <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="1" column="2">
+               <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="2">
+               <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>14</pointsize>
+                 </font>
+                </property>
+                <property name="text">
+                 <string>Set setpoint</string>
+                </property>
+               </widget>
+              </item>
+              <item row="1" column="1">
+               <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="0">
+               <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="0">
+               <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="11" column="0">
+               <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="9" column="0">
+               <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="0">
+               <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="2">
+               <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="2">
+               <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="1">
+               <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="1">
+               <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="1">
+               <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="1">
+               <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="2">
+               <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="2">
+               <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>
+             </layout>
+            </item>
+           </layout>
+          </widget>
+          <widget class="QWidget" name="tab_mpc">
+           <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>
         </item>
         <item>
@@ -2139,7 +2749,7 @@
     <rect>
      <x>0</x>
      <y>0</y>
-     <width>1331</width>
+     <width>1333</width>
      <height>25</height>
     </rect>
    </property>
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 d87085d5..f2f870cf 100644
--- a/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
+++ b/pps_ws/src/d_fall_pps/include/nodes/PPSClient.h
@@ -83,8 +83,8 @@
 #define CF_COMMAND_TYPE_ANGLE  8
 
 // Types of controllers being used:
-#define SAFE_CONTROLLER      0
-#define DEMO_CONTROLLER      1
+#define SAFE_CONTROLLER      1
+#define DEMO_CONTROLLER      2
 #define STUDENT_CONTROLLER   3
 #define MPC_CONTROLLER       4
 
-- 
GitLab