Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • authierj/dfall-system
1 result
Show changes
Showing
with 4218 additions and 302 deletions
// Copyright (C) 2017, ETH Zurich, D-ITET, Angel Romero
// Copyright (C) 2019, ETH Zurich, D-ITET, Paul Beuchat
//
// This file is part of D-FaLL-System.
//
......@@ -30,11 +30,16 @@
// ----------------------------------------------------------------------------------
#include "rosNodeThread.h"
#include "d_fall_pps/CMRead.h"
#include "d_fall_pps/CMUpdate.h"
#include "d_fall_pps/CMCommand.h"
#include "rosNodeThread_for_flyingAgentGUI.h"
// #include "dfall_pkg/CMRead.h"
// #include "dfall_pkg/CMUpdate.h"
// #include "dfall_pkg/CMCommand.h"
// using namespace dfall_pkg;
rosNodeThread::rosNodeThread(int argc, char** pArgv, const char * node_name, QObject* parent)
......@@ -63,7 +68,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 "FlyingAgentGUI" in this case
if (!ros::master::check())
{
......@@ -75,7 +82,7 @@ bool rosNodeThread::init()
ros::Time::init();
ros::NodeHandle nh("~");
m_vicon_subscriber = nh.subscribe("/ViconDataPublisher/ViconData", 100, &rosNodeThread::messageCallback, this);
//m_vicon_subscriber = nh.subscribe("/ViconDataPublisher/ViconData", 3, &rosNodeThread::messageCallback, this);
// clients for db services:
m_read_db_client = nh.serviceClient<CMRead>("/CentralManagerService/Read", false);
......@@ -86,10 +93,10 @@ bool rosNodeThread::init()
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::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::messageCallback(const ViconData& data) // When a message arrives to the topic, this callback is executed
// {
......
#include "safecontrollertab.h"
#include "ui_safecontrollertab.h"
SafeControllerTab::SafeControllerTab(QWidget *parent) :
QWidget(parent),
ui(new Ui::SafeControllerTab)
{
ui->setupUi(this);
}
SafeControllerTab::~SafeControllerTab()
{
delete ui;
}
// 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"
StudentControllerTab::StudentControllerTab(QWidget *parent) :
QWidget(parent),
ui(new Ui::StudentControllerTab)
{
ui->setupUi(this);
// Hide the two red frames that are used to indcated
// when pose data is NOT valid
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<dfall_pkg::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 PUBLISHER
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<dfall_pkg::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
dfall_pkg::GetSetpointService getSetpointCall;
getSetpointCall.request.data = 0;
getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.1));
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
}
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
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("[STUDENT CONTROLLER TAB GUI] button " << button_index << " clicked.");
}
#endif
void StudentControllerTab::on_custom_button_1_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(1,ui->lineEdit_custom_1);
#endif
}
void StudentControllerTab::on_custom_button_2_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(2,ui->lineEdit_custom_2);
#endif
}
void StudentControllerTab::on_custom_button_3_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(3,ui->lineEdit_custom_3);
#endif
}
void StudentControllerTab::on_custom_button_4_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(4,ui->lineEdit_custom_4);
#endif
}
void StudentControllerTab::on_custom_button_5_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(5,ui->lineEdit_custom_5);
#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 isValid)
{
if (isValid)
{
// 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));
// 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_deg = yaw * RAD2DEG - (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_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() )
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 that
// measurement is NOT valid
if ( !(ui->red_frame_position_left->isVisible()) )
ui->red_frame_position_left->setVisible(true);
if ( !(ui->red_frame_position_right->isVisible()) )
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 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 StudentControllerTab::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("[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_degrees << "]";
#endif
}
void StudentControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
{
ui->set_setpoint_button->animateClick();
}
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 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 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();
// Call the function to publish the setpoint
publishSetpoint(x,y,z,yaw);
}
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
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("[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())
{
increment_setpoint_by( (ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,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");
#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())
{
increment_setpoint_by( -(ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,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");
#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())
{
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");
#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())
{
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 y 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())
{
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 z 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 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 z 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 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::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 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_degrees)
{
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() + 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_degrees
);
}
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_degrees;
// 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 setpoint not possible because m_type is not recognised.");
#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<dfall_pkg::GetSetpointService>("StudentControllerService/GetCurrentSetpoint", false);
dfall_pkg::GetSetpointService getSetpointCall;
getSetpointCall.request.data = 0;
getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.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( 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("[STUDENT CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
break;
}
}
}
#endif
#ifdef CATKIN_MAKE
// Fill the header for a message
void StudentControllerTab::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("[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
// 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"
TemplateControllerTab::TemplateControllerTab(QWidget *parent) :
QWidget(parent),
ui(new Ui::TemplateControllerTab)
{
ui->setupUi(this);
// Hide the two red frames that are used to indcated
// when pose data is NOT valide
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(0.1));
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 isValid)
{
if (isValid)
{
// 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 that
// measurement is NOT valid
if ( !(ui->red_frame_position_left->isVisible()) )
ui->red_frame_position_left->setVisible(true);
if ( !(ui->red_frame_position_right->isVisible()) )
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(0.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
// 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 title displayed at the top of the Flying Agent GUI
//
// ----------------------------------------------------------------------------------
#include "topbanner.h"
#include "ui_topbanner.h"
#ifdef CATKIN_MAKE
#else
// Include the shared definitions
#include "include/Constants_for_Qt_compile.h"
#endif
TopBanner::TopBanner(QWidget *parent) :
QWidget(parent),
ui(new Ui::TopBanner)
{
ui->setupUi(this);
(":/images/rf_connected.png");
QPixmap pixmap(":/images/emergency_stop.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());
m_object_name_for_emitting_pose_data = "";
#ifdef CATKIN_MAKE
// Get the namespace of this node
std::string base_namespace = ros::this_node::getNamespace();
ROS_INFO_STREAM("[TOP BANNER GUI] 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("[TOP BANNER GUI] 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");
// > Publisher for the emergency stop button
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<dfall_pkg::CMQuery>("CentralManagerService/Query", false);
#endif
// FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
// 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)
{
// Set the label appropriate for a cooridnator
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();
}
}
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("[TOP BANNER GUI] Database Changed Callback called for agentID = " << m_agentID);
loadCrazyflieContext(m_ID,0);
}
#endif
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
}
// > For loading the "context" for this agent, i.e., the {agentID,cfID,flying zone} tuple
void TopBanner::loadCrazyflieContext(int ID_to_request_from_database , int emit_after_milliseconds)
{
QString qstr_crazyflie_name = "";
#ifdef CATKIN_MAKE
dfall_pkg::CMQuery contextCall;
contextCall.request.studentID = ID_to_request_from_database;
//ROS_INFO_STREAM("StudentID:" << m_agentID);
centralManagerDatabaseService.waitForExistence(ros::Duration(2.0));
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));
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
{
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)
{
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 Agent 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);
}
// ----------------------------------------------------------------------------------
// 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
dfall_pkg::IntWithHeader msg;
msg.shouldCheckForAgentID = false;
msg.data = CMD_CRAZYFLY_MOTORS_OFF;
this->emergencyStopPublisher.publish(msg);
ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked");
#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 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 Agent 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
// 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("[TOP BANNER 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("[TOP BANNER 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("[TOP BANNER GUI] Failed to get agentID");
}
else
{
// Inform the user about the type and ID
ROS_INFO_STREAM("[TOP BANNER 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("[TOP BANNER GUI] Failed to get coordID");
}
else
{
// Inform the user about the type and ID
ROS_INFO_STREAM("[TOP BANNER 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("[TOP BANNER GUI] The 'm_type' variable was not recognised.");
break;
}
}
// Return
return return_was_successful;
}
#endif
// 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"
TuningControllerTab::TuningControllerTab(QWidget *parent) :
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) );
ui->frame_A_left->setVisible(false);
ui->frame_A_right->setVisible(false);
ui->frame_B_left->setVisible(false);
ui->frame_B_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("[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<dfall_pkg::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<dfall_pkg::FloatWithHeader>("TuningControllerService/RequestGainChange", 1);
// CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
//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<dfall_pkg::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
// dfall_pkg::GetSetpointService getSetpointCall;
// getSetpointCall.request.data = 0;
// getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.1));
// 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()
{
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 isValid)
{
if (isValid)
{
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 that
// // measurement is NOT valid
// if ( !(ui->red_frame_position_left->isVisible()) )
// ui->red_frame_position_left->setVisible(true);
// if ( !(ui->red_frame_position_right->isVisible()) )
// 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 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', 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
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 * 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;
ui->frame_A_left->setVisible(true);
ui->frame_A_right->setVisible(true);
ui->frame_B_left->setVisible(false);
ui->frame_B_right->setVisible(false);
}
else if (setpoint_copy < 0.0)
{
new_setpoint = SETPOINT_X_PLUS;
ui->frame_A_left->setVisible(false);
ui->frame_A_right->setVisible(false);
ui->frame_B_left->setVisible(true);
ui->frame_B_right->setVisible(true);
}
else if (setpoint_copy > SETPOINT_X_PLUS)
{
new_setpoint = SETPOINT_X_PLUS;
ui->frame_A_left->setVisible(false);
ui->frame_A_right->setVisible(false);
ui->frame_B_left->setVisible(true);
ui->frame_B_right->setVisible(true);
}
else
{
new_setpoint = SETPOINT_X_MINUS;
ui->frame_A_left->setVisible(true);
ui->frame_A_right->setVisible(true);
ui->frame_B_left->setVisible(false);
ui->frame_B_right->setVisible(false);
}
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
dfall_pkg::FloatWithHeader msg;
// Fill the header of the message
fillFloatMessageHeader( 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<dfall_pkg::GetSetpointService>("TuningControllerService/GetCurrentSetpoint", false);
// dfall_pkg::GetSetpointService getSetpointCall;
// getSetpointCall.request.data = 0;
// getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.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->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( 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("[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( dfall_pkg::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
// 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 Tutorial Controller
//
// ----------------------------------------------------------------------------------
#include "tutorialcontrollertab.h"
#include "ui_tutorialcontrollertab.h"
TutorialControllerTab::TutorialControllerTab(QWidget *parent) :
QWidget(parent),
ui(new Ui::TutorialControllerTab)
{
ui->setupUi(this);
// Hide the two red frames that are used to indcated
// when pose data is NOT valid
ui->red_frame_position_left->setVisible(false);
ui->red_frame_position_right->setVisible(false);
// Hide the two green frames that are used to indcate when MPC optimization problem is successfully set up
ui->green_frame_setup_left->setVisible(false);
ui->green_frame_setup_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("[TUTORIAL 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("[TUTORIAL 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>("TutorialControllerService/RequestSetpointChange", 1);
// SUBSCRIBE TO SETPOINT CHANGES
// Only if this is an agent GUI
if (m_type == TYPE_AGENT)
{
setpointChangedSubscriber = nodeHandle_for_this_gui.subscribe("TutorialControllerService/SetpointChanged", 1, &TutorialControllerTab::setpointChangedCallback, this);
}
// SUBSCRIBE TO OPTIMIZATION SETUP STATUS CHANGES
// Only if this is an agent GUI
if (m_type == TYPE_AGENT)
{
optimizationSetupStatusChangedSubscriber = nodeHandle_for_this_gui.subscribe("TutorialControllerService/OptimizationSetupStatusChanged", 1, &TutorialControllerTab::optimizationSetupStatusChangedCallback, this);
}
// CREATE THE CUSTOM BUTTON PRESSED PUBLISHER
customButtonPublisher = nodeHandle_for_this_gui.advertise<dfall_pkg::CustomButtonWithHeader>("TutorialControllerService/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>("TutorialControllerService/GetCurrentSetpoint", false);
dfall_pkg::GetSetpointService getSetpointCall;
getSetpointCall.request.data = 0;
getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.1));
if(getCurrentSetpointServiceClient.call(getSetpointCall))
{
setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
}
else
{
// Inform the user
ROS_INFO("[TUTORIAL CONTROLLER GUI] Failed to get setpoint from controller using the \"GetCurrentSetpoint\" service");
}
}
#endif
}
TutorialControllerTab::~TutorialControllerTab()
{
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 TutorialControllerTab::publish_custom_button_command(int button_index)
{
// 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;
// Publish the button press
this->customButtonPublisher.publish(msg);
// Inform the user about the change
ROS_INFO_STREAM("[TUTORIAL CONTROLLER TAB GUI] button " << button_index << " clicked.");
}
#endif
void TutorialControllerTab::on_custom_button_1_clicked()
{
#ifdef CATKIN_MAKE
publish_custom_button_command(1);
#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 TutorialControllerTab::setMeasuredPose(float x , float y , float z , float roll , float pitch , float yaw , bool isValid)
{
if (isValid)
{
// 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));
// 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();
// 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));
// 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 that
// measurement is NOT valid
if ( !(ui->red_frame_position_left->isVisible()) )
ui->red_frame_position_left->setVisible(true);
if ( !(ui->red_frame_position_right->isVisible()) )
ui->red_frame_position_right->setVisible(true);
}
}
void TutorialControllerTab::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");
}
// ----------------------------------------------------------------------------------
// 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 TutorialControllerTab::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));
}
#endif
// *** OPTIMIZATION SETUP STATUS CHANGED CALLBACK
#ifdef CATKIN_MAKE
void TutorialControllerTab::optimizationSetupStatusChangedCallback(const dfall_pkg::SetpointWithHeader& newSetpoint)
{
// USING SETPOINT X TO COMMUNICATE OPTIMIZATION SUCCESSFUL FLAG
bool optimization_setup_successful = (newSetpoint.x == 1.0);
// COTNROL THE VISIBILITY OF THE STATUS INDICATORS
ui->green_frame_setup_left->setVisible(optimization_setup_successful);
ui->green_frame_setup_right->setVisible(optimization_setup_successful);
ui->red_frame_setup_left->setVisible(!optimization_setup_successful);
ui->red_frame_setup_right->setVisible(!optimization_setup_successful);
}
#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 TutorialControllerTab::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("[TUTORIAL 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) << "[TUTORIAL CONTROLLER GUI] would publish request for: [" << x << ", "<< y << ", "<< z << ", "<< yaw_degrees << "]";
#endif
}
void TutorialControllerTab::on_lineEdit_setpoint_new_x_returnPressed()
{
ui->set_setpoint_button->animateClick();
}
void TutorialControllerTab::on_lineEdit_setpoint_new_y_returnPressed()
{
ui->set_setpoint_button->animateClick();
}
void TutorialControllerTab::on_lineEdit_setpoint_new_z_returnPressed()
{
ui->set_setpoint_button->animateClick();
}
void TutorialControllerTab::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();
// Call the function to publish the setpoint
publishSetpoint(x,y,z,yaw);
}
void TutorialControllerTab::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("[TUTORIAL CONTROLLER GUI] Published request for setpoint change to the default");
#endif
}
void TutorialControllerTab::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())
{
increment_setpoint_by( (ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,0.0,0.0);
}
else
{
#ifdef CATKIN_MAKE
// Inform the user that nothing can be done
ROS_INFO_STREAM("[TUTORIAL CONTROLLER GUI] Increment x setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::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())
{
increment_setpoint_by( -(ui->lineEdit_setpoint_increment_x->text()).toFloat() ,0.0,0.0,0.0);
}
else
{
#ifdef CATKIN_MAKE
// Inform the user that nothing can be done
ROS_INFO_STREAM("[TUTORIAL CONTROLLER GUI] Increment x setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::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())
{
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("[TUTORIAL CONTROLLER GUI] Increment x setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::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())
{
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("[TUTORIAL CONTROLLER GUI] Increment y setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::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())
{
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("[TUTORIAL CONTROLLER GUI] Increment z setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::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 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("[TUTORIAL CONTROLLER GUI] Increment z setpoint clicked but field is empty");
#endif
}
}
void TutorialControllerTab::increment_setpoint_by(float x_inc, float y_inc, float z_inc, float yaw_inc_degrees)
{
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() + x_inc,
(ui->lineEdit_setpoint_current_y->text() ).toFloat() + y_inc,
(ui->lineEdit_setpoint_current_z->text() ).toFloat() + z_inc,
0.0
);
}
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 y
if(!ui->lineEdit_setpoint_new_y->text().isEmpty())
y = (ui->lineEdit_setpoint_new_y->text()).toFloat();
// > For z
if(!ui->lineEdit_setpoint_new_z->text().isEmpty())
z = (ui->lineEdit_setpoint_new_z->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_degrees;
// 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));
// 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("[TUTORIAL CONTROLLER GUI] Increment setpoint not possible because m_type is not recognised.");
#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 TutorialControllerTab::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>("TutorialControllerService/GetCurrentSetpoint", false);
dfall_pkg::GetSetpointService getSetpointCall;
getSetpointCall.request.data = 0;
getCurrentSetpointServiceClient.waitForExistence(ros::Duration(0.0));
if(getCurrentSetpointServiceClient.call(getSetpointCall))
{
setpointChangedCallback(getSetpointCall.response.setpointWithHeader);
}
else
{
// Inform the user
ROS_INFO("[TUTORIAL 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("TutorialControllerService/SetpointChanged", 1, &TutorialControllerTab::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");
}
#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 TutorialControllerTab::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("[TUTORIAL CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
break;
}
}
}
#endif
#ifdef CATKIN_MAKE
// Fill the header for a message
void TutorialControllerTab::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("[TUTORIAL 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 TutorialControllerTab::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("[TUTORIAL 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("[TUTORIAL 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("[TUTORIAL CONTROLLER TAB GUI] Failed to get agentID");
}
else
{
// Inform the user about the type and ID
ROS_INFO_STREAM("[TUTORIAL 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("[TUTORIAL CONTROLLER TAB GUI] Failed to get coordID");
}
else
{
// Inform the user about the type and ID
ROS_INFO_STREAM("[TUTORIAL 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("[TUTORIAL CONTROLLER TAB GUI] The 'm_type' variable was not recognised.");
break;
}
}
// Return
return return_was_successful;
}
#endif
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>1176</width>
<height>1180</height>
<width>1339</width>
<height>1619</height>
</rect>
</property>
<property name="windowTitle">
......@@ -30,28 +30,19 @@
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<item row="2" column="1">
<widget class="QPushButton" name="pushButton_fitAll">
<property name="text">
<string>Fit All</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QPushButton" name="removeTable">
<property name="text">
<string>Remove Table</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>14</pointsize>
</font>
</property>
<property name="title">
<string>Creation Modes</string>
</property>
......@@ -60,7 +51,7 @@
<widget class="QRadioButton" name="radioButton_table_mode">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -75,7 +66,7 @@
<widget class="QRadioButton" name="radioButton_crazyfly_zones_mode">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -90,7 +81,7 @@
<widget class="QRadioButton" name="radioButton_lock_mode">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -101,20 +92,123 @@
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="removeTable">
<property name="font">
<font>
<pointsize>14</pointsize>
</font>
</property>
<property name="text">
<string>Remove Table</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="pushButton_fitAll">
<property name="font">
<font>
<pointsize>14</pointsize>
</font>
</property>
<property name="text">
<string>Fit All</string>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_zmin">
<property name="text">
<string>zmin</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_zmin">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<family>Courier</family>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>-0.2</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QLabel" name="label_zmax">
<property name="text">
<string>zmax</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="lineEdit_zmax">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<family>Courier</family>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>1.8</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="1" column="1">
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<pointsize>14</pointsize>
</font>
</property>
<property name="title">
<string>What to show</string>
</property>
<layout class="QGridLayout" name="gridLayout_5">
<item row="4" column="0">
<item row="5" column="0">
<widget class="QCheckBox" name="checkBox_grid">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -125,11 +219,11 @@
</property>
</widget>
</item>
<item row="5" column="0">
<item row="6" column="0">
<widget class="QCheckBox" name="checkBox_table">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -140,11 +234,11 @@
</property>
</widget>
</item>
<item row="8" column="0">
<item row="9" column="0">
<widget class="QCheckBox" name="checkBox_vicon_crazyflies">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -159,7 +253,7 @@
<widget class="QCheckBox" name="checkBox_crazyfly_zones">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -174,7 +268,7 @@
<widget class="QCheckBox" name="checkBox_vicon_markers">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -185,20 +279,20 @@
</property>
</widget>
</item>
<item row="8" column="1">
<item row="10" column="0">
<widget class="QDoubleSpinBox" name="scaleSpinBox">
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>12</pointsize>
</font>
</property>
</widget>
</item>
<item row="2" column="1">
<item row="3" column="0">
<widget class="QCheckBox" name="checkBox_vicon_highlight_markers">
<property name="font">
<font>
<pointsize>6</pointsize>
<pointsize>12</pointsize>
</font>
</property>
<property name="text">
......@@ -227,10 +321,8 @@
</item>
</layout>
<zorder>graphicsView</zorder>
<zorder>removeTable</zorder>
<zorder>groupBox</zorder>
<zorder>groupBox_2</zorder>
<zorder>pushButton_fitAll</zorder>
</widget>
</item>
<item row="0" column="1">
......@@ -249,7 +341,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>
......@@ -268,50 +360,81 @@
<height>100</height>
</size>
</property>
<property name="font">
<font>
<pointsize>14</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>All motors OFF</string>
<string>Emergency Stop</string>
</property>
</widget>
</item>
<item>
<widget class="QTabWidget" name="tabWidget_2">
<property name="font">
<font>
<pointsize>14</pointsize>
</font>
</property>
<property name="currentIndex">
<number>1</number>
<number>0</number>
</property>
<widget class="QWidget" name="links_tab">
<attribute name="title">
<string>Links</string>
</attribute>
<layout class="QGridLayout" name="gridLayout">
<item row="6" column="1" colspan="6">
<widget class="QLabel" name="err_message_student_id">
<property name="font">
<font>
<pointsize>7</pointsize>
</font>
<item row="0" column="1">
<widget class="QPushButton" name="refresh_student_ids_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>TextLabel</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</widget>
</item>
<item row="15" column="1" colspan="6">
<widget class="QLabel" name="err_message_cf_zone">
<property name="font">
<font>
<pointsize>7</pointsize>
</font>
<property name="maximumSize">
<size>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
<string>Refresh IDs</string>
</property>
</widget>
</item>
<item row="10" column="1" colspan="6">
<widget class="QLabel" name="err_message_cf">
<item row="13" column="1">
<widget class="QLabel" name="err_message_radio_address">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>600</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>7</pointsize>
<pointsize>10</pointsize>
</font>
</property>
<property name="text">
......@@ -319,121 +442,51 @@
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="spinBox_student_ids">
<item row="22" column="1">
<widget class="QPushButton" name="load_from_DB_button">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimum">
<number>1</number>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximum">
<number>20</number>
<property name="maximumSize">
<size>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="value">
<number>1</number>
<property name="text">
<string>Load from DB</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QListWidget" name="list_discovered_student_ids">
<item row="12" column="1">
<widget class="QLineEdit" name="radioAddress_text">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Minimum">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item row="9" column="1">
<widget class="QComboBox" name="comboBoxCFs"/>
</item>
<item row="14" column="1">
<widget class="QComboBox" name="comboBoxCFZones"/>
</item>
<item row="4" column="1">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Choose Student ID:</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Choose CF to link:</string>
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Choose CF Zone to link:</string>
</property>
</widget>
</item>
<item row="9" column="6">
<widget class="QPushButton" name="refresh_cfs_button">
<property name="text">
<string>Refresh CFs</string>
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QPushButton" name="refresh_student_ids_button">
<property name="text">
<string>Refresh IDs</string>
</property>
</widget>
</item>
<item row="16" column="1" colspan="6">
<widget class="QTableWidget" name="table_links">
<property name="minimumSize">
<size>
<width>273</width>
<height>0</height>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
<property name="rowCount">
<number>0</number>
</property>
<property name="columnCount">
<number>0</number>
</property>
<attribute name="horizontalHeaderVisible">
<bool>false</bool>
</attribute>
</widget>
</item>
<item row="14" column="6">
<widget class="QPushButton" name="link_button">
<property name="text">
<string>Link!</string>
</property>
</widget>
</item>
<item row="18" column="6">
<widget class="QPushButton" name="unlink_button">
<property name="text">
<string>Unlink!</string>
</property>
</widget>
</item>
<item row="20" column="6">
<widget class="QPushButton" name="save_in_DB_button">
<property name="text">
<string>Save in DB</string>
<property name="maximumSize">
<size>
<width>600</width>
<height>30</height>
</size>
</property>
</widget>
</item>
<item row="11" column="6">
<widget class="QLineEdit" name="radioAddress_text">
<property name="readOnly">
<bool>true</bool>
</property>
......@@ -442,60 +495,61 @@
</property>
</widget>
</item>
<item row="19" column="6">
<widget class="QPushButton" name="load_from_DB_button">
<property name="text">
<string>Load from DB</string>
</property>
</widget>
</item>
<item row="11" column="1">
<widget class="QLabel" name="label">
<property name="text">
<string>Radio Address:</string>
</property>
</widget>
</item>
<item row="12" column="6">
<widget class="QLabel" name="err_message_radio_address">
<property name="font">
<font>
<pointsize>7</pointsize>
</font>
</property>
<property name="text">
<string>TextLabel</string>
<item row="5" column="1">
<widget class="QSpinBox" name="spinBox_student_ids">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Command all</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_2">
<item row="1" column="1">
<widget class="QPushButton" name="all_connect_button">
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>30</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Reconnect</string>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>20</number>
</property>
<property name="value">
<number>1</number>
</property>
</widget>
</item>
<item row="2" column="0" colspan="2">
<widget class="QLabel" name="all_flying_state_label">
<item row="2" column="1">
<widget class="QListWidget" name="list_discovered_student_ids">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>600</width>
<height>90</height>
</size>
</property>
</widget>
</item>
<item row="15" column="1">
<widget class="QComboBox" name="comboBoxCFZones">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
......@@ -504,22 +558,16 @@
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>40</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>FLYING STATE</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">
<item row="9" column="1">
<widget class="QComboBox" name="comboBoxCFs">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
......@@ -527,136 +575,204 @@
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Take off</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QPushButton" name="all_enable_safe_controller_button">
<item row="4" column="1">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>15</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>25</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Enable Safe</string>
<string>Choose Student ID:</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QPushButton" name="all_land_button">
<item row="7" column="1">
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>15</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>25</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Land</string>
<string>Choose CF to link:</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="all_disconnect_button">
<item row="14" column="1">
<widget class="QLabel" name="label_3">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>15</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>25</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Disconnect</string>
<string>Choose CF Zone to link:</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QPushButton" name="all_enable_custom_controller_button">
<item row="11" column="1">
<widget class="QLabel" name="label">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>15</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>25</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Enable Custom</string>
<string>Radio Address:</string>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QPushButton" name="all_load_safe_controller_yaml_own_agent_button">
<item row="6" column="1">
<widget class="QLabel" name="err_message_student_id">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="text">
<string>Load Safe YAML</string>
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QPushButton" name="all_load_custom_controller_yaml_own_agent_button">
<widget class="QPushButton" name="refresh_cfs_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Load Custom YAML</string>
<string>Refresh CFs</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="2">
<widget class="QLabel" name="all_radio_label">
<item row="23" column="1">
<widget class="QPushButton" name="save_in_DB_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
......@@ -665,23 +781,23 @@
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>40</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>CRAZYRADIO</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
<string>Save in DB</string>
</property>
</widget>
</item>
<item row="6" column="0" colspan="2">
<widget class="QLabel" name="all_yaml_label">
<item row="16" column="1">
<widget class="QPushButton" name="link_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
......@@ -690,96 +806,191 @@
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>40</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>LOAD YAML PARAMETERS</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
<string>Link!</string>
</property>
</widget>
</item>
<item row="10" column="0">
<widget class="QPushButton" name="all_load_safe_controller_yaml_coordinator_button">
<item row="19" column="1">
<widget class="QTableWidget" name="table_links">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>120</height>
</size>
</property>
<property name="text">
<string>Send Safe YAML</string>
<property name="wordWrap">
<bool>true</bool>
</property>
<property name="rowCount">
<number>0</number>
</property>
<property name="columnCount">
<number>0</number>
</property>
<attribute name="horizontalHeaderVisible">
<bool>false</bool>
</attribute>
</widget>
</item>
<item row="10" column="1">
<widget class="QPushButton" name="all_load_custom_controller_yaml_coordinator_button">
<item row="21" column="1">
<widget class="QPushButton" name="unlink_button">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>100</height>
<width>600</width>
<height>30</height>
</size>
</property>
<property name="text">
<string>Send Custom YAML</string>
<string>Unlink!</string>
</property>
</widget>
</item>
<item row="7" column="0" colspan="2">
<widget class="QLabel" name="all_yaml_agent_label">
<item row="17" column="1">
<widget class="QLabel" name="err_message_cf_zone">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
<width>600</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="text">
<string>&gt; From agenet's local file</string>
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="9" column="0" colspan="2">
<widget class="QLabel" name="all_yaml_coordinator_label">
<item row="10" column="1">
<widget class="QLabel" name="err_message_cf">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>30</height>
<height>10</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>30</height>
<width>600</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="text">
<string>&gt; From coordinator's file</string>
<string>TextLabel</string>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Mocap</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_2">
<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>
</widget>
</item>
</layout>
......@@ -829,8 +1040,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>1176</width>
<height>37</height>
<width>1339</width>
<height>47</height>
</rect>
</property>
</widget>
......