diff --git a/pps_ws/src/d_fall_pps/src/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/ParameterService.cpp index c59e9c5e2f91a9a0e5644eac66d9fa5ecb67ff51..4a70d98cf7ecb4c6ffaa13f1bfcfc8c92c6369f5 100755 --- a/pps_ws/src/d_fall_pps/src/ParameterService.cpp +++ b/pps_ws/src/d_fall_pps/src/ParameterService.cpp @@ -333,7 +333,7 @@ int main(int argc, char* argv[]) case TYPE_AGENT: { //m_ros_namespace = ros::this_node::getNamespace(); - m_ros_namespace = "/" + std::to_string(my_agentID) + "/" + "ParameterService"; + m_ros_namespace = "/" + std::to_string(my_agentID) + '/' + "ParameterService"; ROS_INFO_STREAM("This Paramter Sercice will load .yaml file parameters into the 'base' namespace: " << m_ros_namespace); break; } @@ -343,7 +343,7 @@ int main(int argc, char* argv[]) case TYPE_COORDINATOR: { //m_ros_namespace = ros::this_node::getNamespace(); - m_ros_namespace = "/" + "ParameterService"; + m_ros_namespace = '/' + "ParameterService"; ROS_INFO_STREAM("This Paramter Sercice will load .yaml file parameters into the 'base' namespace: " << m_ros_namespace); break; } diff --git a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp index 24c898c1918a010184cf4ef1eefd77b8a5fd3a66..b8482f9a25fe9f3a0f107d593b38221a7b8201f7 100755 --- a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp +++ b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp @@ -584,7 +584,7 @@ int main(int argc, char* argv[]) { // 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 - namespace_to_own_agent_parameter_service = "ParameterService"; + namespace_to_own_agent_parameter_service = m_namespace + "/ParameterService"; // 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); @@ -611,6 +611,11 @@ int main(int argc, char* argv[]) { // "yamlReadyForFetchCallback" class function. ros::Subscriber controllerYamlReadyForFetchSubscriber_to_coordinator = nodeHandle_to_coordinator_parameter_service.subscribe("controllerYamlReadyForFetch", 1, yamlReadyForFetchCallback); + // 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); + // Call the class function that loads the parameters for this class. fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);