diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp index f11199064a4aeded20288a01b2a1ff45722a043f..441e11d96ade9662d9fd85da124694a3ab6f076b 100755 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/CrazyFlyGUI/src/mainguiwindow.cpp @@ -1110,7 +1110,7 @@ void MainGUIWindow::on_all_motors_off_button_clicked() { dfall_pkg::IntWithHeader msg; msg.data = CMD_CRAZYFLY_MOTORS_OFF; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; //commandAllAgentsPublisher.publish(msg); emergencyStopPublisher.publish(msg); } diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp index b15b8e0b6f54457f9a8b0668edc97b54c35ca76c..0d8c8bfd7f3dfeb3a9a0059492e4bcfcd29e8614 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/connectstartstopbar.cpp @@ -709,7 +709,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg ) { case TYPE_AGENT: { - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; break; } case TYPE_COORDINATOR: @@ -717,7 +717,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg ) // Lock the mutex m_agentIDs_toCoordinate_mutex.lock(); // Add the "coordinate all" flag - msg.shouldCheckForID = !(m_shouldCoordinateAll); + msg.shouldCheckForAgentID = !(m_shouldCoordinateAll); // Add the agent IDs if necessary if (!m_shouldCoordinateAll) { @@ -733,7 +733,7 @@ void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg ) default: { - msg.shouldCheckForID = true; + msg.shouldCheckForAgentID = true; ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised."); break; } diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp index a31d6804bd8495da206614482b4dbfff4e80fb06..2492c22945f698e8ea06cdb96f728cdeb331d2b8 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/coordinatorrow.cpp @@ -762,7 +762,7 @@ void CoordinatorRow::on_rf_connect_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_RECONNECT; this->crazyRadioCommandPublisher.publish(msg); ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Connect button clicked"); @@ -773,7 +773,7 @@ void CoordinatorRow::on_rf_disconnect_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_DISCONNECT; this->crazyRadioCommandPublisher.publish(msg); ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disconnect button clicked"); @@ -784,7 +784,7 @@ void CoordinatorRow::on_enable_flying_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_CRAZYFLY_TAKE_OFF; this->flyingStateCommandPublisher.publish(msg); ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Enable flying button clicked"); @@ -795,7 +795,7 @@ void CoordinatorRow::on_disable_flying_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_CRAZYFLY_LAND; this->flyingStateCommandPublisher.publish(msg); ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Disable flying button clicked"); @@ -806,7 +806,7 @@ void CoordinatorRow::on_motors_off_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_CRAZYFLY_MOTORS_OFF; this->flyingStateCommandPublisher.publish(msg); ROS_INFO_STREAM("[COORDINATOR ROW agentID:" << m_agentID << " GUI] Motors-off button clicked"); diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp index 5b3de64b9dc52d3eabaf6f4dff123700fe935f69..00b09c8a1f2898d17cfe6f766ece6966efcd8a4e 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/enablecontrollerloadyamlbar.cpp @@ -269,7 +269,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader { case TYPE_AGENT: { - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; break; } case TYPE_COORDINATOR: @@ -277,7 +277,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader // Lock the mutex m_agentIDs_toCoordinate_mutex.lock(); // Add the "coordinate all" flag - msg.shouldCheckForID = !(m_shouldCoordinateAll); + msg.shouldCheckForAgentID = !(m_shouldCoordinateAll); // Add the agent IDs if necessary if (!m_shouldCoordinateAll) { @@ -293,7 +293,7 @@ void EnableControllerLoadYamlBar::fillIntMessageHeader( dfall_pkg::IntWithHeader default: { - msg.shouldCheckForID = true; + msg.shouldCheckForAgentID = true; ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised."); break; } @@ -313,7 +313,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith { case TYPE_AGENT: { - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; break; } case TYPE_COORDINATOR: @@ -321,7 +321,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith // Lock the mutex m_agentIDs_toCoordinate_mutex.lock(); // Add the "coordinate all" flag - msg.shouldCheckForID = !(m_shouldCoordinateAll); + msg.shouldCheckForAgentID = !(m_shouldCoordinateAll); // Add the agent IDs if necessary if (!m_shouldCoordinateAll) { @@ -337,7 +337,7 @@ void EnableControllerLoadYamlBar::fillStringMessageHeader( dfall_pkg::StringWith default: { - msg.shouldCheckForID = true; + msg.shouldCheckForAgentID = true; ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised."); break; } diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp index b96cbfa548fafb1152b4a733b6f3e39912a38ee0..2ca4c56207d3e6a85ff3616d7f1ee846f50bc6c6 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/mainwindow.cpp @@ -185,7 +185,7 @@ void MainWindow::on_action_LoadYAML_BatteryMonitor_triggered() // Specify the data yaml_filename_msg.data = "BatteryMonitor"; // Set for whom this applies to - yaml_filename_msg.shouldCheckForID = false; + yaml_filename_msg.shouldCheckForAgentID = false; // Send the message m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg); #endif @@ -203,7 +203,7 @@ void MainWindow::on_action_LoadYAML_ClientConfig_triggered() // Specify the data yaml_filename_msg.data = "ClientConfig"; // Set for whom this applies to - yaml_filename_msg.shouldCheckForID = false; + yaml_filename_msg.shouldCheckForAgentID = false; // Send the message m_requestLoadYamlFilenamePublisher.publish(yaml_filename_msg); #endif diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp index b0a339e6331d4f94e1af75228d55a17bbccb66bd..9990e51cb8858d86397e484c7470439cc9ff169f 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/topbanner.cpp @@ -262,7 +262,7 @@ void TopBanner::on_emergency_stop_button_clicked() { #ifdef CATKIN_MAKE dfall_pkg::IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_CRAZYFLY_MOTORS_OFF; this->emergencyStopPublisher.publish(msg); ROS_INFO("[TOP BANNER GUI] EMERGENCY STOP button clicked"); diff --git a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp index afcfb9702e6149eae92f2c0b3d7d07d928ef777d..b2b101c80ad956ea1e989cc51683859a74d9ccaa 100644 --- a/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp +++ b/dfall_ws/src/dfall_pkg/GUI_Qt/flyingAgentGUI/src/tuningcontrollertab.cpp @@ -537,7 +537,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m { case TYPE_AGENT: { - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; break; } case TYPE_COORDINATOR: @@ -545,7 +545,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m // Lock the mutex m_agentIDs_toCoordinate_mutex.lock(); // Add the "coordinate all" flag - msg.shouldCheckForID = !(m_shouldCoordinateAll); + msg.shouldCheckForAgentID = !(m_shouldCoordinateAll); // Add the agent IDs if necessary if (!m_shouldCoordinateAll) { @@ -561,7 +561,7 @@ void TuningControllerTab::fillFloatMessageHeader( dfall_pkg::FloatWithHeader & m default: { - msg.shouldCheckForID = true; + msg.shouldCheckForAgentID = true; ROS_ERROR("[TUNING CONTROLLER TAB GUI] The 'm_type' variable was not recognised."); break; } diff --git a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py index ddc1fdf457dafcb82b8851cd365e26529448d7d4..3345d60630b2e7832208a8a8eda1989d4c244cd7 100755 --- a/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py +++ b/dfall_ws/src/dfall_pkg/crazyradio/CrazyRadio.py @@ -170,7 +170,7 @@ class CrazyRadioClient: self._send_to_commander_motor(0, 0, 0, 0) # change state to motors OFF msg = IntWithHeader() - msg.shouldCheckForID = False + msg.shouldCheckForAgentID = False msg.data = CMD_CRAZYFLY_MOTORS_OFF self.FlyingAgentClient_command_pub.publish(msg) time.sleep(0.1) @@ -230,7 +230,7 @@ class CrazyRadioClient: self.change_status_to(CONNECTED) # change state to motors OFF msg = IntWithHeader() - msg.shouldCheckForID = False + msg.shouldCheckForAgentID = False msg.data = CMD_CRAZYFLY_MOTORS_OFF cf_client.FlyingAgentClient_command_pub.publish(msg) @@ -260,7 +260,7 @@ class CrazyRadioClient: # change state to motors OFF msg = IntWithHeader() - msg.shouldCheckForID = False + msg.shouldCheckForAgentID = False msg.data = CMD_CRAZYFLY_MOTORS_OFF self.FlyingAgentClient_command_pub.publish(msg) @@ -300,7 +300,7 @@ class CrazyRadioClient: command_is_relevant = False # Check the header details of the message for it relevance - if (msg.shouldCheckForID == False): + if (msg.shouldCheckForAgentID == False): command_is_relevant = True else: for this_ID in msg.agentIDs: @@ -435,7 +435,7 @@ if __name__ == '__main__': cf_client._send_to_commander_motor(0, 0, 0, 0) # change state to motors OFF msg = IntWithHeader() - msg.shouldCheckForID = False + msg.shouldCheckForAgentID = False msg.data = CMD_CRAZYFLY_MOTORS_OFF cf_client.FlyingAgentClient_command_pub.publish(msg) #wait for client to send its commands diff --git a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h index f61481cf6d4e05105c552cae6184564d028a052e..9bc7a6e8dc43a4cc13a206e38ab9c7eed3259075 100644 --- a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h +++ b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h @@ -129,4 +129,4 @@ void constructNamespaceForCoordinator( int coordID, std::string & coord_namespac void constructNamespaceForCoordinatorParameterService( int coordID, std::string & coord_param_service_namespace ); // Check the header of a message for whether it is relevant -bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs ); \ No newline at end of file +bool checkMessageHeader( int agentID , bool shouldCheckForAgentID , const std::vector<uint> & agentIDs ); \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg index cc51997eca3c17200b0fc87768a92944edc795bf..229050a8a26f64e22a91eb2a1bd87074e265ff97 100755 --- a/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg +++ b/dfall_ws/src/dfall_pkg/msg/FloatWithHeader.msg @@ -1,3 +1,3 @@ float32 data -bool shouldCheckForID +bool shouldCheckForAgentID uint32[] agentIDs \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg index 64cbfd8c32b1ac19c1ecdd00d52d269cfe2a1868..1eb4c40ca3c831ed1e18fddf6e09ce65a5937203 100755 --- a/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg +++ b/dfall_ws/src/dfall_pkg/msg/IntWithHeader.msg @@ -1,3 +1,3 @@ uint32 data -bool shouldCheckForID +bool shouldCheckForAgentID uint32[] agentIDs \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg b/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg index 8a93139a59f68aa70879ce2a43c25474c001eee2..3c03b7a25061d9e24135cee6da806ee438ef128e 100755 --- a/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg +++ b/dfall_ws/src/dfall_pkg/msg/StringWithHeader.msg @@ -1,3 +1,3 @@ string data -bool shouldCheckForID +bool shouldCheckForAgentID uint32[] agentIDs \ No newline at end of file diff --git a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp index d8d7af9c915b0c02de490223009edd0409ba1b49..9c7fdcaf370f61a7e09776b4ea9d51d6ccdd36a5 100644 --- a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp +++ b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp @@ -209,11 +209,11 @@ void constructNamespaceForCoordinatorParameterService( int coordID, std::string // Check the header of a message for whether it is relevant -bool checkMessageHeader( int agentID , bool shouldCheckForID , const std::vector<uint> & agentIDs ) +bool checkMessageHeader( int agentID , bool shouldCheckForAgentID , const std::vector<uint> & agentIDs ) { - // The messag is by default relevant if the "shouldCheckForID" + // The messag is by default relevant if the "shouldCheckForAgentID" // flag is false - if (!shouldCheckForID) + if (!shouldCheckForAgentID) { return true; } diff --git a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp index f83abf9ac6ba466c3560ad56a73bf3d3c1e9f2ff..f9ea5fbfc1988274dd3acdf54c666418e23ff8ca 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/BatteryMonitor.cpp @@ -310,7 +310,7 @@ void updateBatteryStateBasedOnLevel(int level) void isReadyBatteryMonitorYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp index 20a5397dd77a69fea7d8214e03fe248a7fbfac88..234299b9214c29d250c7dafcc14e3345ea7f1d51 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/DefaultControllerService.cpp @@ -675,7 +675,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived void isReadyDefaultControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -895,7 +895,7 @@ int main(int argc, char* argv[]) // Specify the Yaml filename as a string loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController"; // Set for whom this applies to - loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false; + loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false; // Wait until the serivce exists requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1)); // Make the service call diff --git a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp index ded124762e44a04c7a4a354291876f2efe4eb7bf..7988825d0e6b7b62c58a5b4f8ff217bb0ad575ee 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/DemoControllerService.cpp @@ -1456,7 +1456,7 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw) void isReadyDemoControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1849,7 +1849,7 @@ int main(int argc, char* argv[]) { // Specify the data yaml_filename_msg.data = "DemoController"; // Set for whom this applies to - yaml_filename_msg.shouldCheckForID = false; + yaml_filename_msg.shouldCheckForAgentID = false; // Sleep to make the publisher known to ROS (in seconds) //ros::Duration(1.0).sleep(); // Send the message diff --git a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp index 467973ab85cc03ed875b2afeaeb9af79f217f7ff..72859686ff7dcbb1ecc6b15b6ea707be7f743b93 100755 --- a/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/FlyingAgentClient.cpp @@ -417,7 +417,7 @@ void loadCrazyflieContext() { ROS_INFO("[FLYING AGENT CLIENT] CF is now different for this student. Disconnect and turn it off"); IntWithHeader msg; - msg.shouldCheckForID = false; + msg.shouldCheckForAgentID = false; msg.data = CMD_DISCONNECT; crazyRadioCommandPublisher.publish(msg); } @@ -438,7 +438,7 @@ void loadCrazyflieContext() { void commandCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -962,7 +962,7 @@ bool getCurrentFlyingStateServiceCallback(IntIntService::Request &request, IntIn void isReadySafeControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1065,7 +1065,7 @@ void fetchSafeControllerYamlParameters(ros::NodeHandle& nodeHandle) void isReadyClientConfigYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1261,7 +1261,7 @@ int main(int argc, char* argv[]) // // Specify the Yaml filename as a string // loadYamlFromFilenameCall.request.stringWithHeader.data = "DefaultController"; // // Set for whom this applies to - // loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false; + // loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false; // // Wait until the serivce exists // requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1)); // // Make the service call diff --git a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp index fe88d56e5fb576dddcacc8f8442724523de6e1bc..8be89f51122694ead98fbad0277679f17a1e1287 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/ParameterService.cpp @@ -138,9 +138,9 @@ void requestLoadYamlFilenameCallback(const StringWithHeader& yaml_filename_to_lo } } // Copy across the boolean field - yaml_ready_msg.shouldCheckForID = yaml_filename_to_load_with_header.shouldCheckForID; + yaml_ready_msg.shouldCheckForAgentID = yaml_filename_to_load_with_header.shouldCheckForAgentID; // Copy across the vector of IDs - if (yaml_filename_to_load_with_header.shouldCheckForID) + if (yaml_filename_to_load_with_header.shouldCheckForAgentID) { for ( int i_ID=0 ; i_ID<yaml_filename_to_load_with_header.agentIDs.size() ; i_ID++ ) { diff --git a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp index 209c4979b69e26934f05dde928973654452981bc..b581597e1b8c4bd7b23477774fbaefe1d6dc2129 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/PickerControllerService.cpp @@ -1090,7 +1090,7 @@ void publish_current_xyz_yaw(float x, float y, float z, float yaw) void isReadyPickerControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1344,7 +1344,7 @@ int main(int argc, char* argv[]) { // Specify the Yaml filename as a string loadYamlFromFilenameCall.request.stringWithHeader.data = "PickerController"; // Set for whom this applies to - loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false; + loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false; // Wait until the serivce exists requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1)); // Make the service call diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp index f7d7eb782558abf4d8dca1570c84b7ea1344ff35..2cb3043437a63fd048d741cb60df65a7799f7718 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp @@ -716,7 +716,7 @@ void customCommandReceivedCallback(const CustomButtonWithHeader& commandReceived void isReadyStudentControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -950,7 +950,7 @@ int main(int argc, char* argv[]) { // Specify the Yaml filename as a string loadYamlFromFilenameCall.request.stringWithHeader.data = "StudentController"; // Set for whom this applies to - loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false; + loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false; // Wait until the serivce exists requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1)); // Make the service call diff --git a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp index e20ab24b770b05be606c6ada874e8de780cc1339..3e2d5fd41d73668302858d8b9d00560d4ecd7ca9 100644 --- a/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp +++ b/dfall_ws/src/dfall_pkg/src/nodes/TuningControllerService.cpp @@ -1320,7 +1320,7 @@ void setNewSetpoint(float x, float y, float z, float yaw) void requestGainChangeCallback(const FloatWithHeader& newGain) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForID , newGain.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , newGain.shouldCheckForAgentID , newGain.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1360,7 +1360,7 @@ void requestGainChangeCallback(const FloatWithHeader& newGain) void isReadyTuningControllerYamlCallback(const IntWithHeader & msg) { // Check whether the message is relevant - bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForID , msg.agentIDs ); + bool isRevelant = checkMessageHeader( m_agentID , msg.shouldCheckForAgentID , msg.agentIDs ); // Continue if the message is relevant if (isRevelant) @@ -1690,7 +1690,7 @@ int main(int argc, char* argv[]) { // Specify the Yaml filename as a string loadYamlFromFilenameCall.request.stringWithHeader.data = "TuningController"; // Set for whom this applies to - loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForID = false; + loadYamlFromFilenameCall.request.stringWithHeader.shouldCheckForAgentID = false; // Wait until the serivce exists requestLoadYamlFilenameServiceClient.waitForExistence(ros::Duration(-1)); // Make the service call