From 84707538133a9f8dad39d7cbdd00cf58873705b9 Mon Sep 17 00:00:00 2001
From: beuchatp <beuchatp@control.ee.ethz.ch>
Date: Tue, 5 Dec 2017 07:12:12 +0100
Subject: [PATCH] Debugging namespace to get proper Parameter Service
 connections

---
 .../src/CustomControllerService.cpp           | 33 ++++++++++++++-----
 pps_ws/src/d_fall_pps/src/PPSClient.cpp       | 29 +++++++++++-----
 .../d_fall_pps/src/SafeControllerService.cpp  | 33 ++++++++++++++-----
 3 files changed, 68 insertions(+), 27 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
index 2a2230b3..8625ffcb 100644
--- a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
@@ -1135,6 +1135,9 @@ int main(int argc, char* argv[]) {
 	// *********************************************************************************
 	// EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
 
+
+	// EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+
 	// Set the class variable "namespace_to_own_agent_parameter_service" to be a the
     // namespace string for the parameter service that is running on the machine of this
     // agent
@@ -1143,14 +1146,6 @@ int main(int argc, char* argv[]) {
     // Create a node handle to the parameter service running on this agent's machine
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    //std::string m_ros_namespace = ros::getNamespace();
-    namespace_to_coordinator_parameter_service = "/ParameterService";
-
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
@@ -1158,18 +1153,38 @@ int main(int argc, char* argv[]) {
     // "yamlReadyForFetchCallback" class function.
     ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
+
+    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
+
+    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
+    // for the parameter service that is running on the coordinate machine
+    //std::string m_ros_namespace = ros::getNamespace();
+    namespace_to_coordinator_parameter_service = "ParameterService";
+
+    // Create a node handle to the parameter service running on the coordinator machine
+    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
+    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+    
+
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
     // received on this topic and the message is passed as an input argument to the
     // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+
+
+    // PRINT OUT SOME INFORMATION
 
     // Let the user know what namespaces are being used for linking to the parameter service
     ROS_INFO_STREAM("The namespace string for accessing the Paramter Services are:");
     ROS_INFO_STREAM("namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
     ROS_INFO_STREAM("namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
 
+
+    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
+
 	// Call the class function that loads the parameters for this class.
     fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
diff --git a/pps_ws/src/d_fall_pps/src/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/PPSClient.cpp
index 20bdaa95..f49e84f3 100755
--- a/pps_ws/src/d_fall_pps/src/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/PPSClient.cpp
@@ -1003,6 +1003,9 @@ int main(int argc, char* argv[])
     // Get the namespace of this "SafeControllerService" node
     std::string m_namespace = ros::this_node::getNamespace();
 
+
+    // EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+
     // Set the class variable "namespace_to_own_agent_parameter_service" to be a the
     // namespace string for the parameter service that is running on the machine of this
     // agent
@@ -1011,14 +1014,6 @@ int main(int argc, char* argv[])
     // Create a node handle to the parameter service running on this agent's machine
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    //std::string m_ros_namespace = ros::getNamespace();
-    namespace_to_coordinator_parameter_service = "/ParameterService";
-
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
@@ -1026,12 +1021,28 @@ int main(int argc, char* argv[])
     // "yamlReadyForFetchCallback" class function.
     ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
+
+    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
+
+    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
+    // for the parameter service that is running on the coordinate machine
+    //std::string m_ros_namespace = ros::getNamespace();
+    namespace_to_coordinator_parameter_service = "ParameterService";
+
+    // Create a node handle to the parameter service running on the coordinator machine
+    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
+    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
     // received on this topic and the message is passed as an input argument to the
     // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+
+
+    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
 
     // Call the class function that loads the parameters for this class.
     fetchYamlParametersForSafeController(nodeHandle_to_own_agent_parameter_service);
diff --git a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
index 68526aa2..a9f60d67 100755
--- a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
@@ -578,6 +578,9 @@ int main(int argc, char* argv[]) {
     // *********************************************************************************
     // EVERYTHING THAT RELATES TO FETCHING PARAMETERS FROM A YAML FILE
 
+
+    // EVERYTHING FOR THE CONNECTION TO THIS AGENT's OWN PARAMETER SERVICE:
+
     // Get the namespace of this "SafeControllerService" node
     std::string m_namespace = ros::this_node::getNamespace();
 
@@ -589,14 +592,6 @@ int main(int argc, char* argv[]) {
     // Create a node handle to the parameter service running on this agent's machine
     ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 
-    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
-    // for the parameter service that is running on the coordinate machine
-    //std::string m_ros_namespace = ros::master::getNamespace();
-    namespace_to_coordinator_parameter_service = "/ParameterService";
-
-    // Create a node handle to the parameter service running on the coordinator machine
-    ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
-
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
@@ -604,18 +599,38 @@ int main(int argc, char* argv[]) {
     // "yamlReadyForFetchCallback" class function.
     ros::Subscriber controllerYamlReadyForFetchSubscriber_to_agent = nodeHandle_to_own_agent_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
 
+
+    // EVERYTHING FOR THE CONNECTION THE COORDINATOR'S PARAMETER SERVICE:
+
+    // Set the class variable "nodeHandle_to_coordinator_parameter_service" to be a node handle
+    // for the parameter service that is running on the coordinate machine
+    //std::string m_ros_namespace = ros::master::getNamespace();
+    namespace_to_coordinator_parameter_service = "ParameterService";
+
+    // Create a node handle to the parameter service running on the coordinator machine
+    ros::NodeHandle nodeHandle_to_coordinator = ros::NodeHandle();
+    //ros::NodeHandle nodeHandle_to_coordinator_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+    
+
     // Instantiate the local variable "controllerYamlReadyForFetchSubscriber" to be a
     // "ros::Subscriber" type variable that subscribes to the "controllerYamlReadyForFetch" topic
     // and calls the class function "yamlReadyForFetchCallback" each time a message is
     // received on this topic and the message is passed as an input argument to the
     // "yamlReadyForFetchCallback" class function.
-    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator.subscribe("/ParameterService/controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+    //ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback);
+
+
+    // PRINT OUT SOME INFORMATION
 
     // Let the user know what namespaces are being used for linking to the parameter service
     ROS_INFO_STREAM("The namespace string for accessing the Paramter Services are:");
     ROS_INFO_STREAM("namespace_to_own_agent_parameter_service    =  " << namespace_to_own_agent_parameter_service);
     ROS_INFO_STREAM("namespace_to_coordinator_parameter_service  =  " << namespace_to_coordinator_parameter_service);
 
+
+    // FINALLY, FETCH ANY PARAMETERS REQUIRED FROM THESE "PARAMETER SERVICES"
+    
     // Call the class function that loads the parameters for this class.
     fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 
-- 
GitLab