diff --git a/pps_ws/src/d_fall_pps/param/SafeController.yaml b/pps_ws/src/d_fall_pps/param/SafeController.yaml index 60efb4480984c85a640d235799b61a0eaa7da4a5..d0e014827cd6bbdb656087b34918920fbd1afe14 100644 --- a/pps_ws/src/d_fall_pps/param/SafeController.yaml +++ b/pps_ws/src/d_fall_pps/param/SafeController.yaml @@ -1,5 +1,5 @@ #equlibrium offset -mass : 29 +mass : 30 #quadratic motor regression equation (a0, a1, a2) motorPoly: [5.484560e-4, 1.032633e-6, 2.130295e-11] diff --git a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp index 6791781e4514ab739ca2d67ea4deb09a35a31c2b..d13baf1baa3b4d11d884e16694b98ed0d7faef32 100644 --- a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp +++ b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp @@ -1138,7 +1138,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); @@ -1165,6 +1165,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);