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] 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