diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/activate_controller_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/activate_controller_eval.py
new file mode 100644
index 0000000000000000000000000000000000000000..02bbf379ebb0eb8ed9d6a443728fd450eb011086
--- /dev/null
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/activate_controller_eval.py
@@ -0,0 +1,21 @@
+import rospy
+from controller_manager_msgs.srv import ListControllers
+
+def evaluate_controller_activation():
+    rospy.wait_for_service('/controller_manager/list_controllers')
+    # Create a service proxy for '/controller_manager/list_controllers'
+    list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)
+    # Retrieve the list of controllers
+    controllers = list_controllers().controller
+
+    # Filter the running controllers
+    running_controllers = [controller.name for controller in controllers if controller.state == 'running']
+    
+    # Check if exactly one controller is running
+    assert len(running_controllers) == 1, f"Expected 1 running controller, but found {len(running_controllers)}"
+    # Check if the running controller is 'position_joint_trajectory_controller'
+    assert running_controllers[0] == 'position_joint_trajectory_controller', \
+        f"Expected 'position_joint_trajectory_controller' to be running, but found {running_controllers[0]}"
+
+if __name__ == "__main__":
+    evaluate_controller_activation()
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/position_controller_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/position_controller_eval.py
index 2f2b23682a7cb8caebef813cf6daf63a01388eff..e42c5ab7e2ac9c34135506af090076bbb6457d3c 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/position_controller_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/position_controller_eval.py
@@ -1,12 +1,9 @@
 import rospy
-from sensor_msgs.msg import JointState
 import math
-import moveit_commander
 import sys
-
+from moveit_commander import roscpp_shutdown, roscpp_initialize, MoveGroupCommander
 # Target positions
-target_positions = [math.pi / 2
-, -math.pi / 4, 0.0, -math.pi * 3 / 4, 0.0, math.pi / 2, math.pi / 4]
+target_positions = [math.pi / 2, -math.pi / 4, 0.0, -math.pi * 3 / 4, 0.0, math.pi / 2, math.pi / 4]
 
 # Tolerance for position verification
 tolerance = 0.1
@@ -15,29 +12,25 @@ tolerance = 0.1
 rospy.init_node('position_controller_evaluation', anonymous=True)
 
 # Initialize MoveIt Commander
-moveit_commander.roscpp_initialize(sys.argv)
-group = moveit_commander.MoveGroupCommander("panda_arm")
+roscpp_initialize(sys.argv)
+group = MoveGroupCommander("panda_arm")
 
-# Wait until joint states are received
 rospy.sleep(5)
 
 # Get current joint states
 current_positions = group.get_current_joint_values()
 
-# Wait until joint states are received
 rospy.sleep(5)
 
 # Verify joint positions
-if 'current_positions' in globals() and len(current_positions) == len(target_positions):
-    for i in range(len(target_positions)):
-        if abs(current_positions[i] - target_positions[i]) > tolerance:
-            rospy.loginfo(f"Joint {i+1} is not in the target position.")
-            rospy.loginfo(current_positions)
-            break
-    else:
-        rospy.loginfo("All joints are in the target positions.")
+for i in range(len(target_positions)):
+    if abs(current_positions[i] - target_positions[i]) > tolerance:
+        rospy.loginfo(f"Joint {i+1} is not in the target position.")
+        rospy.loginfo(current_positions)
+        break
 else:
-    rospy.loginfo("Joint states not received or length mismatch.")
+    rospy.loginfo("All joints are in the correct positions.")
 
 # Shutdown the ROS node
-rospy.signal_shutdown("Evaluation completed")
\ No newline at end of file
+rospy.signal_shutdown("Evaluation completed")
+roscpp_shutdown()
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/stop_controller_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/stop_controller_eval.py
new file mode 100644
index 0000000000000000000000000000000000000000..2f85a28142ab4f615df0d5b271e6cf7f6f010334
--- /dev/null
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/stop_controller_eval.py
@@ -0,0 +1,19 @@
+import rospy
+from controller_manager_msgs.srv import ListControllers
+
+def evaluate_stop_controllers():
+    rospy.wait_for_service('/controller_manager/list_controllers')
+    try:
+        list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)
+        controllers = list_controllers().controller
+        active_controllers = [controller.name for controller in controllers if controller.state == 'running']
+        
+        if not active_controllers:
+            print("Evaluation passed: No active controllers.")
+        else:
+            print("Evaluation failed: There are still active controllers:", active_controllers)
+    except rospy.ServiceException as e:
+        rospy.logerr("Service call failed: %s" % e)
+
+if __name__ == "__main__":
+    evaluate_stop_controllers()
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/switch_controller_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/switch_controller_eval.py
deleted file mode 100644
index a11cfec9eda2041f6af3177844c2186342c4fa94..0000000000000000000000000000000000000000
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/controller/controller_task/switch_controller_eval.py
+++ /dev/null
@@ -1 +0,0 @@
-print("NO NEED TO EVALUATE THIS SCRIPT")
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py
index 09168be587fda6c0c95afd1c4c59d7cef8093d76..c937512e9c019989d76831bd28b842a99e6c116c 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_3_eval.py
@@ -4,8 +4,6 @@ import math
 import rospy
 from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
 
-rospy.loginfo("exercise_4_1_evaluation")
-
 roscpp_initialize(sys.argv)
 rospy.init_node('exercise_4_1_evaluation', anonymous=True)
 
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/activate_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/activate_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..0a25991049494157d2aec6631e9dd4703b43ed83
--- /dev/null
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/activate_controller.ipynb
@@ -0,0 +1,126 @@
+{
+ "cells": [
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "# Educational Plattform Panda Robot\n",
+    "Author: uninh, uqwfa, ultck"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "## Controller_Task\n",
+    "### Activate_Controller\n",
+    "\n",
+    "> In this task, you will learn ...\n",
+    ">\n",
+    "> - how to activate a controller\n",
+    "> - how to check if a controller is already loaded\n",
+    "> - how to load a controller if it is not already loaded\n",
+    "> - how to create a service proxy for loading a controller\n",
+    "> - how to handle service responses and ensure the controller is successfully loaded\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### DO NOT CHANGE #####\n",
+    "\n",
+    "import rospy\n",
+    "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, ListControllers\n",
+    "\n",
+    "##### DO NOT CHANGE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Task :\n",
+    "\n",
+    "Now we want to activate the position controller.\n",
+    "\n",
+    "#### Procedure:\n",
+    "\n",
+    "- First, use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
+    "- Then create a service proxy for this service and retrieve the list of loaded controllers.\n",
+    "\n",
+    "- Check if the `position_joint_trajectory_controller` is already loaded.\n",
+    "- If not, use the `wait_for_service` method to wait for the `/controller_manager/load_controller` service.\n",
+    "- Then create a service proxy for this service and load the controller.\n",
+    "\n",
+    "- Now use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+    "- Then create a service proxy for this service.\n",
+    "- Create a new request (`SwitchControllerRequest`) and add the `position_joint_trajectory_controller` to the `start_controllers` list.\n",
+    "- Set the `strictness` to `BEST_EFFORT`.\n",
+    "- Check if the service was successful.\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### YOUR CODE HERE #####\n",
+    "\n",
+    "# Define the controllers\n",
+    "controller_to_activate = 'position_joint_trajectory_controller'\n",
+    "\n",
+    "# Check if the controller is already loaded\n",
+    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
+    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
+    "loaded_controllers = [controller.name for controller in list_controllers().controller]\n",
+    "\n",
+    "if controller_to_activate not in loaded_controllers:\n",
+    "    # Service for loading the controller to be activated\n",
+    "    rospy.wait_for_service('/controller_manager/load_controller')\n",
+    "    load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n",
+    "    response = load_service(controller_to_activate)\n",
+    "    assert response.ok, \"Controller could not be loaded.\"\n",
+    "\n",
+    "# Service for switching to the controller to be activated\n",
+    "rospy.wait_for_service('/controller_manager/switch_controller')\n",
+    "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
+    "switch_req = SwitchControllerRequest()\n",
+    "switch_req.start_controllers = [controller_to_activate]\n",
+    "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
+    "response = switch_service(switch_req)\n",
+    "assert response.ok, \"Controller could not be started.\"\n",
+    "\n",
+    "# Add a short sleep to ensure the controller is fully activated\n",
+    "rospy.sleep(3)\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Summary\n",
+    "\n",
+    "In this task, you learned how to activate a controller and use ROS services to interact with the controller manager.\n",
+    "\n",
+    "### Next Steps\n",
+    "\n",
+    "In the next notebook, we will use the trajectory to control the robot. This will help you gain a deeper understanding of controlling robots in ROS.\n",
+    "\n",
+    "Proceed with `use_position_controller` to learn how to use a controller."
+   ]
+  }
+ ],
+ "metadata": {
+  "language_info": {
+   "name": "python"
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb
index 1b4a00c4cdfc80d405a1661ced40972c2145a0b3..d659d212e1202e8da92f11d020c7d1f09ec8048d 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/position_controller.ipynb
@@ -15,15 +15,11 @@
     "## Controller_Task\n",
     "### Position_Controller\n",
     "\n",
-    "In this task, you will learn: \n",
+    "> In this task, you will learn ...\n",
     ">\n",
-    "> - how to work with a position controller to move the joints of a robot to specific positions.\n",
-    "> - how to stop all active controllers to ensure no conflicts occur.\n",
-    "> - how to start the position controller if it is not already running.\n",
-    "> - how to create a `JointTrajectory` message for the position controller.\n",
-    "> - how to define target positions for each joint and set the time to reach these positions.\n",
-    "> - how to send the target position to the controller and verify the movement.\n",
-    "> - how to switch back to the previously active controllers after completing the task."
+    "> - how to use the position controller to send joint trajectory commands\n",
+    "> - how to create and publish JointTrajectory messages\n",
+    "> - how to define target positions and durations for joint movements\n"
    ]
   },
   {
@@ -34,123 +30,16 @@
    "source": [
     "##### DO NOT CHANGE #####\n",
     "\n",
+    "import sys\n",
+    "import math\n",
     "import rospy\n",
-    "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
     "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
-    "from moveit_commander import roscpp_shutdown\n",
-    "import math\n",
+    "from moveit_commander import roscpp_shutdown, roscpp_initialize\n",
+    "from controller_manager_msgs.srv import SwitchController, SwitchControllerRequest\n",
     "\n",
     "##### DO NOT CHANGE #####"
    ]
   },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "### Task 1:\n",
-    "\n",
-    "Stop all active controllers.\n",
-    "\n",
-    "**Important**\n",
-    "Use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
-    "\n",
-    "#### Procedure:\n",
-    "\n",
-    "- Then create a service proxy for this service and retrieve the list of active controllers.\n",
-    "- Filter the controllers that have the state 'running' and save their names in a list.\n",
-    "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
-    "- Then create a service proxy for this service.\n",
-    "- Create a new request (`SwitchControllerRequest`) and add the list of active controllers to the `stop_controllers` list.\n",
-    "- Set the `strictness` to `BEST_EFFORT`.\n",
-    "- Check if the service was successful."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### YOUR CODE HERE #####\n",
-    "\n",
-    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
-    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
-    "active_controllers = [controller.name for controller in list_controllers().controller if controller.state == 'running']\n",
-    "\n",
-    "if active_controllers:\n",
-    "    rospy.wait_for_service('/controller_manager/switch_controller')\n",
-    "    try:\n",
-    "        switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
-    "        req = SwitchControllerRequest()\n",
-    "        req.stop_controllers = active_controllers\n",
-    "        req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
-    "        response = switch_controller(req)\n",
-    "        assert response.ok, \"Active controllers could not be stopped.\"\n",
-    "    except rospy.ServiceException as e:\n",
-    "        rospy.logerr(\"Service call failed: %s\" % e)\n",
-    "\n",
-    "##### YOUR CODE HERE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "### Task 2:\n",
-    "\n",
-    "Activate the position controller.\n",
-    "\n",
-    "#### Procedure:\n",
-    "\n",
-    "- First, use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
-    "- Then create a service proxy for this service and retrieve the list of loaded controllers.\n",
-    "\n",
-    "- Check if the `position_joint_trajectory_controller` is already loaded.\n",
-    "- If not, use the `wait_for_service` method to wait for the `/controller_manager/load_controller` service.\n",
-    "- Then create a service proxy for this service and load the controller.\n",
-    "\n",
-    "- Now use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
-    "- Then create a service proxy for this service.\n",
-    "- Create a new request (`SwitchControllerRequest`) and add the `position_joint_trajectory_controller` to the `start_controllers` list.\n",
-    "- Set the `strictness` to `BEST_EFFORT`.\n",
-    "- Check if the service was successful.\n"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### YOUR CODE HERE #####\n",
-    "\n",
-    "# Define the controllers\n",
-    "controller_to_activate = 'position_joint_trajectory_controller'\n",
-    "\n",
-    "# Check if the controller is already loaded\n",
-    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
-    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
-    "loaded_controllers = [controller.name for controller in list_controllers().controller]\n",
-    "\n",
-    "if controller_to_activate not in loaded_controllers:\n",
-    "    # Service for loading the controller to be activated\n",
-    "    rospy.wait_for_service('/controller_manager/load_controller')\n",
-    "    load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n",
-    "    response = load_service(controller_to_activate)\n",
-    "    assert response.ok, \"Controller could not be loaded.\"\n",
-    "\n",
-    "# Service for switching to the controller to be activated\n",
-    "rospy.wait_for_service('/controller_manager/switch_controller')\n",
-    "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
-    "switch_req = SwitchControllerRequest()\n",
-    "switch_req.start_controllers = [controller_to_activate]\n",
-    "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
-    "response = switch_service(switch_req)\n",
-    "assert response.ok, \"Controller could not be started.\"\n",
-    "\n",
-    "##### YOUR CODE HERE #####"
-   ]
-  },
   {
    "cell_type": "markdown",
    "metadata": {},
@@ -168,6 +57,9 @@
    "source": [
     "##### DO NOT CHANGE #####\n",
     "\n",
+    "# Initialize the ROS communication infrastructure\n",
+    "roscpp_initialize(sys.argv)\n",
+    "\n",
     "# Initialize ROS\n",
     "rospy.init_node('position_control', anonymous=True)\n",
     "\n",
@@ -217,9 +109,9 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "### Task 3:\n",
+    "### Task :\n",
     "\n",
-    "Now you have to define more target position yourself.\n",
+    "Now you have to define one more target position yourself.\n",
     "\n",
     "#### Procedure:\n",
     "\n",
@@ -258,6 +150,8 @@
     "point1.time_from_start = rospy.Duration(4.0)\n",
     "traj_msg.points.append(point1)\n",
     "\n",
+    "rospy.sleep(2)\n",
+    "\n",
     "##### YOUR CODE HERE #####"
    ]
   },
@@ -280,7 +174,7 @@
     "pub.publish(traj_msg)\n",
     "\n",
     "# Ensure the message is processed\n",
-    "rospy.sleep(5)\n",
+    "rospy.sleep(6)\n",
     "\n",
     "##### DO NOT CHANGE #####"
    ]
@@ -289,19 +183,7 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "### Task 4:\n",
-    "\n",
-    "Now switch back to the previously active controllers.\n",
-    "\n",
-    "Tip: You have already saved these in a list before.\n",
-    "\n",
-    "#### Procedure:\n",
-    "\n",
-    "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
-    "- Then create a service proxy for this service.\n",
-    "- Create a new request (`SwitchControllerRequest`) and add the previously active controllers to the `start_controllers` list.\n",
-    "- Set the `strictness` to `BEST_EFFORT`.\n",
-    "- Check if the service was successful.\n"
+    "Now switch back to the previously active controllers, which are the franke_gripper_controller, the franka_state_controller and the effort_joint_trajectory_controller."
    ]
   },
   {
@@ -310,7 +192,7 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### YOUR CODE HERE #####\n",
+    "##### DO NOT CHANGE #####\n",
     "\n",
     "# switch back to the previous controllers\n",
     "rospy.wait_for_service('/controller_manager/switch_controller')\n",
@@ -319,14 +201,14 @@
     "    req = SwitchControllerRequest()\n",
     "    req.stop_controllers = ['position_joint_trajectory_controller']\n",
     "    # restart the previously active controllers\n",
-    "    req.start_controllers = active_controllers\n",
+    "    req.start_controllers = ['franka_gripper', 'franka_state_controller', 'effort_joint_trajectory_controller']\n",
     "    req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
     "    response = switch_controller(req)\n",
     "    assert response.ok, \"Previous controllers could not be restarted.\"\n",
     "except rospy.ServiceException as e:\n",
     "    rospy.logerr(\"Service call failed: %s\" % e)\n",
     "\n",
-    "##### YOUR CODE HERE #####"
+    "##### DO NOT CHANGE #####"
    ]
   },
   {
@@ -351,6 +233,19 @@
     "\n",
     "##### DO NOT CHANGE #####"
    ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Summary\n",
+    "\n",
+    "In these three notebooks (stop_controller, activate_controller and use_position_controller), you have learned how to:\n",
+    "\n",
+    "1. Use the position controller to send joint trajectories and define target positions for joint movements.\n",
+    "2. Stop all active controllers to avoid conflicts and how to use the controller manager and ROS services to interact with the controller manager.\n",
+    "3. Activate a controller and ensure that it is successfully loaded and started."
+   ]
   }
  ],
  "metadata": {
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/stop_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/stop_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..b3b86968e7cc632fbd70382d199eef8d3e79e491
--- /dev/null
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/stop_controller.ipynb
@@ -0,0 +1,117 @@
+{
+ "cells": [
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "# Educational Plattform Panda Robot\n",
+    "Author: uninh, uqwfa, ultck"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "## Controller_Task\n",
+    "### Stop_Controller\n",
+    "\n",
+    "> In this task, you will learn ...\n",
+    ">\n",
+    "> - how to stop all active controllers to ensure no conflicts occur.\n",
+    "> - how to work with the controller manager.\n",
+    "> - how to use ROS services to interact with the controller manager.\n",
+    "> - how to handle service proxies and requests in ROS.\n",
+    "> - how to filter and manage controller states."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### DO NOT CHANGE #####\n",
+    "\n",
+    "import rospy\n",
+    "from controller_manager_msgs.srv import SwitchController, SwitchControllerRequest, ListControllers\n",
+    "\n",
+    "##### DO NOT CHANGE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Task :\n",
+    "\n",
+    "First off all we want to stop all active controllers.\n",
+    "\n",
+    "#### Procedure:\n",
+    "\n",
+    "- Use the 'wait_for_service' method to wait for the `/controller_manager/list_controllers`\n",
+    "- Then create a service proxy for this service and retrieve the list of active controllers.\n",
+    "- Filter the controllers that have the state 'running' and save their names in a list.\n",
+    "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+    "- Then create a service proxy for this service.\n",
+    "- Create a new request (`SwitchControllerRequest`) and add the list of active controllers to the `stop_controllers` list.\n",
+    "- Set the `strictness` to `BEST_EFFORT`.\n",
+    "- Check if the service was successful."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### YOUR CODE HERE #####\n",
+    "\n",
+    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
+    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
+    "\n",
+    "# Retrieve the list of active controllers and filter those that are running\n",
+    "active_controllers = [controller.name for controller in list_controllers().controller if controller.state == 'running']\n",
+    "\n",
+    "if active_controllers:\n",
+    "    # Wait for the switch_controller service to become available\n",
+    "    rospy.wait_for_service('/controller_manager/switch_controller')\n",
+    "    try:\n",
+    "        switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
+    "        \n",
+    "        # Create a request to stop the active controllers\n",
+    "        req = SwitchControllerRequest()\n",
+    "        req.stop_controllers = active_controllers\n",
+    "        req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
+    "        \n",
+    "        # Call the service and check if the request was successful\n",
+    "        response = switch_controller(req)\n",
+    "        assert response.ok, \"Active controllers could not be stopped.\"\n",
+    "    except rospy.ServiceException as e:\n",
+    "        rospy.logerr(\"Service call failed: %s\" % e)\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Summary\n",
+    "In this task, you have learned how to stop all active controllers and use ROS services to interact with the controller manager.\n",
+    "\n",
+    "### Next Steps\n",
+    "\n",
+    "In the next notebook, we will focus on how to activate a controller. This will help you develop a deeper understanding of managing controllers in ROS.\n",
+    "\n",
+    "Proceed to `Activate_Controller` to learn how to activate a controller."
+   ]
+  }
+ ],
+ "metadata": {
+  "language_info": {
+   "name": "python"
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/switch_controller.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/switch_controller.ipynb
deleted file mode 100644
index fac989a475113e8ad1d30e11cd7a619031a35d82..0000000000000000000000000000000000000000
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/controller/controller_task/switch_controller.ipynb
+++ /dev/null
@@ -1,276 +0,0 @@
-{
- "cells": [
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "# Educational Plattform Panda Robot\n",
-    "Author: uninh, uqwfa, ultck"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "## Controller_Task\n",
-    "### Switch_Controller\n",
-    "\n",
-    "In this task, you will learn...\n",
-    "\n",
-    "> - Understand how to stop a controller and load a new controller.\n",
-    "> - Learn how to activate a new controller.\n",
-    "> - Find out how to switch back to the previous controllers after completing the task"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "import rospy\n",
-    "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, ListControllers\n",
-    "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
-    "from moveit_commander import roscpp_shutdown\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "#### Creating a List of All Active Controllers\n",
-    "\n",
-    "In the next section, a list of all active controllers will be created.\n",
-    "\n",
-    "The method `wait_for_service` blocks the code until the service `/controller_manager/list_controllers` is available. This ensures that the service is ready before attempting to use it.\n",
-    "\n",
-    "After that, a service proxy is created. A service proxy is an object that allows making service calls as if it were a local function. In this case, the service `/controller_manager/list_controllers` is used.\n",
-    "\n",
-    "Finally, a list of names of the active controllers is created."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "# create a list of active controllers\n",
-    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
-    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
-    "active_controllers = [controller.name for controller in list_controllers().controller if controller.state == 'running']\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "#### Stopping Active Controllers\n",
-    "\n",
-    "If there are active controllers, they should be stopped in the following section.\n",
-    "\n",
-    "As before, we wait until the service is available. Then, in the try block, a proxy for the ROS service `switch_controller` is created and a new request (`SwitchControllerRequest`) is made. The list of controllers to be stopped in the request is set to the list of all active controllers. Setting the strictness to `BEST_EFFORT` means that the service will do its best to stop the controllers, but it is not guaranteed that all will be stopped. Finally, the response is saved and checked to see if all services were successfully stopped."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "if active_controllers:\n",
-    "    rospy.wait_for_service('/controller_manager/switch_controller')\n",
-    "    try:\n",
-    "        switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
-    "        req = SwitchControllerRequest()\n",
-    "        req.stop_controllers = active_controllers\n",
-    "        req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
-    "        response = switch_controller(req)\n",
-    "        assert response.ok, \"Active controllers could not be stopped.\"\n",
-    "    except rospy.ServiceException as e:\n",
-    "        rospy.logerr(\"Service call failed: %s\" % e)\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "#### Loading a New Controller\n",
-    "\n",
-    "Now we load the new controller.\n",
-    "\n",
-    "First, the name of the controller to be activated is defined. Then it is checked whether the controller is already loaded. If not, the service `/controller_manager/load_controller` is used to load the controller. If the controller is successfully loaded, this is confirmed with a confirmation message."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "# Define the controller to be activated\n",
-    "controller_to_activate = 'position_joint_trajectory_controller'\n",
-    "\n",
-    "# Check if the controller is already loaded\n",
-    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
-    "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
-    "loaded_controllers = [controller.name for controller in list_controllers().controller]\n",
-    "if controller_to_activate not in loaded_controllers:\n",
-    "    # Service for loading the controller to be activated\n",
-    "    rospy.wait_for_service('/controller_manager/load_controller')\n",
-    "    load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n",
-    "    response = load_service(controller_to_activate)\n",
-    "    assert response.ok, \"Controller could not be loaded.\"\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "#### Activating the New Controller\n",
-    "\n",
-    "After the new controller has been loaded, it will now be activated.\n",
-    "\n",
-    "First, wait until the service `/controller_manager/switch_controller` is available. Then, a service proxy for the service is created. A new request (`SwitchControllerRequest`) is made and the name of the controller to be started is added to the request. The strictness is set to `BEST_EFFORT`, which means that the service will do its best to start the controller. Finally, the response is saved and checked to see if the controller was successfully started."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "# Service for switching to the controller to be activated\n",
-    "rospy.wait_for_service('/controller_manager/switch_controller')\n",
-    "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
-    "switch_req = SwitchControllerRequest()\n",
-    "switch_req.start_controllers = [controller_to_activate]\n",
-    "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
-    "response = switch_service(switch_req)\n",
-    "assert response.ok, \"Controller could not be started.\"\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "#### Task\n",
-    "\n",
-    "Now create a list of all currently active controllers as done in a previous code cell.\n",
-    "\n",
-    "**Important**\n",
-    "Assign different identifiers to the individual elements to avoid confusion !!!\n",
-    "\n",
-    "- Use the method `wait_for_service` to wait for the service `/controller_manager/list_controllers`\n",
-    "- Then create a service proxy for this service and retrieve the list of active controllers\n",
-    "- Filter the controllers that have the state 'running' and save their names in a list\n",
-    "- Finally, print the list to the terminal"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### YOUR CODE HERE #####\n",
-    "\n",
-    "rospy.wait_for_service('/controller_manager/list_controllers')\n",
-    "list_controllers_1 = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
-    "active_controllers_1 = [controller.name for controller in list_controllers_1().controller if controller.state == 'running']\n",
-    "print(f\"Active controllers: {active_controllers_1}\")\n",
-    "\n",
-    "##### YOUR CODE HERE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "Finally, we switch back to the previous controllers, which you should now implement yourself.\n",
-    "\n",
-    "- Use the method `wait_for_service` to wait for the service `/controller_manager/switch_controller`.\n",
-    "- Then create a service proxy for this service.\n",
-    "- Create a new request (`SwitchControllerRequest`) and add the name of the controller to be stopped (`'position_joint_trajectory_controller'`) to the `stop_controllers` list.\n",
-    "- Add the list of previous active controllers (`active_controllers`) to the `start_controllers` list.\n",
-    "- Set the `strictness` to `BEST_EFFORT`.\n",
-    "- Check if the service was successful."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### YOUR CODE HERE #####\n",
-    "\n",
-    "# Switch back to previous controllers\n",
-    "rospy.wait_for_service('/controller_manager/switch_controller')\n",
-    "try:\n",
-    "    switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
-    "    req = SwitchControllerRequest()\n",
-    "    req.stop_controllers = ['position_joint_trajectory_controller']\n",
-    "    # the controllers that were active before\n",
-    "    req.start_controllers = active_controllers\n",
-    "    req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
-    "    response = switch_controller(req)\n",
-    "    assert response.ok, \"Controller konnte nicht gewechselt werden.\"\n",
-    "except rospy.ServiceException as e:\n",
-    "    rospy.logerr(\"Service call failed: %s\" % e)\n",
-    "\n",
-    "##### YOUR CODE HERE #####"
-   ]
-  },
-  {
-   "cell_type": "markdown",
-   "metadata": {},
-   "source": [
-    "### Cleaning up and quitting the ROS node\n",
-    "At the end, the ROS node is shut down and the resources are released."
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "##### DO NOT CHANGE #####\n",
-    "\n",
-    "# Shutdown the ROS node\n",
-    "rospy.signal_shutdown(\"Task completed\")\n",
-    "roscpp_shutdown()\n",
-    "\n",
-    "##### DO NOT CHANGE #####"
-   ]
-  }
- ],
- "metadata": {
-  "language_info": {
-   "name": "python"
-  }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb
index a6c95cbe26c460db224df56070a92e43c4059da8..301d34646bfc80b66b84de04877030250ca74ac6 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_3.ipynb
@@ -86,7 +86,7 @@
     "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
     "from geometry_msgs.msg import Pose\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb
index 9a05ef102ae6b44855b3e71734f7e361a0e840c6..301141e680c046f4cce87e80ed404825b8d18bcc 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_4.ipynb
@@ -46,7 +46,7 @@
     "import sys\n",
     "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
index d3abb5865e325a9935bd2eedc779b1b14bd8274e..93542b1e4882dfdbbbff8d9c7c3f272610cd6982 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
@@ -32,7 +32,7 @@
    "source": [
     "First, all the necessary packages and classes are imported. You already know these from the move_it_basics and move_it_objects tasks.\n",
     "\n",
-    "Then, as usual, we initialize the MoveIt Commander, create a ROS node and initialize the Move Group."
+    "Then, as usual, we initialize the ROS communication infrastructure, create a ROS node and initialize the Move Group."
    ]
   },
   {
@@ -48,7 +48,7 @@
     "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
     "from geometry_msgs.msg import Pose\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS-Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb
index 04ae9c6edce0d34e566fb983afeea6c5c45a5492..00c5e02a9f9e9ec42ed4bd8e0434baeab8f07b93 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_1.ipynb
@@ -65,7 +65,7 @@
    "source": [
     "##### DO NOT CHANGE #####\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb
index 6492b6e6cbe26efb03c0ec02d6943e49e49f78d0..5bafab61ca1bb8e63b17f8ed44f9f3c962da9895 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_2.ipynb
@@ -69,7 +69,7 @@
    "source": [
     "##### DO NOT CHANGE #####\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb
index 90cc9abd2f32d92cd7855d4fe95aeeacf1bab37f..be1e743ab75358cc0852a82b6806c20b5ab8542b 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_objects/move_it_objects_3.ipynb
@@ -64,7 +64,7 @@
    "source": [
     "##### DO NOT CHANGE #####\n",
     "\n",
-    "# Initialize the MoveIt Commander\n",
+    "# Initialize the ROS communication infrastructure\n",
     "roscpp_initialize(sys.argv)\n",
     "\n",
     "# Initialize the ROS Node\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/task_definitions.json b/catkin_ws/src/learn_environment/task_pool/task_definitions.json
index 568ea9598ba7daaeffdc83f93811cea8645532f5..00df4eb5dba7affc6935f96dd3b5d732ed5ca33c 100644
--- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json
+++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json
@@ -129,15 +129,22 @@
       "folder": "/controller/controller_task",
       "topic": "Controller",
       "difficulty": "intermediate",
+      "previous_subtasks_required": true,
       "subtasks": [
         {
           "title": "Task 1",
-          "description": "Understand how to switch between controllers",
-          "solution_file": "/switch_controller.ipynb",
-          "evaluation_file": "/switch_controller_eval.py"
+          "description": "Understand how to stop the currently running controllers",
+          "solution_file": "/stop_controller.ipynb",
+          "evaluation_file": "/stop_controller_eval.py"
         },
         {
           "title": "Task 2",
+          "description": "Understand how to activate a controller",
+          "solution_file": "/activate_controller.ipynb",
+          "evaluation_file": "/activate_controller_eval.py"
+        },
+        {
+          "title": "Task 3",
           "description": "Understand the basics of the position controller",
           "solution_file": "/position_controller.ipynb",
           "evaluation_file": "/position_controller_eval.py"
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..d5e9b1371195e142c5e1a9c93c11caa8d2d6ca13
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_controller.ipynb
@@ -0,0 +1,131 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## Controller_Task\n",
+                "### Activate_Controller\n",
+                "\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - how to activate a controller"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown\n",
+                "import math\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 2:\n",
+                "\n",
+                "Activate the position controller.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- First, use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
+                "- Then create a service proxy for this service and retrieve the list of loaded controllers.\n",
+                "\n",
+                "- Check if the `position_joint_trajectory_controller` is already loaded.\n",
+                "- If not, use the `wait_for_service` method to wait for the `/controller_manager/load_controller` service.\n",
+                "- Then create a service proxy for this service and load the controller.\n",
+                "\n",
+                "- Now use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the `position_joint_trajectory_controller` to the `start_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful.\n"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "solution_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##############################################################\n####     THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE.    ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n####    USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE.   ####\n##############################################################\n\n",
+                "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n",
+                "\n",
+                "# Define the controllers\n",
+                "controller_to_activate = 'position_joint_trajectory_controller'\n",
+                "\n",
+                "# Check if the controller is already loaded\n",
+                "rospy.wait_for_service('/controller_manager/list_controllers')\n",
+                "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
+                "loaded_controllers = [controller.name for controller in list_controllers().controller]\n",
+                "\n",
+                "if controller_to_activate not in loaded_controllers:\n",
+                "    # Service for loading the controller to be activated\n",
+                "    rospy.wait_for_service('/controller_manager/load_controller')\n",
+                "    load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)\n",
+                "    response = load_service(controller_to_activate)\n",
+                "    assert response.ok, \"Controller could not be loaded.\"\n",
+                "\n",
+                "# Service for switching to the controller to be activated\n",
+                "rospy.wait_for_service('/controller_manager/switch_controller')\n",
+                "switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
+                "switch_req = SwitchControllerRequest()\n",
+                "switch_req.start_controllers = [controller_to_activate]\n",
+                "switch_req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
+                "response = switch_service(switch_req)\n",
+                "assert response.ok, \"Controller could not be started.\"\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_previous_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_previous_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..3094a1037cf457bdd350e779b9d85100f82b94d1
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/activate_previous_controller.ipynb
@@ -0,0 +1,131 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown\n",
+                "import math\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 4:\n",
+                "\n",
+                "Now switch back to the previously active controllers.\n",
+                "\n",
+                "Tip: You have already saved these in a list before.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the previously active controllers to the `start_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "solution_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##############################################################\n####     THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE.    ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n####    USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE.   ####\n##############################################################\n\n",
+                "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n",
+                "\n",
+                "# switch back to the previous controllers\n",
+                "rospy.wait_for_service('/controller_manager/switch_controller')\n",
+                "try:\n",
+                "    switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
+                "    req = SwitchControllerRequest()\n",
+                "    req.stop_controllers = ['position_joint_trajectory_controller']\n",
+                "    # restart the previously active controllers\n",
+                "    req.start_controllers = active_controllers\n",
+                "    req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
+                "    response = switch_controller(req)\n",
+                "    assert response.ok, \"Previous controllers could not be restarted.\"\n",
+                "except rospy.ServiceException as e:\n",
+                "    rospy.logerr(\"Service call failed: %s\" % e)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Cleaning up and quitting the ROS node\n",
+                "At the end, the ROS node is shut down and the resources are released."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Shutdown the ROS node\n",
+                "rospy.signal_shutdown(\"Task completed\")\n",
+                "roscpp_shutdown()\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller2.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..d8d464f92480cfbb419b4f1eb29b45bcf37e890b
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller2.ipynb
@@ -0,0 +1,234 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## Controller_Task\n",
+                "### Position_Controller\n",
+                "\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - how to use the position controller to send joint trajectory commands\n",
+                "> - how to create and publish JointTrajectory messages\n",
+                "> - how to define target positions and durations for joint movements\n"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import sys\n",
+                "import math\n",
+                "import rospy\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown, roscpp_initialize\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now the ROS node is initialized, a publisher is created for the command topic and waited until the publisher is created.\n",
+                "\n",
+                "The publisher sends messages of the type JointTrajectory to the topic /position_joint_trajectory_controller/command. The parameter queue_size=10 sets the size of the message queue. This means that up to 10 messages are held in the queue before old messages are discarded."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Initialize the ROS communication infrastructure\n",
+                "roscpp_initialize(sys.argv)\n",
+                "\n",
+                "# Initialize ROS\n",
+                "rospy.init_node('position_control', anonymous=True)\n",
+                "\n",
+                "# Publisher for the command topic\n",
+                "pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\n",
+                "\n",
+                "# Wait until the publisher is ready\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The position controller receives messages of the type trajectory_msgs/JointTrajectory.\n",
+                "This message contains joint_names, a list of the joints to be controlled, and points, a list of positions to control the joints."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# create a JointTrajectory message\n",
+                "traj_msg = JointTrajectory()\n",
+                "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n",
+                "\n",
+                "# create a JointTrajectoryPoin\n",
+                "point = JointTrajectoryPoint()\n",
+                "# Here the target positions (in radians) for each joint are added as a list\n",
+                "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]\n",
+                "# Now the time is set until the movement should be completed\n",
+                "point.time_from_start = rospy.Duration(1.0)  \n",
+                "\n",
+                "# Finally, the point is added to the trajectory\n",
+                "traj_msg.points.append(point)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task :\n",
+                "\n",
+                "Now you have to define one more target position yourself.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "##### Add target positions:\n",
+                "\n",
+                "Create a JointTrajectoryPoint to define the target positions for each joint and complete the following fields:\n",
+                "\n",
+                "- positions: The target positions in Radiant (e.g. [0.5, -0.5, 0.0])\n",
+                "\n",
+                "- time_from_start: The time it takes for the robot to reach the positions\n",
+                "\n",
+                "The joints should take the following values:\n",
+                "\n",
+                " - Joint1 : π / 2\n",
+                " - Joint2 : - π / 4\n",
+                " - Joint3 : 0.0\n",
+                " - Joint4 : - 3 * π / 4 \n",
+                " - Joint5 : 0.0\n",
+                " - Joint6 : π / 2\n",
+                " - Joint7 : π / 4\n",
+                "\n",
+                "Now add the point to the trajectory."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now a message is sent via a publisher and it is ensured that the message is processed by waiting briefly."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# send the message\n",
+                "pub.publish(traj_msg)\n",
+                "\n",
+                "# Ensure the message is processed\n",
+                "rospy.sleep(5)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Cleaning up and quitting the ROS node\n",
+                "At the end, the ROS node is shut down and the resources are released."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": []
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Summary\n",
+                "In this task, you have learned how to use the position controller to send joint trajectory commands and define target positions for joint movements.\n",
+                "\n",
+                "### Next Steps\n",
+                "\n",
+                "In the next notebook, we will focus on how to activate the controller which have been running previously.\n",
+                "\n",
+                "Proceed to `Activate_Previous_Controller` to learn how to switch back to previously active controllers."
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller3.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller3.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..befe6e51f77b6dc4b68fed3f1721dbcc731ee6e8
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/position_controller3.ipynb
@@ -0,0 +1,339 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## Controller_Task\n",
+                "### Position_Controller\n",
+                "\n",
+                "In this task, you will learn: \n",
+                ">\n",
+                "> - how to work with a position controller to move the joints of a robot to specific positions.\n",
+                "> - how to stop all active controllers to ensure no conflicts occur.\n",
+                "> - how to start the position controller if it is not already running.\n",
+                "> - how to create a `JointTrajectory` message for the position controller.\n",
+                "> - how to define target positions for each joint and set the time to reach these positions.\n",
+                "> - how to send the target position to the controller and verify the movement.\n",
+                "> - how to switch back to the previously active controllers after completing the task."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown\n",
+                "import math\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 1:\n",
+                "\n",
+                "Stop all active controllers.\n",
+                "\n",
+                "**Important**\n",
+                "Use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- Then create a service proxy for this service and retrieve the list of active controllers.\n",
+                "- Filter the controllers that have the state 'running' and save their names in a list.\n",
+                "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the list of active controllers to the `stop_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 2:\n",
+                "\n",
+                "Activate the position controller.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- First, use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
+                "- Then create a service proxy for this service and retrieve the list of loaded controllers.\n",
+                "\n",
+                "- Check if the `position_joint_trajectory_controller` is already loaded.\n",
+                "- If not, use the `wait_for_service` method to wait for the `/controller_manager/load_controller` service.\n",
+                "- Then create a service proxy for this service and load the controller.\n",
+                "\n",
+                "- Now use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the `position_joint_trajectory_controller` to the `start_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful.\n"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now the ROS node is initialized, a publisher is created for the command topic and waited until the publisher is created.\n",
+                "\n",
+                "The publisher sends messages of the type JointTrajectory to the topic /position_joint_trajectory_controller/command. The parameter queue_size=10 sets the size of the message queue. This means that up to 10 messages are held in the queue before old messages are discarded."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Initialize ROS\n",
+                "rospy.init_node('position_control', anonymous=True)\n",
+                "\n",
+                "# Publisher for the command topic\n",
+                "pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\n",
+                "\n",
+                "# Wait until the publisher is ready\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The position controller receives messages of the type trajectory_msgs/JointTrajectory.\n",
+                "This message contains joint_names, a list of the joints to be controlled, and points, a list of positions to control the joints."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# create a JointTrajectory message\n",
+                "traj_msg = JointTrajectory()\n",
+                "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n",
+                "\n",
+                "# create a JointTrajectoryPoin\n",
+                "point = JointTrajectoryPoint()\n",
+                "# Here the target positions (in radians) for each joint are added as a list\n",
+                "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]\n",
+                "# Now the time is set until the movement should be completed\n",
+                "point.time_from_start = rospy.Duration(2.0)  \n",
+                "\n",
+                "# Finally, the point is added to the trajectory\n",
+                "traj_msg.points.append(point)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 3:\n",
+                "\n",
+                "Now you have to define more target position yourself.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "##### Add target positions:\n",
+                "\n",
+                "Create a JointTrajectoryPoint to define the target positions for each joint and complete the following fields:\n",
+                "\n",
+                "- positions: The target positions in Radiant (e.g. [0.5, -0.5, 0.0])\n",
+                "\n",
+                "- time_from_start: The time it takes for the robot to reach the positions\n",
+                "\n",
+                "The joints should take the following values:\n",
+                "\n",
+                " - Joint1 : π / 2\n",
+                " - Joint2 : - π / 4\n",
+                " - Joint3 : 0.0\n",
+                " - Joint4 : - 3 * π / 4 \n",
+                " - Joint5 : 0.0\n",
+                " - Joint6 : π / 2\n",
+                " - Joint7 : π / 4\n",
+                "\n",
+                "Now add the point to the trajectory."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now a message is sent via a publisher and it is ensured that the message is processed by waiting briefly."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# send the message\n",
+                "pub.publish(traj_msg)\n",
+                "\n",
+                "# Ensure the message is processed\n",
+                "rospy.sleep(5)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 4:\n",
+                "\n",
+                "Now switch back to the previously active controllers.\n",
+                "\n",
+                "Tip: You have already saved these in a list before.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the previously active controllers to the `start_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful.\n"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_8",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Cleaning up and quitting the ROS node\n",
+                "At the end, the ROS node is shut down and the resources are released."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_9"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Shutdown the ROS node\n",
+                "rospy.signal_shutdown(\"Task completed\")\n",
+                "roscpp_shutdown()\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/stop_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/stop_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..7d82e37d117a47f05d479bec28c680754629dad5
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/stop_controller.ipynb
@@ -0,0 +1,140 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## Controller_Task\n",
+                "### Stop_Controller\n",
+                "\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - how to stop a running controller"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown\n",
+                "import math\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 1:\n",
+                "\n",
+                "Stop all active controllers.\n",
+                "\n",
+                "**Important**\n",
+                "Use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "- Then create a service proxy for this service and retrieve the list of active controllers.\n",
+                "- Filter the controllers that have the state 'running' and save their names in a list.\n",
+                "- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.\n",
+                "- Then create a service proxy for this service.\n",
+                "- Create a new request (`SwitchControllerRequest`) and add the list of active controllers to the `stop_controllers` list.\n",
+                "- Set the `strictness` to `BEST_EFFORT`.\n",
+                "- Check if the service was successful."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "solution_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##############################################################\n####     THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE.    ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n####    USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE.   ####\n##############################################################\n\n",
+                "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n",
+                "\n",
+                "rospy.wait_for_service('/controller_manager/list_controllers')\n",
+                "list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)\n",
+                "active_controllers = [controller.name for controller in list_controllers().controller if controller.state == 'running']\n",
+                "\n",
+                "if active_controllers:\n",
+                "    rospy.wait_for_service('/controller_manager/switch_controller')\n",
+                "    try:\n",
+                "        switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)\n",
+                "        req = SwitchControllerRequest()\n",
+                "        req.stop_controllers = active_controllers\n",
+                "        req.strictness = SwitchControllerRequest.BEST_EFFORT\n",
+                "        response = switch_controller(req)\n",
+                "        assert response.ok, \"Active controllers could not be stopped.\"\n",
+                "    except rospy.ServiceException as e:\n",
+                "        rospy.logerr(\"Service call failed: %s\" % e)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Shutdown the ROS node\n",
+                "rospy.signal_shutdown(\"Task completed\")\n",
+                "roscpp_shutdown()\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/controller/controller_task/use_position_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/use_position_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..0c098300f3e7d9d8d81c24a364f528153aa15d0a
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/use_position_controller.ipynb
@@ -0,0 +1,206 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, UnloadController, ListControllers\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from moveit_commander import roscpp_shutdown\n",
+                "import math\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now the ROS node is initialized, a publisher is created for the command topic and waited until the publisher is created.\n",
+                "\n",
+                "The publisher sends messages of the type JointTrajectory to the topic /position_joint_trajectory_controller/command. The parameter queue_size=10 sets the size of the message queue. This means that up to 10 messages are held in the queue before old messages are discarded."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Initialize ROS\n",
+                "rospy.init_node('position_control', anonymous=True)\n",
+                "\n",
+                "# Publisher for the command topic\n",
+                "pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\n",
+                "\n",
+                "# Wait until the publisher is ready\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The position controller receives messages of the type trajectory_msgs/JointTrajectory.\n",
+                "This message contains joint_names, a list of the joints to be controlled, and points, a list of positions to control the joints."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# create a JointTrajectory message\n",
+                "traj_msg = JointTrajectory()\n",
+                "traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n",
+                "\n",
+                "# create a JointTrajectoryPoin\n",
+                "point = JointTrajectoryPoint()\n",
+                "# Here the target positions (in radians) for each joint are added as a list\n",
+                "point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]\n",
+                "# Now the time is set until the movement should be completed\n",
+                "point.time_from_start = rospy.Duration(2.0)  \n",
+                "\n",
+                "# Finally, the point is added to the trajectory\n",
+                "traj_msg.points.append(point)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Task 3:\n",
+                "\n",
+                "Now you have to define more target position yourself.\n",
+                "\n",
+                "#### Procedure:\n",
+                "\n",
+                "##### Add target positions:\n",
+                "\n",
+                "Create a JointTrajectoryPoint to define the target positions for each joint and complete the following fields:\n",
+                "\n",
+                "- positions: The target positions in Radiant (e.g. [0.5, -0.5, 0.0])\n",
+                "\n",
+                "- time_from_start: The time it takes for the robot to reach the positions\n",
+                "\n",
+                "The joints should take the following values:\n",
+                "\n",
+                " - Joint1 : π / 2\n",
+                " - Joint2 : - π / 4\n",
+                " - Joint3 : 0.0\n",
+                " - Joint4 : - 3 * π / 4 \n",
+                " - Joint5 : 0.0\n",
+                " - Joint6 : π / 2\n",
+                " - Joint7 : π / 4\n",
+                "\n",
+                "Now add the point to the trajectory."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "solution_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##############################################################\n####     THIS IS A SOLUTION CELL. IT WILL NOT EXECUTE.    ####\n#### YOU CAN RUN THE SOLUTION DIRECTLY WITHIN THE PLUGIN. ####\n####    USE THIS CELL AS INSPIRATION FOR YOUR OWN CODE.   ####\n##############################################################\n\n",
+                "## ↓↓↓↓ SOLUTION CODE HERE ↓↓↓↓ ##\n",
+                "\n",
+                "# define the target position\n",
+                "point1 = JointTrajectoryPoint()\n",
+                "point1.positions = [math.pi / 2, -math.pi / 4, 0.0, -math.pi * 3 / 4, 0.0, math.pi / 2, math.pi / 4]\n",
+                "point1.time_from_start = rospy.Duration(4.0)\n",
+                "traj_msg.points.append(point1)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now a message is sent via a publisher and it is ensured that the message is processed by waiting briefly."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# send the message\n",
+                "pub.publish(traj_msg)\n",
+                "\n",
+                "# Ensure the message is processed\n",
+                "rospy.sleep(5)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file