diff --git a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp index 1dbde303757d2b95b3927d1809e8a898bfb9def3..d4480f4ba3fa6b5336c18a17271ff93ce321dde7 100644 --- a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp +++ b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp @@ -817,7 +817,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg) case FETCH_YAML_CUSTOM_CONTROLLER_AGENT: { // Let the user know that this message was received - ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this machine."); + ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from this agent."); // 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); // Call the function that fetches the parameters @@ -831,8 +831,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg) // Let the user know that this message was received ROS_INFO("The CustomControllerService received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator."); // 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(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service); + ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service); // Call the function that fetches the parameters fetchYamlParameters(nodeHandle_to_coordinator_parameter_service); break; @@ -1165,8 +1164,9 @@ int main(int argc, char* argv[]) { // 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"; + // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService") + // is very important because it specifies that the name is global + 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(); diff --git a/pps_ws/src/d_fall_pps/src/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/PPSClient.cpp index 72ea28231f09beb7a9fe5ab3107537d91c9a894c..993a2e1d1a51cf17b4ddbfcaefc97ca6dafcbe8e 100755 --- a/pps_ws/src/d_fall_pps/src/PPSClient.cpp +++ b/pps_ws/src/d_fall_pps/src/PPSClient.cpp @@ -809,8 +809,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg) // > and also from where the paramters are being fetched ROS_INFO("The PPSClient received the message that YAML parameters were (re-)loaded for the Safe Controller. > Now fetching the parameter values from the coordinator."); // 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(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service); + ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service); // Call the function that fetches the parameters fetchYamlParametersForSafeController(nodeHandle_to_coordinator_parameter_service); break; @@ -1030,8 +1029,9 @@ int main(int argc, char* argv[]) // 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"; + // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService") + // is very important because it specifies that the name is global + 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(); diff --git a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp index 9ead5c4800e8d7d2e3a94596529530003a55aa23..98a42079867b4981a54578e4deb1007a711e65ff 100755 --- a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp +++ b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp @@ -402,8 +402,7 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg) // Let the user know that this message was received ROS_INFO("The SafeControllerService received the message that YAML parameters were (re-)loaded. > Now fetching the parameter values from the coordinator."); // 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(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service); + ros::NodeHandle nodeHandle_to_coordinator_parameter_service(namespace_to_coordinator_parameter_service); // Call the function that fetches the parameters fetchYamlParameters(nodeHandle_to_coordinator_parameter_service); break; @@ -608,8 +607,9 @@ int main(int argc, char* argv[]) { // 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"; + // NOTE: the backslash here (i.e., "/") before the name of the node ("ParameterService") + // is very important because it specifies that the name is global + 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();