diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_6/exercise_6_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_intermediate/move_it_intermediate_eval_1.py
similarity index 100%
rename from catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_6/exercise_6_1_eval.py
rename to catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_intermediate/move_it_intermediate_eval_1.py
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_6/exercise_6_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
similarity index 52%
rename from catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_6/exercise_6_1.ipynb
rename to catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
index b4c3f9b011bf4c7f566d349f8d172f8706eeea9c..eb4b28c02cbb28279359a136eca7b8a960428c2f 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_6/exercise_6_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
@@ -6,15 +6,16 @@
    "source": [
     "# Educational Plattform Franka Emika Panda robot arm\n",
     "\n",
-    "Author: uninh, uqwfa, ultck\n",
-    "\n",
-    "### Exercise_6_1 :"
+    "Author: uninh, uqwfa, ultck"
    ]
   },
   {
    "cell_type": "markdown",
    "metadata": {},
    "source": [
+    "## MoveIt Intermediate\n",
+    "### Task 1\n",
+    "\n",
     "---\n",
     ">\n",
     "Ziel dieses Notebooks ist :\n",
@@ -71,7 +72,7 @@
     "rospy.init_node('exercise_6_1', anonymous=True)\n",
     "\n",
     "# Initialize the MoveGroup\n",
-    "arm_group = MoveGroupCommander('panda_arm')\n",
+    "group = MoveGroupCommander('panda_arm')\n",
     "\n",
     "##### DO NOT CHANGE #####"
    ]
@@ -80,7 +81,7 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Todo : Beschreibung"
+    "Mit group.get_current_pose() fragt man in MoveIt die aktuelle Pose des Endeffektors ab. Die Methode gibt ein PoseStamped-Objekt zurück, dessen Eigenschaft pose die eigentliche Geometrie (Position und Orientierung) enthält"
    ]
   },
   {
@@ -89,10 +90,28 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### DO NOT CHANGE #####\n",
+    "##### YOUR CODE HERE #####\n",
     "\n",
     "# Get the current pose of the end-effector\n",
-    "current_pose = arm_group.get_current_pose().pose\n",
+    "current_pose = group.get_current_pose().pose\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "Füge alle Wegpunkte, die der Roboterarm ablaufen soll der hier definierten liste waypoints hinzu."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### DO NOT CHANGE #####\n",
     "\n",
     "# Define the waypoints\n",
     "waypoints = []\n",
@@ -104,7 +123,13 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Todo : Beschreibung"
+    "Nun soll der erste Wegpunkt definiert werden. Erstelle also ein neues Objekt von der Klasse pose.\n",
+    "\n",
+    "Für den ersten Wegpunkt soll sich der Roboterarm um 10 cm (0.1) entlang der X - Achse bewegen, wobei die y - Koordinate und z - Koordinate, sowie die Orientierung unverändert bleiben soll.\n",
+    "\n",
+    "Füge diesen Wegpunt am Ende der liste waypoints hinzu.\n",
+    "\n",
+    "Tipp : setze diese mithilfe der current pose um"
    ]
   },
   {
@@ -113,20 +138,28 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "# Waypoint 1: Slightly move along the X-axis\n",
+    "##### YOUR CODE HERE #####\n",
+    "\n",
     "waypoint_1 = Pose()\n",
     "waypoint_1.position.x = current_pose.position.x + 0.1\n",
     "waypoint_1.position.y = current_pose.position.y\n",
     "waypoint_1.position.z = current_pose.position.z\n",
     "waypoint_1.orientation = current_pose.orientation\n",
-    "waypoints.append(waypoint_1)"
+    "waypoints.append(waypoint_1)\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Todo : Beschreibung"
+    "Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.\n",
+    "\n",
+    "Halte hier nun die X- und Z-Positionen aus dem ersten Wegpunkt bei und verschiebe die Y-Position um 0,2 (20 cm).\n",
+    "Wieder gilt, dass die Orientierung aus der current_pose übernommen werden soll.\n",
+    "\n",
+    "Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu."
    ]
   },
   {
@@ -135,20 +168,28 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "# Waypoint 2: Move along the Y-axis\n",
+    "##### YOUR CODE HERE #####\n",
+    "\n",
     "waypoint_2 = Pose()\n",
     "waypoint_2.position.x = waypoint_1.position.x\n",
-    "waypoint_2.position.y = waypoint_1.position.y + 0.1\n",
+    "waypoint_2.position.y = waypoint_1.position.y + 0.2\n",
     "waypoint_2.position.z = waypoint_1.position.z\n",
     "waypoint_2.orientation = current_pose.orientation\n",
-    "waypoints.append(waypoint_2)"
+    "waypoints.append(waypoint_2)\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Todo : Beschreibung"
+    "Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.\n",
+    "\n",
+    "Halte hier die X- und Y-Positionen aus dem zweiten Wegpunkt bei und verschiebe die Z-Position um 0,4 (40 cm) nach oben.\n",
+    "Ãœbernimm die Orientierung aus der current_pose.\n",
+    "\n",
+    "Füge den neuen Wegpunkt zur waypoints-Liste hinzu."
    ]
   },
   {
@@ -157,20 +198,29 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "# Waypoint 3: Move upwards along the Z-axis\n",
+    "##### YOUR CODE HERE #####\n",
+    "\n",
     "waypoint_3 = Pose()\n",
     "waypoint_3.position.x = waypoint_2.position.x\n",
     "waypoint_3.position.y = waypoint_2.position.y\n",
-    "waypoint_3.position.z = waypoint_2.position.z + 0.1\n",
+    "waypoint_3.position.z = waypoint_2.position.z + 0.4\n",
     "waypoint_3.orientation = current_pose.orientation\n",
-    "waypoints.append(waypoint_3)"
+    "waypoints.append(waypoint_3)\n",
+    "\n",
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Todo : Beschreibung"
+    "Nun werden Parameter definiert, welche die folgende Bedeutung haben :\n",
+    "\n",
+    "fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,\n",
+    "\n",
+    "max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,\n",
+    "\n",
+    "attempts = 0, zählt die Anzahl der Versuche."
    ]
   },
   {
@@ -179,21 +229,65 @@
    "metadata": {},
    "outputs": [],
    "source": [
+    "##### DO NOT CHANGE #####\n",
+    "\n",
     "# Compute the Cartesian path\n",
     "fraction = 0.0\n",
     "max_attempts = 100\n",
     "attempts = 0\n",
     "\n",
+    "##### DO NOT CHANGE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "Erstelle eine Schleife, die läuft, solange der berechnete Pfadanteil (fraction) kleiner als 1.0 ist und die Anzahl der Versuche (attempts) kleiner als max_attempts ist.\n",
+    "\n",
+    "Innerhalb der Schleife, berechne den kartesischen Pfad basierend auf den angegebenen Wegpunkten (waypoints). Verwende 0.01 als Schrittabstand des Endeffektors und 0.0 als Sprungschwellenwert. Die Methode gibt einen Bewegungsplan (plan) und den berechneten Pfadanteil (fraction) zurück.\n",
+    "\n",
+    "Erhöhe am Ende innerhalb der Schleife die Anzahl der Versuche um 1."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### YOUR CODE HERE #####\n",
+    "\n",
     "while fraction < 1.0 and attempts < max_attempts:\n",
-    "    (plan, fraction) = arm_group.compute_cartesian_path(waypoints, 0.01, 0.0)  # Plan the trajectory\n",
+    "    (plan, fraction) = group.compute_cartesian_path(waypoints, 0.01, 0.0)  # Plan the trajectory\n",
     "    attempts += 1\n",
     "\n",
+    "##### YOUR CODE HERE #####"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "Mithilfe der Methode execute wird nun der erstellte plan ausgeführt."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "##### DO NOT CHANGE #####\n",
+    "\n",
     "if fraction == 1.0:\n",
     "    rospy.loginfo(\"Successfully computed the Cartesian path. Executing...\")\n",
-    "    arm_group.execute(plan, wait=True)\n",
+    "    group.execute(plan, wait=True)\n",
     "    rospy.loginfo(\"Execution completed.\")\n",
     "else:\n",
-    "    rospy.logwarn(f\"Failed to compute a complete path after {attempts} attempts.\")"
+    "    rospy.logwarn(f\"Failed to compute a complete path after {attempts} attempts.\")\n",
+    "\n",
+    "##### DO NOT CHANGE #####"
    ]
   },
   {
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 dc86c08006a1b8ae863d16c26b5ac9f5ffa81c25..8a52ba9f16ee112d6462ddddc8bcf0eefd513b69 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
@@ -161,7 +161,7 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### WRITE YOUR CODE HERE #####\n",
+    "##### YOUR CODE HERE #####\n",
     "\n",
     "box_pose_2 = PoseStamped()\n",
     "box_pose_2.header.frame_id = \"panda_link0\"\n",
@@ -170,7 +170,7 @@
     "box_pose_2.pose.position.z = 1.0\n",
     "box_pose_2.pose.orientation.w = 1.0\n",
     "\n",
-    "##### WRITE YOUR CODE HERE #####"
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
@@ -186,11 +186,11 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### WRITE YOUR CODE HERE #####\n",
+    "##### YOUR CODE HERE #####\n",
     "\n",
     "scene.add_box(\"box_2\", box_pose_2, size=(0.1, 0.1, 0.1))\n",
     "\n",
-    "##### WRITE YOUR CODE HERE #####"
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
@@ -207,7 +207,7 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### WRITE YOUR CODE HERE #####\n",
+    "##### YOUR CODE HERE #####\n",
     "\n",
     "cylinder_pose = PoseStamped()\n",
     "cylinder_pose.header.frame_id = \"panda_link0\"\n",
@@ -223,7 +223,7 @@
     "radius = 0.2\n",
     "height = 1.0\n",
     "\n",
-    "##### WRITE YOUR CODE HERE #####"
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
@@ -239,11 +239,11 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### WRITE YOUR CODE HERE #####\n",
+    "##### YOUR CODE HERE #####\n",
     "\n",
     "scene.add_cylinder(\"cylinder\", cylinder_pose, height=height, radius=radius)\n",
     "\n",
-    "##### WRITE YOUR CODE HERE #####"
+    "##### YOUR CODE HERE #####"
    ]
   },
   {
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 812d0737051eb14a5670f828d438fb4f00b033ae..0735fb3b82c62926d639407d7c91b69a66cdc81b 100644
--- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json
+++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json
@@ -111,30 +111,30 @@
       ]
     },
     {
-      "title": "Trajectory Controller",
-      "folder": "/controller/controller_task",
-      "topic": "Controller",
-      "difficulty": "beginner",
+      "title": "MoveIt Intermediate",
+      "folder": "/move_it/move_it_intermediate",
+      "topic": "MoveIt",
+      "difficulty": "intermediate",
       "subtasks": [
         {
-          "title": "Task 1",
-          "description": "TODO: Add Subtask Description Subtask 1.",
-          "solution_file": "/trajectory_controller.ipynb",
-          "evaluation_file": "/trajectory_controller.py"
+          "title": "Task 1 ",
+          "description": "move the robotic arm through a series of positions (waypoints)",
+          "solution_file": "/move_it_intermediate_1.ipynb",
+          "evaluation_file": "/move_it_intermediate_eval_1.py"
         }
       ]
     },
     {
-      "title": "Task 6 (TODO: Rename)",
-      "topic": "Topic 2",
+      "title": "Trajectory Controller",
+      "folder": "/controller/controller_task",
+      "topic": "Controller",
       "difficulty": "beginner",
-      "folder": "/beginner/exercise_6",
       "subtasks": [
         {
-          "title": "Subtask 6.1 (TODO: Rename)",
+          "title": "Task 1",
           "description": "TODO: Add Subtask Description Subtask 1.",
-          "solution_file": "/exercise_6_1.ipynb",
-          "evaluation_file": "/exercise_6_1_eval.py"
+          "solution_file": "/trajectory_controller.ipynb",
+          "evaluation_file": "/trajectory_controller.py"
         }
       ]
     },
diff --git a/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..8a843dbdd88625b2f8b22550fc896baf5d83e340
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_intermediate/move_it_intermediate_1.ipynb
@@ -0,0 +1,448 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## MoveIt Intermediate\n",
+                "### Task 1\n",
+                "\n",
+                "---\n",
+                ">\n",
+                "Ziel dieses Notebooks ist :\n",
+                "- den Roboterarm durch eine Serie von vorgegebenen Positionen (Wegpunkte) im kartesischen Raum zu bewegen\n",
+                "- wie man Bewegungen planen kann, die entlang einer komplexen Trajektorie ablaufen \n",
+                "- wie mehrere Positionen definiert, in eine Trajektorie umgewandelt und schließlich ausgeführt werden können\n",
+                ">\n",
+                "---\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "TODO : Beschreiben der Funktionalität der Pakete, wenn man nicht in vorheriger Aufgabe schon gemacht hat"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import sys\n",
+                "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
+                "from geometry_msgs.msg import Pose\n",
+                "\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "TODO : Initialisierung beschreiben was man macht"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Initialize the MoveIt Commander\n",
+                "roscpp_initialize(sys.argv)\n",
+                "\n",
+                "# Initialize the ROS-Node\n",
+                "rospy.init_node('exercise_6_1', anonymous=True)\n",
+                "\n",
+                "# Initialize the MoveGroup\n",
+                "group = MoveGroupCommander('panda_arm')\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Mit group.get_current_pose() fragt man in MoveIt die aktuelle Pose des Endeffektors ab. Die Methode gibt ein PoseStamped-Objekt zurück, dessen Eigenschaft pose die eigentliche Geometrie (Position und Orientierung) enthält"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3",
+                    "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",
+                "# Get the current pose of the end-effector\n",
+                "current_pose = group.get_current_pose().pose\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Füge alle Wegpunkte, die der Roboterarm ablaufen soll der hier definierten liste waypoints hinzu."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Define the waypoints\n",
+                "waypoints = []\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Nun soll der erste Wegpunkt definiert werden. Erstelle also ein neues Objekt von der Klasse pose.\n",
+                "\n",
+                "Für den ersten Wegpunkt soll sich der Roboterarm um 10 cm (0.1) entlang der X - Achse bewegen, wobei die y - Koordinate und z - Koordinate, sowie die Orientierung unverändert bleiben soll.\n",
+                "\n",
+                "Füge diesen Wegpunt am Ende der liste waypoints hinzu.\n",
+                "\n",
+                "Tipp : setze diese mithilfe der current pose um"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5",
+                    "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",
+                "waypoint_1 = Pose()\n",
+                "waypoint_1.position.x = current_pose.position.x + 0.1\n",
+                "waypoint_1.position.y = current_pose.position.y\n",
+                "waypoint_1.position.z = current_pose.position.z\n",
+                "waypoint_1.orientation = current_pose.orientation\n",
+                "waypoints.append(waypoint_1)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Erzeuge als nächstes einen zweiten Wegpunkt , ebenfalls vom Typ Pose.\n",
+                "\n",
+                "Halte hier nun die X- und Z-Positionen aus dem ersten Wegpunkt bei und verschiebe die Y-Position um 0,2 (20 cm).\n",
+                "Wieder gilt, dass die Orientierung aus der current_pose übernommen werden soll.\n",
+                "\n",
+                "Füge zuletzt den neuen Wegpunkt zur waypoints-Liste hinzu."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6",
+                    "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",
+                "waypoint_2 = Pose()\n",
+                "waypoint_2.position.x = waypoint_1.position.x\n",
+                "waypoint_2.position.y = waypoint_1.position.y + 0.2\n",
+                "waypoint_2.position.z = waypoint_1.position.z\n",
+                "waypoint_2.orientation = current_pose.orientation\n",
+                "waypoints.append(waypoint_2)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Der letzte Wegpunkt soll auch wieder vom Typ Pose sein.\n",
+                "\n",
+                "Halte hier die X- und Y-Positionen aus dem zweiten Wegpunkt bei und verschiebe die Z-Position um 0,4 (40 cm) nach oben.\n",
+                "Ãœbernimm die Orientierung aus der current_pose.\n",
+                "\n",
+                "Füge den neuen Wegpunkt zur waypoints-Liste hinzu."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7",
+                    "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",
+                "waypoint_3 = Pose()\n",
+                "waypoint_3.position.x = waypoint_2.position.x\n",
+                "waypoint_3.position.y = waypoint_2.position.y\n",
+                "waypoint_3.position.z = waypoint_2.position.z + 0.4\n",
+                "waypoint_3.orientation = current_pose.orientation\n",
+                "waypoints.append(waypoint_3)\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Nun werden Parameter definiert, welche die folgende Bedeutung haben :\n",
+                "\n",
+                "fraction = 0.0, setzt den initialen Wert des berechneten Pfadanteils auf 0,\n",
+                "\n",
+                "max_attempts = 100, legt die maximale Anzahl der Versuche fest, um den Pfad zu berechnen,\n",
+                "\n",
+                "attempts = 0, zählt die Anzahl der Versuche."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_8"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Compute the Cartesian path\n",
+                "fraction = 0.0\n",
+                "max_attempts = 100\n",
+                "attempts = 0\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Erstelle eine Schleife, die läuft, solange der berechnete Pfadanteil (fraction) kleiner als 1.0 ist und die Anzahl der Versuche (attempts) kleiner als max_attempts ist.\n",
+                "\n",
+                "Innerhalb der Schleife, berechne den kartesischen Pfad basierend auf den angegebenen Wegpunkten (waypoints). Verwende 0.01 als Schrittabstand des Endeffektors und 0.0 als Sprungschwellenwert. Die Methode gibt einen Bewegungsplan (plan) und den berechneten Pfadanteil (fraction) zurück.\n",
+                "\n",
+                "Erhöhe am Ende innerhalb der Schleife die Anzahl der Versuche um 1."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_9",
+                    "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",
+                "while fraction < 1.0 and attempts < max_attempts:\n",
+                "    (plan, fraction) = group.compute_cartesian_path(waypoints, 0.01, 0.0)  # Plan the trajectory\n",
+                "    attempts += 1\n",
+                "\n",
+                "## ↑↑↑↑ SOLUTION CODE HERE ↑↑↑↑ ##"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Mithilfe der Methode execute wird nun der erstellte plan ausgeführt."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_10"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "if fraction == 1.0:\n",
+                "    rospy.loginfo(\"Successfully computed the Cartesian path. Executing...\")\n",
+                "    group.execute(plan, wait=True)\n",
+                "    rospy.loginfo(\"Execution completed.\")\n",
+                "else:\n",
+                "    rospy.logwarn(f\"Failed to compute a complete path after {attempts} attempts.\")\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_11"
+                ]
+            },
+            "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