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