diff --git a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
index b7f00978b299f293d7c531228ec8e05ae58d4f1e..e1871be33d7c2a2b9003d67a2d501d3ce84c4c2e 100644
--- a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
@@ -812,17 +812,8 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 	// Switch between fetching for the different controllers and from different locations
 	switch(controller_to_fetch_yaml)
 	{
-		case FETCH_YAML_CUSTOM_CONTROLLER_COORDINATOR:
-		{
-			// 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_parameter_service = ros::NodeHandle(namespace_to_coordinator_parameter_service);
-			// Call the function that fetches the parameters
-			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-			break;
-		}
 
+		// > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
 		case FETCH_YAML_CUSTOM_CONTROLLER_AGENT:
 		{
 			// Let the user know that this message was received
@@ -834,6 +825,19 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
 			break;
 		}
 
+		// > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+		case FETCH_YAML_CUSTOM_CONTROLLER_COORDINATOR:
+		{
+			// 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 = ros::NodeHandle(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service);
+			// Call the function that fetches the parameters
+			fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+			break;
+		}
+
 		default:
 		{
 			// Let the user know that the command was not relevant
diff --git a/pps_ws/src/d_fall_pps/src/PPSClient.cpp b/pps_ws/src/d_fall_pps/src/PPSClient.cpp
index f49e84f369dc0f6df045479b927bbe501d8caa66..6bfd449b908e1ec9aeeb2f93ac129e2b633c3e90 100755
--- a/pps_ws/src/d_fall_pps/src/PPSClient.cpp
+++ b/pps_ws/src/d_fall_pps/src/PPSClient.cpp
@@ -789,26 +789,30 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
     // Switch between fetching for the different controllers and from different locations
     switch(controller_to_fetch_yaml)
     {
-        case FETCH_YAML_SAFE_CONTROLLER_COORDINATOR:
+        
+        // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
+        case FETCH_YAML_SAFE_CONTROLLER_AGENT:
         {
             // Let the user know that this message was received
-            // > 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_parameter_service = ros::NodeHandle(namespace_to_coordinator_parameter_service);
+            ROS_INFO("The PPSClient received the message that YAML parameters were (re-)loaded for the Safe Controller. > Now fetching the parameter values from this machine.");
+            // 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
-            fetchYamlParametersForSafeController(nodeHandle_to_coordinator_parameter_service);
+            fetchYamlParametersForSafeController(nodeHandle_to_own_agent_parameter_service);
             break;
         }
 
-        case FETCH_YAML_SAFE_CONTROLLER_AGENT:
+        // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+        case FETCH_YAML_SAFE_CONTROLLER_COORDINATOR:
         {
             // Let the user know that this message was received
-            ROS_INFO("The PPSClient received the message that YAML parameters were (re-)loaded for the Safe Controller. > Now fetching the parameter values from this machine.");
-            // 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);
+            // > 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 = ros::NodeHandle(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service);
             // Call the function that fetches the parameters
-            fetchYamlParametersForSafeController(nodeHandle_to_own_agent_parameter_service);
+            fetchYamlParametersForSafeController(nodeHandle_to_coordinator_parameter_service);
             break;
         }
 
diff --git a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
index a9f60d67a8a65685046a05799315f78ce483e33b..4a4d63cbf7d222b8309dbd74b79db88e7df6be7f 100755
--- a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
@@ -383,17 +383,8 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
     // Switch between fetching for the different controllers and from different locations
     switch(controller_to_fetch_yaml)
     {
-        case FETCH_YAML_SAFE_CONTROLLER_COORDINATOR:
-        {
-            // 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_parameter_service = ros::NodeHandle(namespace_to_coordinator_parameter_service);
-            // Call the function that fetches the parameters
-            fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
-            break;
-        }
 
+        // > FOR FETCHING FROM THE AGENT'S OWN PARAMETER SERVICE
         case FETCH_YAML_SAFE_CONTROLLER_AGENT:
         {
             // Let the user know that this message was received
@@ -405,6 +396,19 @@ void yamlReadyForFetchCallback(const std_msgs::Int32& msg)
             break;
         }
 
+        // > FOR FETCHING FROM THE COORDINATOR'S PARAMETER SERVICE
+        case FETCH_YAML_SAFE_CONTROLLER_COORDINATOR:
+        {
+            // 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 = ros::NodeHandle(nodeHandle_to_coordinator,namespace_to_coordinator_parameter_service);
+            // Call the function that fetches the parameters
+            fetchYamlParameters(nodeHandle_to_coordinator_parameter_service);
+            break;
+        }
+
         default:
         {
             // Let the user know that the command was not relevant
@@ -630,7 +634,7 @@ int main(int argc, char* argv[]) {
 
 
     // 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);