From 6773a4acad585e183e55d1f0707115e87c9d2167 Mon Sep 17 00:00:00 2001
From: Max <uqwfa@student.kit.edu>
Date: Thu, 19 Dec 2024 11:28:14 +0100
Subject: [PATCH 1/2] final changes notebooks

---
 .../move_it_basics/move_it_basics_2.ipynb     |  2 +-
 .../ros/ros_basics/ros_basics_1.ipynb         |  4 ++--
 .../ros/ros_basics/ros_basics_2.ipynb         |  1 -
 .../ros/ros_basics/ros_basics_3.ipynb         |  4 ++--
 .../ros_intermediate/ros_intermediate_1.ipynb |  2 ++
 .../ros_intermediate/ros_intermediate_2.ipynb | 23 +++++++++++++++----
 .../task_pool/solution_template.ipynb         | 12 ++++++----
 7 files changed, 33 insertions(+), 15 deletions(-)

diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
index c40ea1e..269af91 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
@@ -58,7 +58,7 @@
     "\n",
     "- initialize ``roscpp`` with ``sys.argv`` as an argument\n",
     "- initialize a ``ROS node``\n",
-    "- assign a ``MoveGroupCommander`` instace to ``group``"
+    "- assign a ``MoveGroupCommander`` instance to ``group``"
    ]
   },
   {
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
index 9a93b76..c14d00f 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
@@ -41,7 +41,7 @@
    "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."
+    "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 ``std_msgs.msg``. Additionally, the standard Python module ``time`` is used for handling time calculations."
    ]
   },
   {
@@ -85,7 +85,7 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Now we want to create a ``Publisher`` that sends Strings messages to the ``'chatter'`` topic."
+    "Now we want to create a ``Publisher`` that sends ``Strings`` messages to the ``'chatter'`` topic. The ``queue_size`` argument specifies the number of messages that can be held in a buffer when ``subscribers`` to the ``topic`` are not immediately ready to process them."
    ]
   },
   {
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
index c189dd9..efd2bf9 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
@@ -64,7 +64,6 @@
     "\n",
     "def callback(msg):\n",
     "    rospy.loginfo(\"data: \" + msg.data)\n",
-    "    sys.stdout.flush()\n",
     "\n",
     "##### DO NOT CHANGE #####"
    ]
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_3.ipynb
index d50c3d3..1279cd3 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_3.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_3.ipynb
@@ -77,9 +77,9 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "The Panda Robot is a 7-axis robotic arm with a gripper/ finger.\n",
+    "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",
+    "- ``/joint_states``: on this topic the current joint positions, 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."
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
index f44f144..69f0708 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
@@ -64,6 +64,8 @@
    "metadata": {},
    "outputs": [],
    "source": [
+    "pub = None\n",
+    "\n",
     "##### YOUR CODE HERE #####\n",
     "\n",
     "rospy.init_node(\"joint_manipulator\")\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
index 849bcdd..080800a 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
@@ -51,7 +51,12 @@
    "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."
+    "Initialize a publisher node by first creating the ``ROS node``. Then, define a ``publisher`` within this node, selecting the appropriate ``topic`` and ensuring that the correct message type is specified.\n",
+    "\n",
+    "ToDo:\n",
+    "\n",
+    "- create ``ROS node``\n",
+    "- implement a ``publisher`` to the ``pub`` variable"
    ]
   },
   {
@@ -60,6 +65,8 @@
    "metadata": {},
    "outputs": [],
    "source": [
+    "pub = None\n",
+    "\n",
     "##### YOUR CODE HERE #####\n",
     "\n",
     "rospy.init_node(\"joint_manipulator\")\n",
@@ -95,7 +102,15 @@
    "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."
+    "Next, add three points to the ``JointTrajectory`` object. For the first point, change a single joint. For the second point, set the joint positions to a completly new position. 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.\n",
+    "\n",
+    "ToDo:\n",
+    "\n",
+    "- point1: set ``joint6`` to ``155`` degrees\n",
+    "- point2: set to ``[-1.5, -0.5, 0, -1.5, 0, 1.5, 0]``\n",
+    "- point3: set to default position\n",
+    "- set the ``time_from_start``\n",
+    "- append the points to the ``joint_trajectory``"
    ]
   },
   {
@@ -104,12 +119,12 @@
    "metadata": {},
    "outputs": [],
    "source": [
-    "##### YOUR CODE HERE #####\n",
-    "\n",
     "point1 = JointTrajectoryPoint()\n",
     "point2 = JointTrajectoryPoint()\n",
     "point3 = JointTrajectoryPoint()\n",
     "\n",
+    "##### YOUR CODE HERE #####\n",
+    "\n",
     "current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position\n",
     "\n",
     "point1.positions = list(current_joint_values)\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_template.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_template.ipynb
index e136534..a5fc488 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_template.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_template.ipynb
@@ -4,8 +4,8 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "# Learn Environment Panda Robot\n",
-    "Author: NAME"
+    "# Educational Plattform Panda Robot\n",
+    "Author: uninh, uqwfa, ultck"
    ]
   },
   {
@@ -13,12 +13,14 @@
    "metadata": {},
    "source": [
     "## Task_Name\n",
-    "### Subtask_Name\n",
-    "\n",
+    "### Task X\n",
+    "---\n",
     "> In this task, you will learn ...\n",
     ">\n",
     "> - ... \n",
-    "> - ... "
+    "> - ... \n",
+    "\n",
+    "---"
    ]
   },
   {
-- 
GitLab


From 26f0a6cd9f6736bfc3453803dbb1d1d6c41d6f57 Mon Sep 17 00:00:00 2001
From: Max <uqwfa@student.kit.edu>
Date: Fri, 3 Jan 2025 13:34:45 +0100
Subject: [PATCH 2/2] finish tasks

---
 .../move_it/move_it_basics/move_it_basics_1_eval.py   |  2 +-
 .../move_it/move_it_basics/move_it_basics_2_eval.py   |  2 +-
 .../ros/ros_basics/ros_basics_1_eval.py               |  4 ++--
 .../ros/ros_basics/ros_basics_2_eval.py               |  4 ++--
 .../ros/ros_intermediate/ros_intermediate_1_eval.py   |  2 +-
 .../ros/ros_intermediate/ros_intermediate_2_eval.py   |  6 +++---
 .../move_it/move_it_basics/move_it_basics_2.ipynb     | 11 +++++++++--
 .../ros/ros_basics/ros_basics_1.ipynb                 |  4 ++--
 .../ros/ros_basics/ros_basics_2.ipynb                 |  3 +--
 .../ros/ros_intermediate/ros_intermediate_1.ipynb     |  4 ++--
 .../ros/ros_intermediate/ros_intermediate_2.ipynb     |  2 +-
 .../learn_environment/task_pool/task_definitions.json | 10 +++++-----
 12 files changed, 30 insertions(+), 24 deletions(-)

diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py
index e3708a2..53f734f 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_1_eval.py
@@ -22,7 +22,7 @@ for i, (current, expected) in enumerate(zip(current_joint_values, expected_value
     if abs(current - expected) > error_margin:
         
         roscpp_shutdown()
-        print('Joint {} is not in the correct position'.format(i))
+        print('Joint {} is not in the correct position.'.format(i))
         print('false')
         sys.exit(0)
 
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_2_eval.py
index 2aac46c..4d50e47 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_2_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/move_it/move_it_basics/move_it_basics_2_eval.py
@@ -39,7 +39,7 @@ for i, (current, expected) in enumerate(zip(current_values, expected_pose)):
         
         roscpp_shutdown()
 
-        print("Pose component \'{}\' is not in the correct position".format(value_names[i]))
+        print("Pose component \'{}\' is not in the correct position.".format(value_names[i]))
         print("false")
         sys.exit(0)
 
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py
index cd936d2..49aa3ac 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_1_eval.py
@@ -64,11 +64,11 @@ if node_exists and msg_received:
     print('true')
 
 elif not node_exists:
-    print('Node not found')
+    print('Node not found.')
     print('false')
 
 else:
-    print('No messages received on the /chatter topic')
+    print('No messages received on the /chatter topic.')
     print('false')
 
 
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py
index 9d61736..88cd6f7 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_basics/ros_basics_2_eval.py
@@ -70,11 +70,11 @@ if node_exist and sub_exist:
     print('true')
 
 elif not node_exist:
-    print('node not found')
+    print('Node not found.')
     print('false')
 
 else:
-    print('subscriber does not exist')
+    print('Subscriber does not exist.')
     print('false')
 
 rospy.signal_shutdown('evaluation done')
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py
index 188e9b1..bd5e815 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_1_eval.py
@@ -18,7 +18,7 @@ for i, (current, expected) in enumerate(zip(current_joint_values, expected_value
     if abs(current - expected) > error_margin:
         
         roscpp_shutdown()
-        print("Joint {} is not in the correct position".format(i+1))
+        print("Joint {} is not in the correct position".format(i))
         print('false')
         sys.exit(0)
 
diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py
index acdaac6..f3db0f1 100644
--- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py
+++ b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/ros/ros_intermediate/ros_intermediate_2_eval.py
@@ -20,7 +20,7 @@ class Eval():
     def joint_state_callback(self, msg):
         self.current_joint_values = msg
 
-    def joint_trajectory_callback(self, msg):
+    def joint_trajectory_callback(self):
         self.received_msg = True
 
     def evaluate_position(self, target_position):
@@ -70,9 +70,9 @@ if sucessful_positions == 3:
     print('true')
 
 elif not x.received_msg:
-    print('no message received on the topic')
+    print('No message received on the topic.')
     print('false')
 
 else:
-    print('position {} not reached'.format(sucessful_positions + 1))
+    print('Position {} not reached.'.format(sucessful_positions + 1))
     print('false')
\ No newline at end of file
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
index 269af91..ad3ffac 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/move_it/move_it_basics/move_it_basics_2.ipynb
@@ -82,7 +82,12 @@
    "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``."
+    "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. \n",
+    "\n",
+    "ToDo:\n",
+    "\n",
+    "- set ``set_max_velocity_scaling_factor()`` to ``1``\n",
+    "- set ``set_max_acceleration_scaling_factor()`` to ``1``."
    ]
   },
   {
@@ -148,7 +153,9 @@
    "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)."
+    "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. \n",
+    "\n",
+    "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)."
    ]
   },
   {
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
index c14d00f..0cc2ae9 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_1.ipynb
@@ -85,7 +85,7 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "Now we want to create a ``Publisher`` that sends ``Strings`` messages to the ``'chatter'`` topic. The ``queue_size`` argument specifies the number of messages that can be held in a buffer when ``subscribers`` to the ``topic`` are not immediately ready to process them."
+    "Now we want to create a ``Publisher`` that sends ``String`` messages to the ``'/chatter'`` topic. The ``queue_size`` argument specifies the number of messages that can be held in a buffer when ``Subscribers`` to the ``topic`` are not immediately ready to process them."
    ]
   },
   {
@@ -109,7 +109,7 @@
     "\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."
+    "- call the ``publish()`` method of the Publisher to send the ``msg`` variable."
    ]
   },
   {
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
index efd2bf9..1d48617 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_basics/ros_basics_2.ipynb
@@ -18,7 +18,7 @@
     "---\n",
     "> In this task, you will learn ...\n",
     ">\n",
-    "> - ... how to create a simple ``ROS`` topic subscriber.\n",
+    "> - ... how to create a simple ``ROS topic`` Subscriber.\n",
     "\n",
     "---"
    ]
@@ -40,7 +40,6 @@
     "\n",
     "import rospy\n",
     "import time\n",
-    "import sys\n",
     "\n",
     "from std_msgs.msg import String\n",
     "\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
index 69f0708..60c3a6b 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_1.ipynb
@@ -55,7 +55,7 @@
     "\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"
+    "- implement the `Publisher` that publishes data to the ``/effort_joint_trajectory_controller/command`` topic using the ``JointTrajectory`` message type, for this use the ``pub`` variable"
    ]
   },
   {
@@ -140,7 +140,7 @@
     "\n",
     "ToDo:\n",
     "\n",
-    "- rotate the joint1 to 90 degrees,\n",
+    "- rotate the joint2 to 90 degrees,\n",
     "- rotate the joint4 to 155 degrees. \n",
     "\n",
     "Tip:\n",
diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
index 080800a..cee103b 100644
--- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
+++ b/catkin_ws/src/learn_environment/task_pool/solution_scripts/ros/ros_intermediate/ros_intermediate_2.ipynb
@@ -27,7 +27,7 @@
    "cell_type": "markdown",
    "metadata": {},
    "source": [
-    "First import ``rospy``, ``math``, ``JointTrajectory`` and ``JointTrajectoryPoint``."
+    "First we import ``rospy``, ``math``, ``JointTrajectory``, ``JointTrajectoryPoint`` and ``JointState``."
    ]
   },
   {
diff --git a/catkin_ws/src/learn_environment/task_pool/task_definitions.json b/catkin_ws/src/learn_environment/task_pool/task_definitions.json
index c6b804c..a180dd5 100644
--- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json
+++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json
@@ -8,7 +8,7 @@
       "subtasks": [
         {
           "title": "Task 1",
-          "description": "Explains the ROS system and implement a simple publisher.",
+          "description": "Explains the ROS system and implement a simple Publisher.",
           "solution_file": "/ros_basics_1.ipynb",
           "evaluation_file": "/ros_basics_1_eval.py",
           "parallelized_evaluation_required": true,
@@ -16,7 +16,7 @@
         },
         {
           "title": "Task 2",
-          "description": "Implement a simple subscriber.",
+          "description": "Implement a simple Subscriber.",
           "solution_file": "/ros_basics_2.ipynb",
           "evaluation_file": "/ros_basics_2_eval.py",
           "parallelized_evaluation_required": true,
@@ -39,7 +39,7 @@
       "subtasks": [
         {
           "title": "Task 1",
-          "description": "Implement your first simple movement.",
+          "description": "Implement your first movement.",
           "solution_file": "/ros_intermediate_1.ipynb",
           "evaluation_file": "/ros_intermediate_1_eval.py"
         },
@@ -60,13 +60,13 @@
       "subtasks": [
         {
           "title": "Task 1",
-          "description": "Implement a simple movement with MoveIt.",
+          "description": "Implement a movement with the MoveIt Package.",
           "solution_file": "/move_it_basics_1.ipynb",
           "evaluation_file": "/move_it_basics_1_eval.py"
         },
         {
           "title": "Task 2",
-          "description": "Implement a simple movement with MoveIt.",
+          "description": "Move the robot to cartesian coordinates.",
           "solution_file": "/move_it_basics_2.ipynb",
           "evaluation_file": "/move_it_basics_2_eval.py"
         }
-- 
GitLab