diff --git a/catkin_ws/.catkin_workspace b/catkin_ws/.catkin_workspace
new file mode 100644
index 0000000000000000000000000000000000000000..52fd97e7ea4bd421af3f7dacb539d241bcee6583
--- /dev/null
+++ b/catkin_ws/.catkin_workspace
@@ -0,0 +1 @@
+# This file currently only serves to mark the location of a catkin workspace for tool integration
diff --git a/catkin_ws/src/CMakeLists.txt b/catkin_ws/src/CMakeLists.txt
new file mode 120000
index 0000000000000000000000000000000000000000..20168168606294577155b02b7fd1000947532faf
--- /dev/null
+++ b/catkin_ws/src/CMakeLists.txt
@@ -0,0 +1 @@
+/opt/ros/noetic/share/catkin/cmake/toplevel.cmake
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/tasks/beginner/exercise_4/exercise_4_1.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_4/exercise_4_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..635abaa366a85a9879f7dd068c08a43f3366d0d3
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_4/exercise_4_1.ipynb
@@ -0,0 +1,222 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck\n",
+                "\n",
+                "### Exercise_4_1 :"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "---\n",
+                ">\n",
+                "The goal of this notebook is: \n",
+                "- understand what planning algorithms are\n",
+                "- what types there are\n",
+                "- how to implement them in code\n",
+                ">\n",
+                "---\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Introduction planning algorithms\n",
+                "\n",
+                "#### What are planning algorithms?\n",
+                "\n",
+                "- Methods used to calculate a sequence of movements or actions that the robot must perform in order to reach a target (e.g. a final position)\n",
+                "- help solve complex problems, such as overcoming obstacles, precise reaching of endpoint\n",
+                "- ensure that movement is efficient, collision-free and physically possible\n",
+                "\n",
+                "#### What types of planning algorithms are there ?\n",
+                "\n",
+                "Sampling-based algorithms\n",
+                "\n",
+                "- create random sample to find way from start to finish\n",
+                "- Examples: RTT, RTTConnect\n",
+                "\n",
+                "##### Search-based algorithms\n",
+                "\n",
+                "- use grids or graphs to calculate shortest path\n",
+                "- Example: A*\n",
+                "\n",
+                "##### Optimization based algorithms\n",
+                "\n",
+                "- improve existing paths through optimization criteria, such as efficiency\n",
+                "- Examples: CHOMP, STOMP"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First, we import all the important modules for this task. You already know Rospy and sys from previous tasks.\n",
+                "The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements.\n",
+                "roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API.\n",
+                "geometry_msgs.msg is used to provide standardized message formats such as position(pose) and orientation (point) of the robotic arm."
+            ]
+        },
+        {
+            "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",
+                "# Initialize the MoveIt Commander\n",
+                "roscpp_initialize(sys.argv)\n",
+                "\n",
+                "# Initialize the ROS Node\n",
+                "rospy.init_node('exercise_4_1', anonymous=True)\n",
+                "\n",
+                "# Initialize MoveGroupCommander\n",
+                "group = MoveGroupCommander('panda_arm')\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we want to select the planning algorithm we want to use to calculate the motion. To do this, we use the set_planner_id method to select the specific planning algorithm."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Select the desired planning algorithm\n",
+                "group.set_planner_id(\"RRTConnectkConfigDefault\")"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we define the target position of the end effector. The end effector is the part of a robot arm that is attached to the extreme end of the kinematic chain and directly interacts with the environment. It is the functional \"tool holder\" of the robot, whose job it is to perform specific actions. These actions depend heavily on the task of the robot.\n",
+                "\n",
+                "The pose class provides a data structure that describes the spatial position and orientation of an object in 3D space. The position contains the x-, y- and z-coordinates, which in the following code defines the target position of the end effector in Cartesian space (in meters).\n",
+                "The orientation w describes the orientation, which is used for orientation in 3D space.\n",
+                "\n",
+                "A w=cos(θ/2) that is less than 1 indicates that a rotation is taking place.\n",
+                "The rotation angle θ can be calculated via arccos(w)⋆2.\n",
+                "\n",
+                "w should always be in the range [−1.1] because it is related to cos(θ/2). Values outside this range result in invalid quaternions."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "target_pose = Pose()\n",
+                "target_pose.position.x = 0.1\n",
+                "target_pose.position.y = 0.1\n",
+                "target_pose.position.z = 0.1\n",
+                "target_pose.orientation.w = 1.0"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now it's about planning and executing the movement of the robotic arm.\n",
+                "\n",
+                "The group.go() method executes the planned movement of the robot based on the target pose that was previously set.\n",
+                "\n",
+                "The wait=True argument means that further execution of the code is blocked (i.e. waits) until the movement is complete. Only after the movement is completed will the next command be executed.\n",
+                "\n",
+                "The group.stop() method stops the movement of the robot immediately.\n",
+                "Even if the movement is already complete, this command ensures that no further movements or residual movements (e.g. by inertia or revival) take place.\n",
+                "\n",
+                "The group.clear_pose_targets() method removes all pose targets previously defined for the robot.\n",
+                "\n",
+                "This is very important because target positions that are not removed remain in the memory of the MoveIt object (group) and could be reused inadvertently in later move commands."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "plan = group.go(wait=True)\n",
+                "group.stop()\n",
+                "group.clear_pose_targets()\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_5"
+                ]
+            },
+            "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/beginner/exercise_4/exercise_4_2.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_4/exercise_4_2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..7d3a7940a090cebbc778ec04916b2c4c2d59c9dc
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_4/exercise_4_2.ipynb
@@ -0,0 +1,194 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck\n",
+                "\n",
+                "### Exercise_4_2 :"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "---\n",
+                "> \n",
+                "The goal of this notebook is: \n",
+                "- query and interpret the status of the Franka Emika Panda robotic arm. \n",
+                "- check the current state of the robot (positions, orientations, > joint angle) and understand how to access feedback during or after a movement.\n",
+                ">\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First, we import all the important modules for this task. You already know Rospy and sys from previous tasks.\n",
+                "The MoveGroupCommander allows interaction with MoveIt! via the Python API, so you can then control the robot arm, plan and execute movements.\n",
+                "roscpp_initialize and roscpp_shutdown allow initialization and termination of communication with ROS from the MoveIt API."
+            ]
+        },
+        {
+            "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",
+                "\n",
+                "# Initialize the MoveIt Commander\n",
+                "roscpp_initialize(sys.argv)\n",
+                "\n",
+                "# Initialize the ROS Node\n",
+                "rospy.init_node('exercise_4_2', anonymous=True)\n",
+                "\n",
+                "##### DO NOT CHANGE #####\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now the MoveGroup for the robot arm `panda_arm` is initialized.\n",
+                "In addition, planning parameters such as the planning algorithm and the number of planning attempts are defined."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Initialize the MoveGroup\n",
+                "group = MoveGroupCommander('panda_arm')\n",
+                "\n",
+                "# Set the planner ID to 'RRTConnectkConfigDefault'\n",
+                "group.set_planner_id(\"RRTConnectkConfigDefault\")\n",
+                "\n",
+                "# Set the number of planning attempts to 10\n",
+                "group.set_num_planning_attempts(10)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Query of current joint angles\n",
+                "Next, the current joint angles of the robot arm are queried and output in the log. The MoveGroupCommander class provides the get_current_joint_values() method.\n",
+                "\n",
+                "This harvests the current values of the joint angles and returns them as a list. The i-th entry in the list contains the angle of the i-th joint of the robot arm.\n"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Query the current joint values\n",
+                "joint_values = group.get_current_joint_values() \n",
+                "rospy.loginfo(\"Current Joint Values: \")\n",
+                "for i, joint in enumerate(joint_values):\n",
+                "    rospy.loginfo(f\"Joint {i+1}: {joint:.2f} rad\")"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Query the current end effector position\n",
+                "In the next step, the current pose of the end effector is queried and output in the log. The MoveGroupCommander class provides the get_current_pose() method. This method is used to determine the position and orientation of the end effector's space relative to a defined frame of reference.\n",
+                "\n",
+                "The get_current_pose() method returns a message of the type PoseStamped. This contains the position as x -, y - and z - coordinates of the end effector, the orientation describes the orientation of the end effector given as quaternion (x, y, z, w) and much more information.\n",
+                "\n",
+                ".pose is used to access the Pose attribute, which contains only the information about the position and orientation of the end effector. This attribute is of the Pose type."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Query the current end-effector pose\n",
+                "pose = group.get_current_pose().pose\n",
+                "rospy.loginfo(f\"Endeffector Position: x={pose.position.x:.3f}, y={pose.position.y:.3f}, z={pose.position.z:.3f}\")\n",
+                "rospy.loginfo(f\"Endeffector Orientation: x={pose.orientation.x:.3f}, y={pose.orientation.y:.3f}, z={pose.orientation.z:.3f}, w={pose.orientation.w:.3f}\")\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The pose of the end effector is crucial to check the current condition of the robotic arm.\n",
+                "\n",
+                "The position is needed to ensure that the end effector is in the right place in the room.\n",
+                "\n",
+                "The orientation is essential when the end effector has to act in a certain orientation, e.g. to grasp an object correctly."
+            ]
+        },
+        {
+            "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_5"
+                ]
+            },
+            "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/beginner/exercise_5/exercise_5_1.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..63e15e77a574d5e88baffdf55183a9f01d08f109
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_1.ipynb
@@ -0,0 +1,316 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck\n",
+                "\n",
+                "### Exercise_5_1 :\n",
+                "\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "---\n",
+                ">\n",
+                "The goal of this notebook is:\n",
+                "- to understand how to create objects\n",
+                "- and how to add them to the scene\n",
+                ">\n",
+                "---\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The class PoseStamped extends the class PoseStamped, already known in Exercise_4_1, and is thus used to capture position and orientation and to associate them with a point in time, i.e. at which point in time the pose was captured.\n",
+                "\n",
+                "The PlanningSceneInterface is responsible for managing the planning scene, i.e. the environment in which the robot works. This environment contains all the obstacles and objects that need to be taken into account when planning movement."
+            ]
+        },
+        {
+            "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 geometry_msgs.msg import PoseStamped\n",
+                "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now ROS and MoveIt will be initialized again, as well as here the new planning scene."
+            ]
+        },
+        {
+            "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_5_1', anonymous=True)\n",
+                "\n",
+                "# Initialize PlanningScene\n",
+                "scene = PlanningSceneInterface()\n",
+                "rospy.sleep(1)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "This section defines the pose of an object, which is later added to the planning environment. To do this, an object of the class PoseStamped, which describes a combination of spatial position and orientation within a specific coordinate frame, is created. \n",
+                "\n",
+                "This object contains two main components:\n",
+                " - header: information about the coordinate frame and time stamp.\n",
+                " - pose: The actual position (translation) and orientation (rotation) of the object.\n",
+                "\n",
+                "Now the frame_id is set in the header of the PoseStamped-object.\n",
+                "\"panda_link0\" is the base frame of the robotic arm. All position and orientation information refers to this coordinate frame."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "box_pose = PoseStamped()\n",
+                "box_pose.header.frame_id = \"panda_link0\"\n",
+                "box_pose.pose.position.x = 0.4\n",
+                "box_pose.pose.position.y = 0.0\n",
+                "box_pose.pose.position.z = 0.1\n",
+                "box_pose.pose.orientation.w = 1.0\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "In the next section, a cube object is added to the planning environment. The PlanningSceneInterface class provides the add_box() method, which adds the object (a cube, i.e. 3-dimensional rectangular object) based on the previously defined position and orientation data of the scene.\n",
+                "\n",
+                "The add_box(name, pose, size) method must be given the following arguments :\n",
+                " - name (type : string): a string that describes the name of the object to be added\n",
+                " - pose (type: PoseStamped): the pose of the object, which consists of position and orientation\n",
+                " - size (type : tuple): a tuple describing the size of the box"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# adding a 5cmx5cmx5cm cube\n",
+                "scene.add_box(\"box_1\", box_pose, size=(0.05, 0.05, 0.05))\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Exercise 1:\n",
+                "\n",
+                " Creates a cube on the coordinates (1.0,1.0,1.0), no rotation and with the side length 10cm and adds it to the planning scene.\n",
+                "Give it a name: box_2.\n",
+                "\n",
+                "Proceed as follows:"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Create a new PoseStamped object and define the coordinates of the new object."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### WRITE YOUR CODE HERE #####\n",
+                "\n",
+                "box_pose_2 = PoseStamped()\n",
+                "box_pose_2.header.frame_id = \"panda_link0\"\n",
+                "box_pose_2.pose.position.x = 1.0\n",
+                "box_pose_2.pose.position.y = 1.0\n",
+                "box_pose_2.pose.position.z = 1.0\n",
+                "box_pose_2.pose.orientation.w = 1.0\n",
+                "\n",
+                "##### WRITE YOUR CODE HERE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now add the object with the specified dimensions of the scene."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### WRITE 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 #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Exercise 2:\n",
+                "Created a cylinder with radius 20 cm, height 1 m, which has the x coordinate 2, y coordinate 0 and z coordinate 4 and which is rotated by 90 degrees about the y axis."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### WRITE YOUR CODE HERE #####\n",
+                "\n",
+                "cylinder_pose = PoseStamped()\n",
+                "cylinder_pose.header.frame_id = \"panda_link0\"\n",
+                "cylinder_pose.pose.position.x = 2.0\n",
+                "cylinder_pose.pose.position.y = 0.0\n",
+                "cylinder_pose.pose.position.z = 4.0\n",
+                "\n",
+                "cylinder_pose.pose.orientation.x = 0.0\n",
+                "cylinder_pose.pose.orientation.y = 0.7071\n",
+                "cylinder_pose.pose.orientation.z = 0.0\n",
+                "cylinder_pose.pose.orientation.w = 0.7071\n",
+                "\n",
+                "radius = 0.2\n",
+                "height = 1.0\n",
+                "\n",
+                "##### WRITE YOUR CODE HERE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now add the cylinder with the defined coordinates and orientation to the scene."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_8"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### WRITE YOUR CODE HERE #####\n",
+                "\n",
+                "scene.add_cylinder(\"cylinder\", cylinder_pose, height=height, radius=radius)\n",
+                "\n",
+                "##### WRITE 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": {
+                "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/beginner/exercise_5/exercise_5_2.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..c5a77ef6acbf50fa9bdb4c9db6b9e404b3bc481d
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_2.ipynb
@@ -0,0 +1,170 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Exercise_5_2\n",
+                "\n",
+                "---\n",
+                "> \n",
+                "The goal of this notebook is:\n",
+                "- to understand how to remove objects from a scene\n",
+                "- to check which objects are currently in the scene\n",
+                "> \n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "We import the same packages we did in the previous task."
+            ]
+        },
+        {
+            "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 geometry_msgs.msg import PoseStamped\n",
+                "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now ROS, MoveIt and the PlanningScene will be initialized."
+            ]
+        },
+        {
+            "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_5_1', anonymous=True)\n",
+                "\n",
+                "# Initialize PlanningScene\n",
+                "scene = PlanningSceneInterface()\n",
+                "rospy.sleep(1)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now remove the two objects added in the previous task of the scene. This is possible using the method provided by the PlanningSceneInterface class, remove_world_object(name), where name is the sting name of the object to be removed.\n",
+                "\n",
+                "You can also remove all objects in the scene at once by calling remove_world_object() without parameter."
+            ]
+        },
+        {
+            "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 check that all objects have been removed from the scene. This is where the get_known_object_names() method, which is also provided by the PlanningSceneInterface class, comes in handy. This method returns a list of strings, with each string representing the name of a known object in the scene."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### WRITE YOUR CODE HERE #####\n",
+                "\n",
+                "object_names = scene.get_known_object_names()\n",
+                "rospy.loginfo(len(object_names) == 0)\n",
+                "\n",
+                "##### WRITE 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": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "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/beginner/exercise_5/exercise_5_3.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_3.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..65a336a266e193c5701600dbb0266161904ccd96
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_5/exercise_5_3.ipynb
@@ -0,0 +1,291 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck\n",
+                "\n",
+                "### Exercise_5_3 :"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "---\n",
+                ">\n",
+                "The goal of this notebook is:\n",
+                "- get to know new classes for creating objects\n",
+                "- Stacking objects on top of each other\n",
+                ">\n",
+                "---\n"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First, all necessary packages are imported.\n",
+                "\n",
+                "The SolidPrimitive class offers the ability to create simple geometric objects, such as boxes, cylinders and cones. It has the two attributes Type, which determine the type of object (e.g. BOX, CYLINDER) and Dimension, which determine the size of the object.\n",
+                "\n",
+                "The CollisionObject class is used to describe the position and orientation of the object and is used to define obstacles and objects in the scene that are taken into account in the collision check."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import sys\n",
+                "import rospy\n",
+                "from moveit_commander import roscpp_initialize, roscpp_shutdown, PlanningSceneInterface\n",
+                "from moveit_msgs.msg import CollisionObject\n",
+                "from shape_msgs.msg import SolidPrimitive\n",
+                "from geometry_msgs.msg import Pose\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now you initialize the ROS node, MoveIt Commander and the PlanningSceneInterface."
+            ]
+        },
+        {
+            "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_5_2', anonymous=True)\n",
+                "\n",
+                "# Initialize the PlanningSceneInterface\n",
+                "planning_scene_interface = PlanningSceneInterface()\n",
+                "\n",
+                "# Wait for the planning scene interface to initialize\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now create the first object, a rectangle with the following attributes :\n",
+                "\n",
+                "Size:\n",
+                "- width 20 cm\n",
+                "- Length 40 cm\n",
+                "- Height 40 cm\n",
+                "\n",
+                "Coordinates:\n",
+                "- (0.5, 0.0, 0.2)\n",
+                "\n",
+                "Directions:\n",
+                "- Neutral\n",
+                "\n",
+                "Important : this one has the id : rectangle_1"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# rectangle_1\n",
+                "rectangle_1 = CollisionObject()\n",
+                "rectangle_1.id = \"rectangle_1\"\n",
+                "rectangle_1.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "primitive1 = SolidPrimitive()\n",
+                "primitive1.type = SolidPrimitive.BOX\n",
+                "primitive1.dimensions = [0.2, 0.4, 0.4]\n",
+                "\n",
+                "rectangle_1.primitives.append(primitive1)\n",
+                "\n",
+                "pose1 = Pose()\n",
+                "pose1.position.x = 0.5\n",
+                "pose1.position.y = 0.0\n",
+                "pose1.position.z = 0.2\n",
+                "pose1.orientation.w = 1.0\n",
+                "\n",
+                "rectangle_1.primitive_poses.append(pose1)\n",
+                "rectangle_1.operation = CollisionObject.ADD\n",
+                "\n",
+                "# add rectangle_1 to the planning scene\n",
+                "planning_scene_interface.add_object(rectangle_1)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, create the second rectangle, with the same attributes as the first:\n",
+                "\n",
+                "Size:\n",
+                "- width 20 cm\n",
+                "- Length 40 cm\n",
+                "- Height 40 cm\n",
+                "\n",
+                "Coordinates:\n",
+                "- (0.5, 0.0, 0.2)\n",
+                "\n",
+                "Directions:\n",
+                "- Neutral\n",
+                "\n",
+                "Important : this one has the id : rectangle_2"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# rectangle_2\n",
+                "rectangle_2 = CollisionObject()\n",
+                "rectangle_2.id = \"rectangle_2\"\n",
+                "rectangle_2.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "primitive2 = SolidPrimitive()\n",
+                "primitive2.type = SolidPrimitive.BOX\n",
+                "primitive2.dimensions = [0.4, 0.2, 0.4]\n",
+                "\n",
+                "rectangle_2.primitives.append(primitive2)\n",
+                "\n",
+                "pose2 = Pose()\n",
+                "pose2.position.x = 0.0\n",
+                "pose2.position.y = 0.5\n",
+                "pose2.position.z = 0.2\n",
+                "pose2.orientation.w = 1.0\n",
+                "\n",
+                "rectangle_2.primitive_poses.append(pose2)\n",
+                "rectangle_2.operation = CollisionObject.ADD\n",
+                "\n",
+                "# add rectangle_2 to the planning scene\n",
+                "planning_scene_interface.add_object(rectangle_2)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Finally, create a rod which is placed on one of the rectangles and which has the following attributes:\n",
+                "\n",
+                "Size:\n",
+                "- width 2 cm\n",
+                "- Length 2 cm\n",
+                "- height 20 cm\n",
+                "\n",
+                "Coordinates:\n",
+                "- (0.5, 0.0, 0.5)\n",
+                "\n",
+                "Directions:\n",
+                "- Neutral\n",
+                "\n",
+                "Important : this one has the id : target"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# target_object\n",
+                "target_object = CollisionObject()\n",
+                "target_object.id = \"target\"\n",
+                "target_object.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "primitive3 = SolidPrimitive()\n",
+                "primitive3.type = SolidPrimitive.BOX\n",
+                "primitive3.dimensions = [0.02, 0.02, 0.2]\n",
+                "\n",
+                "target_object.primitives.append(primitive3)\n",
+                "\n",
+                "pose3 = Pose()\n",
+                "pose3.position.x = 0.5\n",
+                "pose3.position.y = 0.0\n",
+                "pose3.position.z = 0.5\n",
+                "pose3.orientation.w = 1.0\n",
+                "\n",
+                "target_object.primitive_poses.append(pose3)\n",
+                "target_object.operation = CollisionObject.ADD\n",
+                "\n",
+                "# add target_object to the planning scene\n",
+                "planning_scene_interface.add_object(target_object)"
+            ]
+        },
+        {
+            "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": [
+                "##### 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/beginner/exercise_6/exercise_6_1.ipynb b/catkin_ws/src/learn_environment/tasks/beginner/exercise_6/exercise_6_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..2f2144846abc90d7261f064474266b16c8989600
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/beginner/exercise_6/exercise_6_1.ipynb
@@ -0,0 +1,262 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Franka Emika Panda robot arm\n",
+                "\n",
+                "Author: uninh, uqwfa, ultck\n",
+                "\n",
+                "### Exercise_6_1 :"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "---\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",
+                "arm_group = MoveGroupCommander('panda_arm')\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Todo : Beschreibung"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "# Get the current pose of the end-effector\n",
+                "current_pose = arm_group.get_current_pose().pose\n",
+                "\n",
+                "# Define the waypoints\n",
+                "waypoints = []\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Todo : Beschreibung"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Waypoint 1: Slightly move along the X-axis\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)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Todo : Beschreibung"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Waypoint 2: Move along the Y-axis\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.z = waypoint_1.position.z\n",
+                "waypoint_2.orientation = current_pose.orientation\n",
+                "waypoints.append(waypoint_2)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Todo : Beschreibung"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Waypoint 3: Move upwards along the Z-axis\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.orientation = current_pose.orientation\n",
+                "waypoints.append(waypoint_3)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Todo : Beschreibung"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "# Compute the Cartesian path\n",
+                "fraction = 0.0\n",
+                "max_attempts = 100\n",
+                "attempts = 0\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",
+                "    attempts += 1\n",
+                "\n",
+                "if fraction == 1.0:\n",
+                "    rospy.loginfo(\"Successfully computed the Cartesian path. Executing...\")\n",
+                "    arm_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.\")"
+            ]
+        },
+        {
+            "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_8"
+                ]
+            },
+            "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/trajectory_controller.ipynb b/catkin_ws/src/learn_environment/tasks/controller/controller_task/trajectory_controller.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..608d157f46d8d3af36bd1b7d9b1d2e14383b2254
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/controller/controller_task/trajectory_controller.ipynb
@@ -0,0 +1,73 @@
+{
+    "cells": [
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ],
+                "vscode": {
+                    "languageId": "plaintext"
+                }
+            },
+            "outputs": [],
+            "source": [
+                "#!/usr/bin/env python\n",
+                "\n",
+                "import rospy\n",
+                "from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal\n",
+                "from trajectory_msgs.msg import JointTrajectoryPoint\n",
+                "import actionlib\n",
+                "\n",
+                "# ROS-Knoten initialisieren\n",
+                "rospy.init_node(\"position_controller_example\", anonymous=True)\n",
+                "\n",
+                "# Verbindung mit dem Trajectory Controller herstellen\n",
+                "# Der Code verwendet den ROS-Action-Server /panda_arm_controller/follow_joint_trajectory, um Gelenkpositionen anzusteuern.\n",
+                "# Diese Schnittstelle basiert auf dem Trajectory Controller, der für die präzise Steuerung von Gelenkbewegungen zuständig ist.\n",
+                "\n",
+                "client = actionlib.SimpleActionClient('/panda_arm_controller/follow_joint_trajectory', FollowJointTrajectoryAction)\n",
+                "rospy.loginfo(\"Waiting for trajectory controller...\")\n",
+                "client.wait_for_server()\n",
+                "rospy.loginfo(\"Connected to trajectory controller!\")\n",
+                "\n",
+                "# Zielgelenkpositionen definieren\n",
+                "joint_goal = [0.0, -0.785, 0.0, -2.356, 0.0, 1.57, 0.785]\n",
+                "\n",
+                "# Trajektorie erstellen\n",
+                "goal = FollowJointTrajectoryGoal()\n",
+                "goal.trajectory.joint_names = [\n",
+                "    \"panda_joint1\", \"panda_joint2\", \"panda_joint3\",\n",
+                "    \"panda_joint4\", \"panda_joint5\", \"panda_joint6\", \"panda_joint7\"\n",
+                "]\n",
+                "\n",
+                "point = JointTrajectoryPoint()\n",
+                "point.positions = joint_goal\n",
+                "point.time_from_start = rospy.Duration(5.0)  # Die Bewegung soll in 5 Sekunden abgeschlossen sein\n",
+                "\n",
+                "goal.trajectory.points.append(point)\n",
+                "goal.trajectory.header.stamp = rospy.Time.now()\n",
+                "\n",
+                "# Ziel senden\n",
+                "rospy.loginfo(\"Sending goal to trajectory controller...\")\n",
+                "client.send_goal(goal)\n",
+                "client.wait_for_result()\n",
+                "\n",
+                "# Ergebnis überprüfen\n",
+                "result = client.get_result()\n",
+                "if result:\n",
+                "    rospy.loginfo(\"Trajectory successfully executed!\")\n",
+                "else:\n",
+                "    rospy.logwarn(\"Failed to execute trajectory.\")"
+            ]
+        }
+    ],
+    "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/intermediate/exercise_1/exercise_1_1.ipynb b/catkin_ws/src/learn_environment/tasks/intermediate/exercise_1/exercise_1_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..6733d7a51dff8427ab8d1bd1f03f0bd132393a20
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/intermediate/exercise_1/exercise_1_1.ipynb
@@ -0,0 +1,215 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "TODO: FORMAT AS NOTEBOOK"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ],
+                "vscode": {
+                    "languageId": "plaintext"
+                }
+            },
+            "outputs": [],
+            "source": [
+                "import rospy\n",
+                "from moveit_commander import PlanningSceneInterface, MoveGroupCommander\n",
+                "from moveit_msgs.msg import Grasp, PlaceLocation, CollisionObject\n",
+                "from geometry_msgs.msg import PoseStamped, Pose\n",
+                "from tf.transformations import quaternion_from_euler\n",
+                "from shape_msgs.msg import SolidPrimitive\n",
+                "import moveit_msgs\n",
+                "import shape_msgs\n",
+                "import geometry_msgs\n",
+                "import trajectory_msgs\n",
+                "\n",
+                "def create_collision_objects(planning_scene_interface):\n",
+                "    # Tabelle 1\n",
+                "    table1 = moveit_msgs.msg.CollisionObject()\n",
+                "    table1.id = \"table1\"\n",
+                "    table1.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "    primitive1 = shape_msgs.msg.SolidPrimitive()\n",
+                "    primitive1.type = shape_msgs.msg.SolidPrimitive.BOX\n",
+                "    primitive1.dimensions = [0.2, 0.4, 0.4]  # Länge, Breite, Höhe\n",
+                "\n",
+                "    table1.primitives.append(primitive1)\n",
+                "\n",
+                "    pose1 = geometry_msgs.msg.Pose()\n",
+                "    pose1.position.x = 0.5\n",
+                "    pose1.position.y = 0.0\n",
+                "    pose1.position.z = 0.2\n",
+                "    pose1.orientation.w = 1.0\n",
+                "\n",
+                "    table1.primitive_poses.append(pose1)\n",
+                "    table1.operation = moveit_msgs.msg.CollisionObject.ADD\n",
+                "\n",
+                "    # Füge Tabelle 1 hinzu\n",
+                "    planning_scene_interface.add_object(table1)\n",
+                "\n",
+                "    # Tabelle 2\n",
+                "    table2 = moveit_msgs.msg.CollisionObject()\n",
+                "    table2.id = \"table2\"\n",
+                "    table2.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "    primitive2 = shape_msgs.msg.SolidPrimitive()\n",
+                "    primitive2.type = shape_msgs.msg.SolidPrimitive.BOX\n",
+                "    primitive2.dimensions = [0.4, 0.2, 0.4]\n",
+                "\n",
+                "    table2.primitives.append(primitive2)\n",
+                "\n",
+                "    pose2 = geometry_msgs.msg.Pose()\n",
+                "    pose2.position.x = 0.0\n",
+                "    pose2.position.y = 0.5\n",
+                "    pose2.position.z = 0.2\n",
+                "    pose2.orientation.w = 1.0\n",
+                "\n",
+                "    table2.primitive_poses.append(pose2)\n",
+                "    table2.operation = moveit_msgs.msg.CollisionObject.ADD\n",
+                "\n",
+                "    # Füge Tabelle 2 hinzu\n",
+                "    planning_scene_interface.add_object(table2)\n",
+                "\n",
+                "    # Zielobjekt\n",
+                "    target_object = moveit_msgs.msg.CollisionObject()\n",
+                "    target_object.id = \"object\"\n",
+                "    target_object.header.frame_id = \"panda_link0\"\n",
+                "\n",
+                "    primitive3 = shape_msgs.msg.SolidPrimitive()\n",
+                "    primitive3.type = shape_msgs.msg.SolidPrimitive.BOX\n",
+                "    primitive3.dimensions = [0.02, 0.02, 0.2]\n",
+                "\n",
+                "    target_object.primitives.append(primitive3)\n",
+                "\n",
+                "    pose3 = geometry_msgs.msg.Pose()\n",
+                "    pose3.position.x = 0.5\n",
+                "    pose3.position.y = 0.0\n",
+                "    pose3.position.z = 0.5\n",
+                "    pose3.orientation.w = 1.0\n",
+                "\n",
+                "    target_object.primitive_poses.append(pose3)\n",
+                "    target_object.operation = moveit_msgs.msg.CollisionObject.ADD\n",
+                "\n",
+                "    # Füge Zielobjekt hinzu\n",
+                "    planning_scene_interface.add_object(target_object)\n",
+                "\n",
+                "def open_gripper():\n",
+                "    \"\"\"Define the gripper open position.\"\"\"\n",
+                "    posture = {\"joint_names\": [\"panda_finger_joint1\", \"panda_finger_joint2\"],\n",
+                "               \"points\": [{\"positions\": [0.04, 0.04], \"time_from_start\": rospy.Duration(0.5)}]}\n",
+                "    return posture\n",
+                "\n",
+                "def close_gripper():\n",
+                "    \"\"\"Define the gripper closed position.\"\"\"\n",
+                "    posture = {\"joint_names\": [\"panda_finger_joint1\", \"panda_finger_joint2\"],\n",
+                "               \"points\": [{\"positions\": [0.0, 0.0], \"time_from_start\": rospy.Duration(0.5)}]}\n",
+                "    return posture\n",
+                "\n",
+                "def pick(move_group):\n",
+                "    # Erstelle ein Grasp-Objekt\n",
+                "    grasp = moveit_msgs.msg.Grasp()\n",
+                "\n",
+                "    # Grasp Pose: Wo der Roboter das Objekt greifen soll\n",
+                "    grasp.grasp_pose.header.frame_id = \"panda_link0\"\n",
+                "    grasp.grasp_pose.pose.position.x = 0.5\n",
+                "    grasp.grasp_pose.pose.position.y = 0.0\n",
+                "    grasp.grasp_pose.pose.position.z = 0.5\n",
+                "    grasp.grasp_pose.pose.orientation.w = 1.0\n",
+                "\n",
+                "    # Pre-Grasp Approach: Bewegung zum Greifen\n",
+                "    grasp.pre_grasp_approach.direction.header.frame_id = \"panda_link0\"\n",
+                "    grasp.pre_grasp_approach.direction.vector.z = -1.0  # Bewegung entlang der -z-Achse\n",
+                "    grasp.pre_grasp_approach.min_distance = 0.095\n",
+                "    grasp.pre_grasp_approach.desired_distance = 0.115\n",
+                "\n",
+                "    # Post-Grasp Retreat: Bewegung nach dem Greifen\n",
+                "    grasp.post_grasp_retreat.direction.header.frame_id = \"panda_link0\"\n",
+                "    grasp.post_grasp_retreat.direction.vector.z = 1.0  # Bewegung entlang der +z-Achse\n",
+                "    grasp.post_grasp_retreat.min_distance = 0.1\n",
+                "    grasp.post_grasp_retreat.desired_distance = 0.25\n",
+                "\n",
+                "    # Pre-Grasp Posture: Öffne den Greifer\n",
+                "    grasp.pre_grasp_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n",
+                "    grasp.pre_grasp_posture.points = [\n",
+                "        trajectory_msgs.msg.JointTrajectoryPoint(\n",
+                "            positions=[0.04, 0.04], time_from_start=rospy.Duration(0.5)\n",
+                "        )\n",
+                "    ]\n",
+                "\n",
+                "    # Grasp Posture: Schließe den Greifer\n",
+                "    grasp.grasp_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n",
+                "    grasp.grasp_posture.points = [\n",
+                "        trajectory_msgs.msg.JointTrajectoryPoint(\n",
+                "            positions=[0.0, 0.0], time_from_start=rospy.Duration(0.5)\n",
+                "        )\n",
+                "    ]\n",
+                "\n",
+                "    # Führe den Greifvorgang aus\n",
+                "    move_group.pick(\"object\", [grasp])\n",
+                "\n",
+                "def place(move_group):\n",
+                "    # Erstelle ein PlaceLocation-Objekt\n",
+                "    place_location = moveit_msgs.msg.PlaceLocation()\n",
+                "\n",
+                "    # Setze die Zielpose für das Platzieren\n",
+                "    place_location.place_pose.header.frame_id = \"panda_link0\"\n",
+                "    place_location.place_pose.pose.position.x = 0.0\n",
+                "    place_location.place_pose.pose.position.y = 0.5\n",
+                "    place_location.place_pose.pose.position.z = 0.5\n",
+                "    place_location.place_pose.pose.orientation.w = 1.0\n",
+                "\n",
+                "    # Pre-Place Approach: Bewegung vor dem Platzieren\n",
+                "    place_location.pre_place_approach.direction.header.frame_id = \"panda_link0\"\n",
+                "    place_location.pre_place_approach.direction.vector.z = -1.0  # Bewegung entlang der -z-Achse\n",
+                "    place_location.pre_place_approach.min_distance = 0.095\n",
+                "    place_location.pre_place_approach.desired_distance = 0.115\n",
+                "\n",
+                "    # Post-Place Retreat: Bewegung nach dem Platzieren\n",
+                "    place_location.post_place_retreat.direction.header.frame_id = \"panda_link0\"\n",
+                "    place_location.post_place_retreat.direction.vector.y = -1.0  # Bewegung entlang der -y-Achse\n",
+                "    place_location.post_place_retreat.min_distance = 0.1\n",
+                "    place_location.post_place_retreat.desired_distance = 0.25\n",
+                "\n",
+                "    # Post-Place Posture: Öffne den Greifer\n",
+                "    place_location.post_place_posture.joint_names = [\"panda_finger_joint1\", \"panda_finger_joint2\"]\n",
+                "    place_location.post_place_posture.points = [\n",
+                "        trajectory_msgs.msg.JointTrajectoryPoint(\n",
+                "            positions=[0.04, 0.04], time_from_start=rospy.Duration(0.5)\n",
+                "        )\n",
+                "    ]\n",
+                "\n",
+                "    # Führe den Platzierungsvorgang aus\n",
+                "    move_group.place(\"object\", [place_location])\n",
+                "    \n",
+                "if __name__ == \"__main__\":\n",
+                "    rospy.init_node(\"pick_place_tutorial\", anonymous=True)\n",
+                "    planning_scene_interface = PlanningSceneInterface()\n",
+                "    move_group = MoveGroupCommander(\"panda_arm\")\n",
+                "    move_group.set_planning_time(45.0)\n",
+                "\n",
+                "    create_collision_objects(planning_scene_interface)\n",
+                "    rospy.sleep(2)\n",
+                "\n",
+                "    pick(move_group)\n",
+                "    rospy.sleep(2)\n",
+                "\n",
+                "    place(move_group)"
+            ]
+        }
+    ],
+    "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/move_it/move_it_basics/move_it_basics_1.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..278819390fa843c9d95e208924671cca11949ecb
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_1.ipynb
@@ -0,0 +1,196 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## MoveIt Basics\n",
+                "### Task 1\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... what MoveIt is.\n",
+                "> - ... how to use it.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "After mastering the direct method of rotating the Panda robot’s joints using ``ROS``, it’s time to explore an easier approach. For this, we’ll use the ``MoveIt`` package. The ``MoveIt Commander`` Python package provides a straightforward interface for motion planning and Cartesian path computation. MoveIt, as a whole, is a robust framework for motion planning and robot manipulation."
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First, we need to import the required modules. We still use ``rospy`` to initialize a``ROS node``. What’s new here are ``MoveGroupCommander``, ``roscpp_initialize``, and ``roscpp_shutdown`` from the ``MoveIt Commander`` package. As the names suggest, ``roscpp_initialize`` is used to initialize, and ``roscpp_shutdown`` to shut down the ``MoveIt Commander`` within the ``ROS system``. The ``MoveGroupCommander``, on the other hand, acts as the core interface for commanding robot motion planning."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import math\n",
+                "import sys\n",
+                "\n",
+                "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The next step would be initialize roscpp and initialize a ``ROS node``."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "roscpp_initialize(sys.argv)\n",
+                "rospy.init_node('commander', anonymous=True)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we create a ``MoveGroupCommander`` instance. We configure it to use the planning algorithm ``'RRTConnectkConfigDefault'`` and set the number of planning attempts to 10 for better motion planning results."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "group = MoveGroupCommander(\"panda_arm\")\n",
+                "group.set_planner_id(\"RRTConnectkConfigDefault\")\n",
+                "group.set_num_planning_attempts(10)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now we can adjust the joint values. To do this, use the ``get_current_joint_values()`` method of the ``MoveGroupCommander`` to retrieve the current joint values, then modify the specific axes you want.\n",
+                "\n",
+                "ToDo:\n",
+                "\n",
+                "- add 50 degrees to the joint4 and store the changed values in the ``joint_goal`` variable"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "joint_goal = None\n",
+                "\n",
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "We can now set our ``joint_goal`` as the target joint values for the ``MoveGroupCommander`` by using the ``set_joint_value_target()`` method. Once the target is set, execute the movement with the ``go(wait=True)`` method."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "As always, we clean up by deleting the node and shutting down the MoveIt Commander."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\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/move_it/move_it_basics/move_it_basics_2.ipynb b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..f107543052dc0d0acfc3dc8b6fa5fec7753c96f7
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/move_it/move_it_basics/move_it_basics_2.ipynb
@@ -0,0 +1,238 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## MoveIt Basics\n",
+                "### Task 2\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... how to move the robot to a specific cartesian position.\n",
+                "> - ... how to determine the joint values that represent a Cartesian position (alternative).\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "As always, we need to start by implementing the required modules."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import sys\n",
+                "import rospy\n",
+                "\n",
+                "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n",
+                "\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we need to initialize ``roscpp``, set up a ``ROS node``, and implement a ``MoveGroupCommander`` instance.\n",
+                "\n",
+                "ToDo:\n",
+                "\n",
+                "- initialize ``roscpp`` with ``sys.argv`` as an argument\n",
+                "- initialize a ``ROS node``\n",
+                "- assign a ``MoveGroupCommander`` instace to ``group``"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "group = None\n",
+                "\n",
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "To speed up the movement with the ``MoveIt Commander``, you can adjust the ``set_max_velocity_scaling_factor()`` and ``set_max_acceleration_scaling_factor()`` of the ``MoveGroupCommander`` object. Set both to ``1``."
+            ]
+        },
+        {
+            "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": [
+                "Next, we retrieve the robot's current Cartesian pose and modify it as needed. The Cartesian coordinates ``position.x``, ``position.y``, and ``position.z`` represent the position of the ``gripper`` in 3D space, where (0, 0, 0) corresponds to the robot's base. The orientation is described by ``orientation.x``, ``orientation.y``, ``orientation.z`` and ``orientation.w``, which define the angular position of the gripper.\n",
+                "\n",
+                "- ``orientation.x``, ``orientation.y``, ``orientation.z`` represent the axis of rotation of the gripper.\n",
+                "- ``orientation.w`` represents the magnitude of the rotation about this axis.\n",
+                "\n",
+                "Since the orientation values use a ``quaternion`` representation, they must satisfy the normalization condition:\n",
+                "$$x^2 + y^2 + z^2 + w^2 = 1$$\n",
+                "\n",
+                "<img src=\"https://leimao.github.io/images/blog/2022-04-20-3D-Rotation-Unit-Quaternion/quaternion.png\" \n",
+                "     alt=\"joints of the panda robot\" width=\"200\">\n",
+                "\n",
+                "ToDo:\n",
+                "\n",
+                "- set the ``position.y`` to 0.0 and ``position.z`` to 0.2\n",
+                "- set the ``orientation -y, -z, -w`` to 0.5"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "target_pose = group.get_current_pose().pose\n",
+                "\n",
+                "target_pose.position.x = 0.5\n",
+                "target_pose.orientation.x = 0.5\n",
+                "\n",
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we aim to retrieve the joint values required to move the ``gripper`` to specific Cartesian positions. To achieve this, we use the ``plan()`` method of the ``MoveGroupCommander``. This method generates a motion plan to the defined goal state, essentially providing a sequence of joint values the robot must follow to reach the target joint state. Our focus is on extracting the last joint values in the sequence, representing the final goal corresponding to the target Cartesian position. Check the terminal to verify if the final goal joint values remain consistent for the same Cartesian position (look for the 'Output of Robot Script:' lines)."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "for i in range(5):\n",
+                "    plan = group.plan(target_pose)\n",
+                "\n",
+                "    point_list = plan[1].joint_trajectory.points\n",
+                "    last_point = point_list[-1].positions\n",
+                "\n",
+                "    rospy.loginfo(last_point)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "If done correctly, you might notice that the joint values are sometimes slightly different, and sometimes the +/ - signs are inverted. This happens because there isn’t just one correct solution. Different joint configurations can result in the same Cartesian position.\n",
+                "\n",
+                "Finally, we set the target Cartesian pose using the ``set_pose_target()`` method of the ``MoveGroupCommander`` and execute the motion with the ``go()`` method."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "group.set_pose_target(target_pose)\n",
+                "group.go(wait=True)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "At the end, we need to shut everything down."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\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/ros/ros_basics/ros_basics_1.ipynb b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..6fc4100d64f289c5a135c0fda9e1771c7bfb8a3b
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_1.ipynb
@@ -0,0 +1,189 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## ROS Basics\n",
+                "### Task 1\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... what ROS is.\n",
+                "> - ... the essential functions and classes provided by ROS.\n",
+                "> - ... how to create a simple Publisher using the ``rospy`` python API.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The ``Robot Operating System (ROS)`` is an open-source framework that simplifies the development of robot software. At its core, ``ROS`` uses:\n",
+                "\n",
+                "- ``Topics``, which are named communication channels used to exchange messages. ``Nodes`` can publish data to a ``topic`` to send data or subscribe to a ``topic`` to receive the data being published on this ``topic``.\n",
+                "- ``Nodes``, which is basically a process that performs computation, similar to an executable program running inside your application. Communicates with other ``ROS nodes`` using ``topics``.\n",
+                "- ``Messages``, which describe the data values that ``ROS nodes`` publish.\n",
+                "- ``Services``, which provides a request/ reply model. A client calls a ``service`` by sending the request message and awaiting the reply. Unlike the many-to-many communication of the publish/ subscribe model.  "
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "To use the ``ROS`` Python API, the ``rospy`` library must first be imported. Since we want to exchange regular strings later, we need to import the String message type. Additionally, the standard Python module ``time`` is used for handling time calculations."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import time\n",
+                "\n",
+                "from std_msgs.msg import String\n",
+                "\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we want to create our first ``ROS node``, which will later ``publish`` string messages to a specific ``topic`` of our choice. For this we set the name of our node to ``'publisher_node'``. The ``anonymous=True`` argument ensures that the node name is unique by appending a random number to it. "
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "rospy.init_node('publisher_node', anonymous=True)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now we want to create a ``Publisher`` that sends Strings messages to the ``'chatter'`` topic."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "pub = rospy.Publisher('/chatter', String, queue_size=10)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, we will ``publish`` the String message in a loop at a rate of 10Hz, using the ``rospy.Rate()`` method in combination with a while loop. To maintain the 10Hz loop rate, ``ROS`` provides the ``rate.sleep()`` method. For better practice, we will allow the publisher to publish messages continuously for 15 seconds.\n",
+                "\n",
+                "ToDo: \n",
+                "- Set the loop rate to 10Hz by modify the ``rate`` variable and \n",
+                "- call the ``publish()`` method of the Publisher to send the message."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "t = time.time()\n",
+                "rate = None\n",
+                "\n",
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()",
+                "\n",
+                "while not rospy.is_shutdown():\n",
+                "\n",
+                "    msg = 'Hello, ROS!'\n",
+                "\n",
+                "    ##### YOUR CODE HERE #####\n",
+                "    raise NotImplementedError()",
+                "\n",
+                "    rate.sleep()\n",
+                "\n",
+                "    if time.time() - t > 15:\n",
+                "        break"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "While ``ROS`` is running, we aim to keep the ``ROS nodes`` as clean as possible, so we will delete any ``ROS node`` that is no longer needed afterwards."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "rospy.signal_shutdown(\"Task completed.\")\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/ros/ros_basics/ros_basics_2.ipynb b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..63932ad94aa62caa0fece8381373a165d2189029
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_2.ipynb
@@ -0,0 +1,167 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## ROS Basics\n",
+                "### Task 2\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... how to create a simple ``ROS`` topic subscriber.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First we need to import the Modules."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import time\n",
+                "import sys\n",
+                "\n",
+                "from std_msgs.msg import String\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "In the background, we will have a ``ROS node`` that ``publishes`` String messages on the ``/notification`` ``topic``. First, we need to initialize the ``callback()`` method of the ``Subscriber``. If the ``Subscriber`` receives any messages on the subscribed ``topic``, it will call a method that we specify, passing the received message as an argument to this method. We want our callback method to just log the incoming data with the ``rospy.loginfo()`` method."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_2"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "def callback(msg):\n",
+                "    rospy.loginfo(\"data: \" + msg.data)\n",
+                "    sys.stdout.flush()\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now, we will specify the ``Subscriber``. First, we initialize a ``ROS node``. Then, we set the ``topic`` that the subscriber should listen to to ``/notification``. We also define the data type of the received messages as ``String`` and specify the method that the subscriber should call if data is published on this ``topic``, passing the received data as an argument. \n",
+                "\n",
+                "ToDo:\n",
+                "- initialize the ``ROS node`` with the name ``'subscriber_node'``"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()",
+                "\n",
+                "rospy.Subscriber(\"/notification\", String, callback)"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "For better practice, we will allow the ``Subscriber`` to listen continuously for 15 seconds."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "t = time.time()\n",
+                "\n",
+                "while not rospy.is_shutdown():\n",
+                "    if time.time() - t > 15:\n",
+                "        break\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "After that we delete the ``ROS node``. Now, when you execute the script, you'll observe that the ``subscriber`` collects incoming data — in this case, random integers between 1 and 100 — and prints them out."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "rospy.signal_shutdown(\"Task completed.\")\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/ros/ros_basics/ros_basics_3.ipynb b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_3.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..2f2b7481ac88d77ce86750be8d747ac67f670aeb
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/ros/ros_basics/ros_basics_3.ipynb
@@ -0,0 +1,96 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## ROS Basics\n",
+                "### Task 3\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... useful ``ROS`` command-line tools.\n",
+                "> - ... useful ``ROS topics`` for working with the Panda Robot.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Useful ROS tools"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "ROS offers users very useful command-line tools that assist in working with and debugging ROS-based systems. In this section of the exercise, we will introduce our top three command-line tools. Let’s begin with the ``rostopic`` tool, which provides several handy commands:\n",
+                "\n",
+                "- ``rostopic list``: Displays all active topics.\n",
+                "- ``rostopic echo /topic_name``: Shows messages being published to the topic.\n",
+                "- ``rostopic info /topic_name``: Prints detailed information about the topic.\n",
+                "\n",
+                "Try it yourself: list all active ``topics``, pick one, display its detailed information using ``rostopic info /topic_name``, and review the messages published to it. If you’re unsure which topic to select, try ``/franka_state_controller/franka_states``."
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The next essential command-line tool is ``rosnode``, which provides several helpful commands:\n",
+                "\n",
+                "- ``rosnode list``: Displays all active nodes.\n",
+                "- ``rosnode ping /node_name``: Tests connectivity to the node.\n",
+                "- ``rosnode info /node_name``: Prints detailed information about the node.\n",
+                "\n",
+                "Try it out yourself: list all active ``nodes``, select a ``node``, test its connectivity using ``rosnode ping /node_name``, and retrieve detailed information. A good choice might be the ``/joint_state_publisher`` node."
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Last but not least, the ``rqt_graph`` is an useful tool. It visualizes a graph of nodes and topics, making it much easier to understand the system architecture. Simply run ``rqt_graph``, and it will display the ``nodes`` along with their ``publishers`` and ``subscribers``.\n",
+                "\n",
+                "Try it out yourself."
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "### Useful ROS topics for the panda robot"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "The Panda Robot is a 7-axis robotic arm with a gripper/ finger.\n",
+                "\n",
+                "- ``/joint_states``: on this topic the current joints position, velocity and effort are published and the message type is JointState\n",
+                "- ``/franka_state_controller/franka_states ``: on this topic the pose of the end-effector (gripper) relative to the robot's base frame, robot_mode, control_mode and many more are published. It uses the message type FrankaState.\n",
+                "- ``/tf``: contains metadata that describes the translation and rotation (quaternion) between two frames\n",
+                "- etc."
+            ]
+        }
+    ],
+    "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/ros/ros_intermediate/ros_intermediate_1.ipynb b/catkin_ws/src/learn_environment/tasks/ros/ros_intermediate/ros_intermediate_1.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..4e752b0e600a66c5cda3d95428a59b2c21aea352
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/ros/ros_intermediate/ros_intermediate_1.ipynb
@@ -0,0 +1,242 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## ROS Intermediate\n",
+                "### Task 1\n",
+                "\n",
+                "---\n",
+                "> In this task, you will learn ...\n",
+                ">\n",
+                "> - ... how to rotate the joints of the robot using rostopics.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now that we understand how ``ROS`` works, let's use this knowledge to control the joints of the Panda robot. To do this, we first need to import ``rospy``, the Python API for ``ROS``, along with some essential libraries such as ``math``. Additionally, we will need specific message types that the robot can interpret and execute to perform the desired movements."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import math\n",
+                "\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from sensor_msgs.msg import JointState\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Now, let's start with initializing a ``ROS node`` and creating a ``Publisher``. The ``Publisher`` will later publish our target joint values to the correct topic.\n",
+                "\n",
+                "ToDo:\n",
+                "- create a ``ROS node`` with the name ``joint_manipulator``\n",
+                "- implement the `Publisher` that publishes data to the ``/effort_joint_trajectory_controller`` topic using the JointTrajectory message type"
+            ]
+        },
+        {
+            "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": [
+                "Next, we need to initialize the message that will hold the target values, which will later be published to control the robot's movements. To do this, we create an object of the ``JointTrajectory`` class, set the header, and then add the joint_names that we want to modify. The ``JointTrajectory`` is a message type used to define the movement of the robot's joints over time."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "joint_trajectory = JointTrajectory()\n",
+                "joint_trajectory.header.stamp = rospy.Time.now()\n",
+                "joint_trajectory.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "To the ``JointTrajectory``, we can add ``JointTrajectoryPoints``, which the robot will then execute sequentially. To do this, we need to create a ``JointTrajectoryPoint`` and add the desired values for the movement. We initial set the values of our target point to the current joint values of the robot."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_4"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "point = JointTrajectoryPoint()\n",
+                "\n",
+                "current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position\n",
+                "\n",
+                "point.positions = list(current_joint_values)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "<img src=\"https://www.researchgate.net/publication/378309540/figure/fig2/AS:11431281224653965@1708362343804/The-7DoF-Franka-Emika-Panda-robot-arm.jpg\" \n",
+                "     alt=\"joints of the panda robot\" width=\"350\">\n",
+                "\n",
+                "Each axis of the robot can only rotate within a specific range, defined by a minimum and maximum radiant value.\n",
+                "\n",
+                "> - joint0: [-2.8973, 2.8973]\n",
+                "> - joint1: [-1.7628, 1.7628]\n",
+                "> - joint2: [-2.8973, 2.8973]\n",
+                "> - joint3: [-3.0718, -0.0698]\n",
+                "> - joint4: [-2.8973, 2.8073]\n",
+                "> - joint5: [-0.0175, 3.7525]\n",
+                "> - joint6: [-2.8973, 2.8973]\n",
+                "\n",
+                "ToDo:\n",
+                "\n",
+                "- rotate the joint1 to 90 degrees,\n",
+                "- rotate the joint4 to 155 degrees. \n",
+                "\n",
+                "Tip:\n",
+                "- use ``math.pi``\n",
+                "- $$degrees = 180 * randiant / pi$$"
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5",
+                    "solution_removed_cell"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "point.positions[0] = 0.0\n",
+                "\n",
+                "##### YOUR CODE HERE #####\n",
+                "raise NotImplementedError()"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "To complete the script, we can set the duration of the movement, append the point to the ``JointTrajectory``, and then, after a short pause, publish our message."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_6"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "point.time_from_start = rospy.Duration(2) \n",
+                "\n",
+                "joint_trajectory.points.append(point)\n",
+                "\n",
+                "rospy.sleep(1.0)\n",
+                "\n",
+                "pub.publish(joint_trajectory)\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "At the end, sleep for the same duration as the movement to ensure nothing interrupts it. Finally, don’t forget to shut down the node when the process is complete."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_7"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "rospy.signal_shutdown(\"Task completed\")\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/ros/ros_intermediate/ros_intermediate_2.ipynb b/catkin_ws/src/learn_environment/tasks/ros/ros_intermediate/ros_intermediate_2.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..ef32bd938a24203a78d671f5ecba82216ac84265
--- /dev/null
+++ b/catkin_ws/src/learn_environment/tasks/ros/ros_intermediate/ros_intermediate_2.ipynb
@@ -0,0 +1,162 @@
+{
+    "cells": [
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "# Educational Plattform Panda Robot\n",
+                "Author: uninh, uqwfa, ultck"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "## ROS Intermediate\n",
+                "### Task 2\n",
+                "\n",
+                "---\n",
+                "> In this task, you will ...\n",
+                ">\n",
+                "> - ... execute multiple movements of the robot on your own.\n",
+                "\n",
+                "---"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "First import ``rospy``, ``math``, ``JointTrajectory`` and ``JointTrajectoryPoint``."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_1"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "import rospy\n",
+                "import math\n",
+                "\n",
+                "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n",
+                "from sensor_msgs.msg import JointState\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Initialize a subscriber node by first creating the ``ROS node``. Then, define a ``subscriber`` within this node, selecting the appropriate ``topic`` and ensuring that the correct message type is specified."
+            ]
+        },
+        {
+            "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": [
+                "As in Task 1, we then proceed to create a ``JointTrajectory`` object."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_3"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "joint_trajectory = JointTrajectory()\n",
+                "joint_trajectory.header.stamp = rospy.Time.now()\n",
+                "joint_trajectory.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        },
+        {
+            "cell_type": "markdown",
+            "metadata": {},
+            "source": [
+                "Next, add three points to the ``JointTrajectory`` object. In the first point, set ``joint6`` to ``155`` degrees. For the second point, set the joint positions to ``[-1.5, -0.5, 0, -1.5, 0, 1.5, 0]``. In the final point, reset the robot to its default position. That would be ``[0, -45, 0, -135, 0, 90, 45]`` degrees. Set the time_from_start variable correctly to 2, 4 and 6 seconds."
+            ]
+        },
+        {
+            "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": [
+                "We now publish the ``JointTrajectory`` message, allow the robot 6 seconds to execute the movement, and then delete the ``node``."
+            ]
+        },
+        {
+            "cell_type": "code",
+            "execution_count": null,
+            "metadata": {
+                "tags": [
+                    "task_cell_5"
+                ]
+            },
+            "outputs": [],
+            "source": [
+                "##### DO NOT CHANGE #####\n",
+                "\n",
+                "rospy.sleep(2)\n",
+                "\n",
+                "pub.publish(joint_trajectory)\n",
+                "\n",
+                "rospy.sleep(6)\n",
+                "\n",
+                "rospy.signal_shutdown(\"Task completed.\")\n",
+                "\n",
+                "##### DO NOT CHANGE #####"
+            ]
+        }
+    ],
+    "metadata": {
+        "language_info": {
+            "name": "python"
+        }
+    },
+    "nbformat": 4,
+    "nbformat_minor": 2
+}
\ No newline at end of file