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