diff --git a/pps_ws/src/d_fall_pps/src/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/ParameterService.cpp index d94ca277a1f8549ee53f16ea41c6bb782257dcc3..0d5582aaad9ad3e428950318a2258551d2114725 100755 --- a/pps_ws/src/d_fall_pps/src/ParameterService.cpp +++ b/pps_ws/src/d_fall_pps/src/ParameterService.cpp @@ -288,7 +288,6 @@ int main(int argc, char* argv[]) // the "~" indcates that "self" is the node handle assigned to this variable. ros::NodeHandle nodeHandle("~"); - m_ros_namespace = ros::this_node::getNamespace(); // Get the value of the "type" parameter into a local string variable std::string type_string; @@ -327,6 +326,37 @@ int main(int argc, char* argv[]) controllerYamlReadyForFetchPublihser = nodeHandle.advertise<std_msgs::Int32>("controllerYamlReadyForFetch", 1); + // Construct the string to the namespace of this Paramater Service + // SUBSCRIBE TO THE APPROPRIATE "request" MESSAGES DEPENDING ON THE "my_type" + switch (my_type) + { + case TYPE_AGENT: + { + //m_ros_namespace = ros::this_node::getNamespace(); + m_ros_namespace = "/" + std::to_string(agentID_to_follow) + "/" + "ParameterService"; + ROS_INFO_STREAM("This Paramter Sercice will load .yaml file parameters into the 'base' namespace: " << m_ros_namespace); + break; + } + + // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM: + // > The master GUI + case TYPE_COORDINATOR: + { + //m_ros_namespace = ros::this_node::getNamespace(); + m_ros_namespace = "/" + "ParameterService"; + ROS_INFO_STREAM("This Paramter Sercice will load .yaml file parameters into the 'base' namespace: " << m_ros_namespace); + break; + } + + default: + { + ROS_ERROR("The 'my_type' type parameter was not recognised."); + break; + } + } + + + // Delare the subscribers as local variables here so that they persist for the life // time of this main() function. The varaibles will be assigned in the switch case below