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