diff --git a/catkin_ws/src/asclinic_pkg/launch/aruco_detector.launch b/catkin_ws/src/asclinic_pkg/launch/aruco_detector.launch
index 3b0b086efaba1822da6734e4fc092fcb5f81397a..bda7e27e8c17cb5220f52cfdce0ef69912507ffe 100644
--- a/catkin_ws/src/asclinic_pkg/launch/aruco_detector.launch
+++ b/catkin_ws/src/asclinic_pkg/launch/aruco_detector.launch
@@ -36,7 +36,7 @@
 			/>
 			<param
 				name   = "aruco_detector_save_image_path"
-				value  = "1"
+				value  = "/home/asc/saved_camera_images/"
 			/>
 			<param
 				name   = "aruco_detector_should_save_all_aruco_images"
diff --git a/catkin_ws/src/asclinic_pkg/launch/asclinic_system.launch b/catkin_ws/src/asclinic_pkg/launch/asclinic_system.launch
index c115c9976bf6969796959cef0c0b75968a64be8e..e7785c5af56595ad1e702c39b96169456f7537fe 100644
--- a/catkin_ws/src/asclinic_pkg/launch/asclinic_system.launch
+++ b/catkin_ws/src/asclinic_pkg/launch/asclinic_system.launch
@@ -67,7 +67,7 @@
 			<param name = "aruco_detector_desired_camera_frame_width" value = "1920" />
 			<param name = "aruco_detector_desired_camera_fps" value = "5" />
 			<param name = "aruco_detector_marker_size" value = "0.250" />
-			<param name = "aruco_detector_save_image_path" value = "1" />
+			<param name = "aruco_detector_save_image_path" value = "/home/asc/saved_camera_images/" />
 			<param name = "aruco_detector_should_save_all_aruco_images" value = "False" />
 			<param name = "aruco_detector_should_publish_camera_images" value = "True" />
 			<param name = "aruco_detector_should_show_camera_images" value = "False" />
diff --git a/catkin_ws/src/asclinic_pkg/launch/camera_capture.launch b/catkin_ws/src/asclinic_pkg/launch/camera_capture.launch
index 467c634aeb8073106b1b2d6a6e7d131f21766230..6a4a13f6fc2126803b3b9de285a21f4fd5f36ae7 100644
--- a/catkin_ws/src/asclinic_pkg/launch/camera_capture.launch
+++ b/catkin_ws/src/asclinic_pkg/launch/camera_capture.launch
@@ -16,7 +16,7 @@
 			/>
 			<param
 				name   = "camera_capture_usb_camera_device_number"
-				value  = "2"
+				value  = "0"
 			/>
 			<param
 				name   = "camera_capture_desired_camera_frame_height"
@@ -40,11 +40,11 @@
 			/>
 			<param
 				name   = "camera_capture_save_image_path"
-				value  = "1"
+				value  = "/home/asc/saved_camera_images/"
 			/>
 			<param
 				name   = "camera_capture_should_save_all_chessboard_images"
-				value  = "False"
+				value  = "True"
 			/>
 			<param
 				name   = "camera_capture_should_publish_camera_images"
diff --git a/catkin_ws/src/asclinic_pkg/src/nodes/aruco_detector.py b/catkin_ws/src/asclinic_pkg/src/nodes/aruco_detector.py
index 2be57dc87951eac1d53bb36fa3a2794954d20feb..e8c06840f25925e91cef1fdc486ab177c52f3cde 100755
--- a/catkin_ws/src/asclinic_pkg/src/nodes/aruco_detector.py
+++ b/catkin_ws/src/asclinic_pkg/src/nodes/aruco_detector.py
@@ -349,6 +349,11 @@ class ArucoDetector:
         # Initialize a sequence number for each camera frame that is read
         self.camera_frame_sequence_number = 0
 
+        # Display command line command for publishing a
+        # request to save a camera image
+        if (self.aruco_detector_verbosity >= 1):
+            rospy.loginfo("[ARUCO DETECTOR] publish request from command line to save a single camera image using: rostopic pub --once " + node_namespace + "request_save_image std_msgs/UInt32 1")
+
         # Display the status
         if (self.aruco_detector_verbosity >= 1):
             rospy.loginfo("[ARUCO DETECTOR] Node initialisation complete")
diff --git a/catkin_ws/src/asclinic_pkg/src/nodes/camera_capture.py b/catkin_ws/src/asclinic_pkg/src/nodes/camera_capture.py
index c8344c3c8016a9c59e2e2147f20afb03fcd035c0..152d8e5a1e88f5304cf15f4fb786e73da74e041f 100755
--- a/catkin_ws/src/asclinic_pkg/src/nodes/camera_capture.py
+++ b/catkin_ws/src/asclinic_pkg/src/nodes/camera_capture.py
@@ -294,6 +294,11 @@ class CameraCapture:
             self.camera_frame_height = dimensions[0]
             self.camera_frame_width  = dimensions[1]
 
+        # Display command line command for publishing a
+        # request to save a camera image
+        if (self.camera_capture_verbosity >= 1):
+            rospy.loginfo("[CAMERA CAPTURE] publish request from command line to save a single camera image using: rostopic pub --once " + node_namespace + "request_save_image std_msgs/UInt32 1")
+
         # Display the status
         if (self.camera_capture_verbosity >= 1):
             rospy.loginfo("[CAMERA CAPTURE] Node initialisation complete")
@@ -335,7 +340,7 @@ class CameraCapture:
                 #   > The second argument is the grid size of internal
                 #     corner points that the function should search for
                 #   > This function can be quite slow when a chessboard is not visible in the image
-                internal_corner_grid_size = (self.self.chessboard_size_height,self.self.chessboard_size_width)
+                internal_corner_grid_size = (self.chessboard_size_height,self.chessboard_size_width)
                 chessboard_found, chessboard_corners = cv2.findChessboardCorners(current_frame_as_gray, internal_corner_grid_size, flags=find_flags)
                 # If found, then set the save image flag to true
                 if (chessboard_found == True):