diff --git a/Lecture/TutorialTask_DH.ipynb b/Lecture/TutorialTask_DH.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..82fa64ec23611829e6bdafde2f527e7a6a5fffd7
--- /dev/null
+++ b/Lecture/TutorialTask_DH.ipynb
@@ -0,0 +1,513 @@
+{
+ "cells": [
+  {
+   "cell_type": "markdown",
+   "id": "e4ccc978",
+   "metadata": {},
+   "source": [
+    "# Forward Kinematics - Denavit-Hartenberg Matrix\n"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "79d129c2",
+   "metadata": {},
+   "source": [
+    "![txt](task1.png)"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "d138648a",
+   "metadata": {},
+   "source": [
+    "## Exercise 1:\n",
+    "\n",
+    "The frame attachment information and the DH table of the Puma 560 robot are given below. \n",
+    "\n",
+    "The constant parameters are\n",
+    "- h = 40 cm,\n",
+    "- $a_2$ = 50 cm,\n",
+    "- $a_3$ = 10 cm,\n",
+    "- $d_3$ = 20 cm and\n",
+    "- $d_4$ = 30 cm.\n",
+    "\n",
+    "1. Find transformation matrices between every consectuive frame.\n",
+    "\n",
+    "   **Remember**:\n",
+    "   \n",
+    "   $T_{i-1}^i = \n",
+    "   \\begin{bmatrix}\n",
+    "    c_{\\theta} & -s_{\\theta}c_{\\alpha} & s_{\\theta}s_{\\alpha} & a_i c_{\\theta} \\\\\n",
+    "    s_{\\theta} & c_{\\theta}c_{\\alpha} & -c_{\\theta}s_{\\alpha} & a_i s_{\\theta}\\\\\n",
+    "    0 & s_{\\alpha} & c_{\\alpha} & d_i\\\\\n",
+    "    0 & 0 & 0 & 1\\\\\n",
+    "    \\end{bmatrix}$\n",
+    "    \n",
+    "\n",
+    "2. Find the angular Jacobian matrix ($J_{\\omega}$) between the world frame and the end-effector.\n",
+    "   \n",
+    "   **Remember**:\n",
+    "   \n",
+    "   $J_{\\omega} = \\begin{bmatrix}\n",
+    "   R_{0}^1 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix} & R_{0}^2 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix} & R_{0}^3 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix} & R_{0}^4 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix}  & R_{0}^5 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix} & R_{0}^6 \\begin{bmatrix}0\\\\0\\\\1\\end{bmatrix} \n",
+    "   \\end{bmatrix}$"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "856e8c26",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# importing necessary modules\n",
+    "import numpy as np\n",
+    "import math \n",
+    "!pip install sympy\n",
+    "import sympy as sym\n",
+    "#setting the precision for decimal values.|\n",
+    "%precision 4 "
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "3e160bf2",
+   "metadata": {},
+   "source": [
+    "Define your constant parameter **$h$**, **$a_i$** and **$d_i$**. You can define the variable parameters **$\\theta_i$** using the [`Symbol`](https://www.tutorialspoint.com/sympy/sympy_symbols.htm) function available in the `sympy` library. A quick start tutorial to the sympy library can be found [here](https://docs.sympy.org/latest/tutorials/intro-tutorial/gotchas.html). We use the library [sympy](https://www.sympy.org/en/index.html) in the context of this task to allow for matrix multiplication with elements of the matrix being symbolic, since the $\\theta_i$ values are variable parameters. "
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "2a7a4011",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#YOUR CODE HERE"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "946fe40a",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "# constant parameters\n",
+    "h = 0.4 # in meter\n",
+    "a_2 = 0.5 # in meter\n",
+    "a_3 = 0.1 # in meter\n",
+    "d_3 = 0.2 # in meter\n",
+    "d_4 = 0.3 # in meter\n",
+    "\n",
+    "# variable parameters\n",
+    "#A quick start tutorial to the sympy library - https://docs.sympy.org/latest/tutorials/intro-tutorial/gotchas.html\n",
+    "theta_1 = sym.Symbol('theta_1')\n",
+    "theta_2 = sym.Symbol('theta_2')\n",
+    "theta_3 = sym.Symbol('theta_3')\n",
+    "theta_4 = sym.Symbol('theta_4')\n",
+    "theta_5 = sym.Symbol('theta_5')\n",
+    "theta_6 = sym.Symbol('theta_6')\n"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "023cc991",
+   "metadata": {},
+   "source": [
+    "Create a table to store the value of the DH table.\n",
+    "\n",
+    "**Hint:** Try using the [`array`](https://numpy.org/doc/stable/reference/generated/numpy.array.html) function from the `numpy` library. Each row of the array will represent row from the DH table."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "6fb13c2f",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#YOUR CODE HERE"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "1bd37565",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "# creating an array for the DH table\n",
+    "#the values are in the order shown in the table\n",
+    "dh_table = np.array([(0,0,h,theta_1),\n",
+    "                    (-90,0,0,theta_2),\n",
+    "                    (0,a_2,d_3,theta_3),\n",
+    "                    (-90,a_3,d_4,theta_4),\n",
+    "                    (90,0,0,theta_5),\n",
+    "                    (-90,0,0,theta_6)])\n",
+    "print(dh_table)"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "af6b38c9",
+   "metadata": {},
+   "source": [
+    "Create a function `calc_T` that takes as input the values from each row of the DH table and then calculates the transformation matrix $T_{i-1}^i$ for each row of the DH Table.\n",
+    "\n",
+    "**Hint:** Check the [`Matrix`](https://docs.sympy.org/latest/tutorials/intro-tutorial/matrices.html) function provided in the `sympy` package\n",
+    "\n",
+    "**Note:** Once you implement the function remove the `pass` keyword from the function."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "5ae5f46a",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# function to calculate transformation matrix\n",
+    "def calc_T(alpha, a, d, theta):\n",
+    "    #YOUR CODE HERE\n",
+    "    pass"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "0ee7c6bd",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "# function to calculate transformation matrix\n",
+    "def calc_T(alpha, a, d, theta):\n",
+    "    \n",
+    "    s_theta = sym.sin(theta)\n",
+    "    c_theta = sym.cos(theta)\n",
+    "    s_alpha = math.sin(math.radians(alpha))\n",
+    "    c_alpha = math.cos(math.radians(alpha))\n",
+    "    \n",
+    "    # Sympy Matrix Documentation - https://docs.sympy.org/latest/tutorials/intro-tutorial/matrices.html\n",
+    "    T = sympy.Matrix([[c_theta, -s_theta*s_alpha, s_theta*s_alpha,a*c_theta],\n",
+    "                  [s_theta, c_theta*c_alpha, -c_theta*s_alpha, a*s_theta],\n",
+    "                  [0, s_alpha, c_alpha, d],\n",
+    "                  [0,0,0,1]])\n",
+    "    return T"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "9d36c06b",
+   "metadata": {},
+   "source": [
+    "## To Kemal and Jan\n",
+    "I think we can leave the below cell as such so that they will understand how the data is being input to the function. We can leave out this section for Task 2."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "fd3975c1",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "n_frame = dh_table.shape[0]\n",
+    "T_list = []\n",
+    "for i in range(0,n_frame):\n",
+    "    T = calc_T(alpha=dh_table[i,0], a=dh_table[i,1], d=dh_table[i,2], theta=dh_table[i,3])\n",
+    "    T_list.append(T)"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "56230bbd",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{0}^1$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "fb9fff68",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "5a2f93fc",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[0]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "2fbdb3d4",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{1}^2$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "aee3978b",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "92c4262b",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[1]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "08d7ff99",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{2}^3$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "4e2ceb82",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "3013564b",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[2]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "66b1f49b",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{3}^4$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "15a390dc",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "27ad3be0",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[3]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "5f1a09eb",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{4}^5$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "a2bda339",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "e7272bd3",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[4]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "139344a9",
+   "metadata": {},
+   "source": [
+    "Print the transformation matrix $T_{5}^6$:"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "71646159",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#Print statement here"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "80000505",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#SAMPLE SOLUTION\n",
+    "T_list[5]"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "95844079",
+   "metadata": {},
+   "source": [
+    "## Note To kemal\n",
+    "I don't understand how you want the rotational jacobian to be formed. The lecture say that the jacobian is made of derivatives. But the task mentions to use the rotation matrix. So, I am not sure how to set up this task"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "86f1dd3f",
+   "metadata": {},
+   "source": [
+    "## Exercise 2\n",
+    "![Task2](taks2.png)"
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "b0494415",
+   "metadata": {},
+   "source": [
+    "For this exercise we will use the same steps as before with the **only** difference being the values of $a_{i-1}$ is also a variable. \n",
+    "We will follow the steps below to complete this task\n",
+    "\n",
+    "1. Define the variables as symbols using the `Symbol` function from the `sympy` library.\n",
+    "2. Create a DH table using the `array` function from the `numpy` library.\n",
+    "3. Define a function `calc_T` which takes as input the variable required to calculate the transformation matrix $T_{i-1}^i$ .\n",
+    "4. Create a `for` loop that will call the `calc_T` repeatedly to calculate the tranformation matrix one by one."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "33a02c35",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# 1. Define the variables as symbols using the `Symbol` function from the `sympy` library."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "ced0882f",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# 2. Create a DH table using the `array` function from the `numpy` library."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "7ad86c87",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#3. Define a function `calc_T` which takes as input the variable required to calculate the transformation matrix T_{i-1}^i."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "d735ae4e",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#4. Create a `for` loop that will call the `calc_T` repeatedly to calculate the tranformation matrix one by one."
+   ]
+  },
+  {
+   "cell_type": "markdown",
+   "id": "0409b179",
+   "metadata": {},
+   "source": [
+    "Finally calculate the transformation matrix $T_{0}^3$ from the base frame `0` to the end effector frame `3`."
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "id": "fcb08280",
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "#calculate the transformation between the base and end-effector frame."
+   ]
+  }
+ ],
+ "metadata": {
+  "kernelspec": {
+   "display_name": "Python 3 (ipykernel)",
+   "language": "python",
+   "name": "python3"
+  },
+  "language_info": {
+   "codemirror_mode": {
+    "name": "ipython",
+    "version": 3
+   },
+   "file_extension": ".py",
+   "mimetype": "text/x-python",
+   "name": "python",
+   "nbconvert_exporter": "python",
+   "pygments_lexer": "ipython3",
+   "version": "3.10.6"
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}