diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h index 5c239d184998b27daf54233c55b1b87adb754110..3df7edddfd6a8241c8000b0be7349aee8fbca0dc 100644 --- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h +++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/include/enablecontrollerloadyamlbar.h @@ -2,6 +2,7 @@ #define ENABLECONTROLLERLOADYAMLBAR_H #include <QWidget> +#include <QMutex> #ifdef CATKIN_MAKE #include <ros/ros.h> @@ -58,6 +59,11 @@ public: explicit EnableControllerLoadYamlBar(QWidget *parent = 0); ~EnableControllerLoadYamlBar(); + +public slots: + void setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll); + + private slots: // ENABLE CONTROLLER BUTTONS ON-CLICK CALLBACK @@ -86,6 +92,12 @@ private: // 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 // PUBLISHERS AND SUBSRIBERS // > For {take-off,land,motors-off} and controller selection 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 437aa7ccdd45f7cfedcd4fbc4e92f01fe6c007e1..1e842c83128cc839eae6c2acb0016535249b6fbc 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 @@ -639,7 +639,7 @@ void ConnectStartStopBar::fillIntMessageHeader( d_fall_pps::IntWithHeader & msg // Add the agent IDs if necessary if (!m_shouldCoordinateAll) { - for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.length() ; irow++ ) + for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ ) { msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] ); } 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 6e1f52d2143d2a0e66f3ee925192061f5a757e27..64bece6d7e12dc743cc2ccc683d9f15a6147a74b 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 @@ -61,6 +61,13 @@ void Coordinator::on_refresh_button_clicked() // Check the box if "coordinate all" is checked 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); diff --git a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp index 2822b7b69391d6e0331cf21d07cc8ba8db18b681..6eaaa3cf0b7346f4180d3983a565942b3097ac5c 100644 --- a/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp +++ b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp @@ -116,6 +116,51 @@ void EnableControllerLoadYamlBar::on_load_yaml_default_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 EnableControllerLoadYamlBar::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 // MM MM S G G H H E A A D D E R R @@ -139,8 +184,20 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( d_fall_pps::IntWithHeade } 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.size() ; 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/mainwindow.cpp b/pps_ws/src/d_fall_pps/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp index b744a9a40f39d3cbaa00afaf94fbdd93c0c240c7..65645bb8aa79b97d93bf104a25ba4d940b559b01 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 @@ -102,6 +102,11 @@ MainWindow::MainWindow(int argc, char **argv, QWidget *parent) : ui->customWidget_connectStartStopBar , &ConnectStartStopBar::setAgentIDsToCoordinate ); + QObject::connect( + ui->customWidget_coordinator , &Coordinator::agentIDsToCoordinateChanged , + ui->customWidget_enableControllerLoadYamlBar , &EnableControllerLoadYamlBar::setAgentIDsToCoordinate + ); + } MainWindow::~MainWindow()