diff --git a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
index b4599096b0cc06ca715090d24e171c8718f5577c..6791781e4514ab739ca2d67ea4deb09a35a31c2b 100644
--- a/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/CustomControllerService.cpp
@@ -826,9 +826,9 @@ 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.\r> 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 machine.");
 			// Create a node handle to the parameter service running on this agent's machine
-			ros::NodeHandle nodeHandle_to_own_agent_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+			ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 			// Call the function that fetches the parameters
 			fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
 			break;
@@ -1141,7 +1141,7 @@ int main(int argc, char* argv[]) {
     namespace_to_own_agent_parameter_service = "ParameterService";
 
     // Create a node handle to the parameter service running on this agent's machine
-    ros::NodeHandle nodeHandle_to_own_agent_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+    ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
 
     // 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
diff --git a/pps_ws/src/d_fall_pps/src/ParameterService.cpp b/pps_ws/src/d_fall_pps/src/ParameterService.cpp
index 33a2b0fc8d894080379d04fd1c5c1e44d4dd2388..d94ca277a1f8549ee53f16ea41c6bb782257dcc3 100755
--- a/pps_ws/src/d_fall_pps/src/ParameterService.cpp
+++ b/pps_ws/src/d_fall_pps/src/ParameterService.cpp
@@ -226,7 +226,7 @@ void requestLoadControllerYamlCallback(const std_msgs::Int32& msg)
         system(cmd.c_str());
 
         // Pause breifly to ensure that the yaml file is fully loaded
-        ros::Duration(0.2).sleep();
+        ros::Duration(0.5).sleep();
 
         // Instantiate a local varaible to confirm that something was actually loaded from
         // a YAML file
diff --git a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
index ff24c9eb603166e7cf69590e07ab3d5ff4e1d8ec..24c898c1918a010184cf4ef1eefd77b8a5fd3a66 100755
--- a/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
+++ b/pps_ws/src/d_fall_pps/src/SafeControllerService.cpp
@@ -399,7 +399,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 this machine.");
             // Create a node handle to the parameter service running on this agent's machine
-            ros::NodeHandle nodeHandle_to_own_agent_parameter_service = ros::NodeHandle(namespace_to_own_agent_parameter_service);
+            ros::NodeHandle nodeHandle_to_own_agent_parameter_service(namespace_to_own_agent_parameter_service);
             // Call the function that fetches the parameters
             fetchYamlParameters(nodeHandle_to_own_agent_parameter_service);
             break;
@@ -446,6 +446,9 @@ void fetchYamlParameters(ros::NodeHandle& nodeHandle)
     // > The defailt setpoint of the controller
     getParameterFloatVector(nodeHandle_for_safeController, "defaultSetpoint", defaultSetpoint, 4);
 
+    // DEBUGGING: Print out one of the parameters that was loaded
+    ROS_INFO_STREAM("DEBUGGING: the fetched SafeController/mass = " << cf_mass);
+
     // Call the function that computes details an values that are needed from these
     // parameters loaded above
     processFetchedParameters();