From 2fae01fee8a539db371375ea3986834312ceebcc Mon Sep 17 00:00:00 2001 From: Max <uqwfa@student.kit.edu> Date: Tue, 17 Dec 2024 14:34:10 +0100 Subject: [PATCH] delete exercise 1-3 from beginner directory --- .../beginner/exercise_1/exercise_1_1_eval.py | 28 --- .../beginner/exercise_1/exercise_1_2_eval.py | 28 --- .../beginner/exercise_1/exercise_1_3_eval.py | 28 --- .../beginner/exercise_2/exercise_2_1_eval.py | 39 ---- .../beginner/exercise_2/exercise_2_2_eval.py | 39 ---- .../beginner/exercise_3/exercise_3_1_eval.py | 91 -------- .../beginner/exercise_1/exercise_1_1.ipynb | 185 ---------------- .../beginner/exercise_1/exercise_1_2.ipynb | 187 ---------------- .../beginner/exercise_1/exercise_1_3.ipynb | 186 ---------------- .../beginner/exercise_2/exercise_2_1.ipynb | 183 ---------------- .../beginner/exercise_2/exercise_2_2.ipynb | 207 ------------------ .../beginner/exercise_3/exercise_3_1.ipynb | 78 ------- .../task_pool/task_definitions.json | 67 ------ 13 files changed, 1346 deletions(-) delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_1_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_2_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_3_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_1_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_2_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_3/exercise_3_1_eval.py delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_1.ipynb delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_2.ipynb delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_3.ipynb delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_1.ipynb delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb delete mode 100644 catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_3/exercise_3_1.ipynb diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_1_eval.py deleted file mode 100644 index 80e4c3a..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_1_eval.py +++ /dev/null @@ -1,28 +0,0 @@ -import sys -import math - -import rospy -from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown - - -rospy.loginfo("exercise_1_1_evaluation") - -roscpp_initialize(sys.argv) -rospy.init_node('exercise_1_1_evaluation', anonymous=True) - -group = MoveGroupCommander("panda_arm") - -current_joint_values = group.get_current_joint_values() -expected_values = [0.0, -math.pi/4, 0.0, -math.pi * 3/4, (155 * math.pi) / 180, math.pi/2, math.pi/4] -error_margin = 0.01 - -for i, (current, expected) in enumerate(zip(current_joint_values, expected_values)): - if abs(current - expected) > error_margin: - - roscpp_shutdown() - print("false, Joint {} is not in the correct position".format(i+1)) - sys.exit(0) - -roscpp_shutdown() - -print("true") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_2_eval.py deleted file mode 100644 index dd51aa6..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_2_eval.py +++ /dev/null @@ -1,28 +0,0 @@ -import sys -import math - -import rospy -from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown - - -rospy.loginfo("exercise_1_2_evaluation") - -roscpp_initialize(sys.argv) -rospy.init_node('exercise_1_2_evaluation', anonymous=True) - -group = MoveGroupCommander("panda_arm") - -current_joint_values = group.get_current_joint_values() -expected_values = [math.pi * 150/180, math.pi/2, math.pi * 150/180, -math.pi * 6/180, math.pi * 150 / 180, math.pi * 206/180, math.pi * 150/180] -error_margin = 0.01 - -for i, (current, expected) in enumerate(zip(current_joint_values, expected_values)): - if abs(current - expected) > error_margin: - - roscpp_shutdown() - print("false, Joint {} is not in the correct position".format(i+1)) - sys.exit(0) - -roscpp_shutdown() - -print("true") diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_3_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_3_eval.py deleted file mode 100644 index a953b24..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_1/exercise_1_3_eval.py +++ /dev/null @@ -1,28 +0,0 @@ -import sys -import math - -import rospy -from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown - - -rospy.loginfo("exercise_1_3_evaluation") - -roscpp_initialize(sys.argv) -rospy.init_node('exercise_1_3_evaluation', anonymous=True) - -group = MoveGroupCommander("panda_arm") - -current_joint_values = group.get_current_joint_values() -expected_values = [0.0, -math.pi/4, 0.0, -math.pi * 3/4, 0.0, math.pi/2, math.pi/4] -error_margin = 0.01 - -for i, (current, expected) in enumerate(zip(current_joint_values, expected_values)): - if abs(current - expected) > error_margin: - - roscpp_shutdown() - print("false, Joint {} is not in the correct position".format(i+1)) - sys.exit(0) - -roscpp_shutdown() - -print("true") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_1_eval.py deleted file mode 100644 index e6e784f..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_1_eval.py +++ /dev/null @@ -1,39 +0,0 @@ -import sys -import math - -import rospy -from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown - - -rospy.loginfo("exercise_2_1_evaluation") - -roscpp_initialize(sys.argv) -rospy.init_node('exercise_2_1_evaluation', anonymous=True) - -group = MoveGroupCommander("panda_arm") - -current_pose = group.get_current_pose().pose -expected_pose = [0.5, 0, 0.2, 0.5, 0.5, 0.5, 0.5] -error_margin = 0.01 - -current_values = [ - current_pose.position.x, - current_pose.position.y, - current_pose.position.z, - current_pose.orientation.x, - current_pose.orientation.y, - current_pose.orientation.z, - current_pose.orientation.w -] - -for i, (current, expected) in enumerate(zip(current_values, expected_pose)): - if abs(current - expected) > error_margin: - - roscpp_shutdown() - - print("false, Pose component {} is not in the correct position".format(i+1)) - sys.exit(0) - -roscpp_shutdown() - -print("true") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_2_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_2_eval.py deleted file mode 100644 index bc5e0d9..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_2/exercise_2_2_eval.py +++ /dev/null @@ -1,39 +0,0 @@ -import sys -import math - -import rospy -from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown - - -rospy.loginfo("exercise_2_2_evaluation") - -roscpp_initialize(sys.argv) -rospy.init_node('exercise_2_2_evaluation', anonymous=True) - -group = MoveGroupCommander("panda_arm") - -current_pose = group.get_current_pose().pose -expected_pose = [-0.5, -0.2, 0.8, 0.0, 0.0, 0.0, 1] -error_margin = 0.01 - -current_values = [ - current_pose.position.x, - current_pose.position.y, - current_pose.position.z, - current_pose.orientation.x, - current_pose.orientation.y, - current_pose.orientation.z, - current_pose.orientation.w -] - -for i, (current, expected) in enumerate(zip(current_values, expected_pose)): - if abs(current - expected) > error_margin: - - roscpp_shutdown() - - print("false, Pose component {} is not in the correct position".format(i+1)) - sys.exit(0) - -roscpp_shutdown() - -print("true") \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_3/exercise_3_1_eval.py b/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_3/exercise_3_1_eval.py deleted file mode 100644 index d9ef482..0000000 --- a/catkin_ws/src/learn_environment/task_pool/evaluation_scripts/beginner/exercise_3/exercise_3_1_eval.py +++ /dev/null @@ -1,91 +0,0 @@ -#!/usr/bin/env python - -import rospy -from sensor_msgs.msg import JointState -import time - - -class JointSequenceEvaluator: - def __init__(self, tolerance=0.01): - """Initialize the evaluator.""" - self.current_joint_states = None - self.target_joint_positions = None - self.start_time = None - self.tolerance = tolerance - - # Initialize the ROS node - rospy.init_node('exercise_3_1_evaluation', anonymous=True) - - # Subscribe to the /joint_states topic - rospy.Subscriber('/joint_states', JointState, self.joint_state_callback) - - rospy.loginfo("JointSequenceEvaluator initialized and listening to /joint_states.") - - def joint_state_callback(self, msg): - """Callback for joint states topic.""" - self.current_joint_states = msg - - def set_target_position(self, target_position): - """Set the target joint positions to evaluate.""" - self.target_joint_positions = target_position - self.start_time = None # Reset timer for new target - - def evaluate_position_hold(self, required_duration=0.5): - """Evaluate if the robot holds a position for the required duration.""" - if self.current_joint_states is None or self.target_joint_positions is None: - return False # Cannot evaluate without data - - # Check if all joints are within the tolerance of the target position - within_tolerance = all( - abs(current - target) < self.tolerance - for current, target in zip(self.current_joint_states.position, self.target_joint_positions) - ) - - if within_tolerance: - # Start or update the timer - if self.start_time is None: - self.start_time = time.time() - - elif time.time() - self.start_time >= required_duration: - rospy.loginfo("Position held for {} seconds. Marking as positive.".format(required_duration)) - return True - else: - # Reset the timer if the robot moves out of tolerance - self.start_time = None - - return False - - -if __name__ == '__main__': - try: - evaluator = JointSequenceEvaluator() - - target_positions_sequence = [ - [0.5, -0.5, 0.5, -1.5, 0.5, 1.0, 0.5], # Position 1 - [1.0, -1.0, 1.0, -2.0, 1.0, 0.5, 1.0], # Position 2 - [1.5, -0.5, 1.5, -1.0, 1.5, 0.5, 1.5], # position 3 - [1.0, -1.0, 1.0, -2.0, 1.0, 0.5, 1.0], # Position 2 - [0.5, -0.5, 0.5, -1.5, 0.5, 1.0, 0.5], # position 1 - [0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785] # home position - ] - - for idx, target_position in enumerate(target_positions_sequence): - rospy.loginfo(f"Setting target position: {target_position}") - evaluator.set_target_position(target_position) - - # Wait until the position is evaluated as positive - rate = rospy.Rate(10) # 10 Hz - duration = 0.5 - while not rospy.is_shutdown(): - if idx == len(target_positions_sequence) - 1: - duration = 2.0 - - if evaluator.evaluate_position_hold(duration): - rospy.loginfo("Target position successfully evaluated.") - break - rate.sleep() - - print("All target positions successfully evaluated.") - - except rospy.ROSInterruptException: - pass \ No newline at end of file diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_1.ipynb deleted file mode 100644 index 6bf0ed8..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_1.ipynb +++ /dev/null @@ -1,185 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Educational Plattform Panda Robot\n", - "Author: uninh, uqwfa, ultck" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Exercise_1_1\n", - "\n", - "---\n", - "> In this task, you will learn ...\n", - ">\n", - "> - ... which Python modules are needed for a basic Python script.\n", - "> - ... how to initialize all the imported modules.\n", - "> - ... how to rotate a joint of the robot and execute the movement.\n", - "> - ... how to delete the initialized modules again.\n", - "\n", - "---" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "First, we load the required modules. These include standard library modules such as ``sys`` and ``math``, which are used for interaction with the interpreter and performing mathematical calculations. A key module is ``rospy``, which is essential for the Robot Operating System (ROS) and later enables communication with the robot. Finally, we use the ``moveit_commander`` module, which provides a user-friendly interface for motion planning via MoveIt." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "import sys\n", - "import math\n", - "\n", - "import rospy\n", - "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now, we initialize the ``moveit_commander`` using the ``roscpp_initialize()`` method and the ROS node using the ``init_node()`` method. For a more detailed explanation of what ``init_node()`` or the argument means, take a look here: https://docs.ros.org/en/melodic/api/rospy/html/rospy-module.html." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "roscpp_initialize(sys.argv)\n", - "rospy.init_node('exercise_1_1', anonymous=True)\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Next, we create an instance of the ``MoveGroupCommander()``, setting the ``planner ID`` to the 'RRTConnectkConfigDefault' motion planning algorithm and the ``number of planning attempts`` to 10." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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": [ - "The Franke Emika Robot is a 7-axis robotic arm.\n", - "\n", - "<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=\"400\">\n", - "\n", - "Every axis can rotate to a min, max radiant value.\n", - "\n", - "> - joint1: [-2.8973, 2.8973]\n", - "> - joint2: [-1.7628, 1.7628]\n", - "> - joint3: [-2.8973, 2.8973]\n", - "> - joint4: [-3.0718, -0.0698]\n", - "> - joint5: [-2.8973, 2.8073]\n", - "> - joint6: [-0.0175, 3.7525]\n", - "> - joint7: [-2.8973, 2.8973]\n", - "\n", - "Now, adjust the 5th axis to a rotation of 155 degrees. Use the ``get_current_joint_values()`` of the ``MoveGroupCommander`` and modify the correct index.\n", - "\n", - "tip:\n", - "- use ``math.pi`` \n", - "- ``degrees = radiant x 180 / pi``" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "joint_goal = group.get_current_joint_values()\n", - "joint_goal[4] = (155 * math.pi) / 180\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now, we just need to set our ``joint_goal`` as our target and execute the movement. For this use the ``set_joint_value_target()`` and ``go(wait=True)`` methods of the ``MoveGroupCommander``." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "group.set_joint_value_target(joint_goal)\n", - "group.go(wait=True)\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Finally, we want to shut down our ``ROS node`` and the ``moveit_commander``." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_2.ipynb deleted file mode 100644 index 560e448..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_2.ipynb +++ /dev/null @@ -1,187 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Educational Plattform Panda Robot\n", - "Author: uninh, uqwfa, ultck" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Exercise_1_2\n", - "\n", - "---\n", - "> In this task, you will learn ...\n", - ">\n", - "> - ... how to rotate the robot directly via rostopics.\n", - "---" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "First, we import the necessary modules. The core module, ``rospy``, is fundamental for working with the Robot Operating System (ROS), as it facilitates communication with the robot. The ``JointTrajectory``, ``JointTrajectoryPoint``, and ``JointState`` message types are crucial for defining and communicating movement commands and joint states to the robot." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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, we initialize a ``ROS node`` and set up a ``publisher`` to send the desired joint values to the appropriate ROS topic, allowing the robot to read and execute the commands seamlessly." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "rospy.init_node('exercise_1_2', anonymous=True)\n", - "pub = rospy.Publisher('/effort_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\n", - "\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We start by creating a ``JointTrajectory()`` object, the ROS message type that will later be used to publish our target joint values. Before that, we need to define its ``header`` and specify the ``joint_names`` to the default names." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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, we create a ``JointTrajectoryPoint()`` object, which will later be added to our ``JointTrajectory()`` to define a point in the trajectory for the robot to move to. To do this, we first retrieve the ``current_joint_values`` by subscribing to the ``/joint_states`` ROS topic and waiting for the first message within a 5-second timeout. Once the current joint values are obtained, we initialize a new ``JointTrajectoryPoint()`` and assign these values to it." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "\n", - "##### DO NOT CHANGE #####\n", - "\n", - "current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position\n", - "\n", - "point = JointTrajectoryPoint()\n", - "point.positions = list(current_joint_values)\n", - "\n", - "##### DO NOT CHANGE #####\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now, we adjust ...\n", - "- ... joint1 to 150 degrees,\n", - "- ... joint2 to 90 degreess,\n", - "- ... joint3 to 150 degrees,\n", - "- ... joint4 to -6 degrees,\n", - "- ... joint5 to 150 degrees,\n", - "- ... joint6 to 206 degrees,\n", - "- ... joint7 to 150 degrees." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "point.positions[0] = (150 * math.pi) / 180\n", - "point.positions[1] = (90 * math.pi) / 180\n", - "point.positions[2] = (150 * math.pi) / 180\n", - "point.positions[3] = -(6 * math.pi) / 180\n", - "point.positions[4] = (150 * math.pi) / 180\n", - "point.positions[5] = (206 * math.pi) / 180\n", - "point.positions[6] = (150 * math.pi) / 180\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Finally, we set the ``time_from_start`` to 2.5 seconds to define the duration of the movement. We then append the target ``point`` to the ``joint_trajectory`` and publish it. Between we pause for 1 second to give the trajectory time for the initialization. During the movement, we pause execution for 2.5 seconds to avoid interference. Once the movement is complete, we shut down the ``ROS node``." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "point.time_from_start = rospy.Duration(2.5) \n", - "\n", - "joint_trajectory.points.append(point)\n", - "\n", - "rospy.sleep(1.0)\n", - "\n", - "pub.publish(joint_trajectory)\n", - "\n", - "rospy.sleep(2.5)\n", - "\n", - "rospy.signal_shutdown(\"Task completed\")\n", - "\n", - "##### DO NOT CHANGE #####" - ] - } - ], - "metadata": { - "language_info": { - "name": "python" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_3.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_3.ipynb deleted file mode 100644 index b77aae0..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_1/exercise_1_3.ipynb +++ /dev/null @@ -1,186 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Educational Plattform Panda Robot\n", - "Author: uninh, uqwfa, ultck" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Exercise_1_3\n", - "\n", - "---\n", - "> In this task, you will learn ...\n", - ">\n", - "> - ... how to return the robot to his initial setup.\n", - "---" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "As always, we begin by importing the essential modules. " - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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", - "from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint\n", - "from sensor_msgs.msg import JointState\n", - "\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "rospy.init_node('exercise_1_3', anonymous=True)\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "You can choose to control the robot using the `MoveGroupCommander` or by publishing to relevant `rostopics`. Set the decision variable to `'move_group'` for MoveGroupCommander or to `'rostopics'` for control via rostopics. " - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### WRITE YOUR CODE HERE #####\n", - "\n", - "decision = 'move_group'\n", - "\n", - "##### WRITE YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We start by creating a ``JointTrajectory()`` object, the ROS message type that will later be used to publish our target joint values. Before that, we need to define its ``header`` and specify the ``joint_names`` to the default names.\n", - "\n", - "The default joint values are [0, -45, 0, -135, 0, 90, 45] degrees." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "if decision == 'move_group':\n", - " ##### YOUR CODE HERE IF YOU CHOOSED MOVEGROUPCOMMANDER #####\n", - "\n", - " roscpp_initialize(sys.argv)\n", - "\n", - " group = MoveGroupCommander(\"panda_arm\")\n", - " group.set_planner_id(\"RRTConnectkConfigDefault\")\n", - " group.set_planning_time(10)\n", - "\n", - " group.set_max_velocity_scaling_factor(1.0) # Set to 1.0 for maximum speed\n", - " group.set_max_acceleration_scaling_factor(1.0)\n", - "\n", - " joint_goal = group.get_current_joint_values()\n", - "\n", - " joint_goal[0] = 0.0\n", - " joint_goal[1] = -math.pi / 4\n", - " joint_goal[2] = 0.0\n", - " joint_goal[3] = -math.pi * 3 / 4\n", - " joint_goal[4] = 0.0\n", - " joint_goal[5] = math.pi / 2\n", - " joint_goal[6] = math.pi / 4\n", - "\n", - " group.set_joint_value_target(joint_goal)\n", - " group.go(wait=True)\n", - "\n", - " roscpp_shutdown()\n", - "\n", - " ##### YOUR CODE HERE IF YOU CHOOSED MOVEGROUPCOMMANDER #####\n", - "\n", - "elif decision == 'rostopic':\n", - " ##### YOUR CODE HERE IF YOU CHOOSED MOVEGROUPCOMMANDER #####\n", - "\n", - " pub = rospy.Publisher('/effort_joint_trajectory_controller/command', JointTrajectory, queue_size=10)\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", - " current_joint_values = rospy.wait_for_message('/joint_states', JointState, timeout=5).position\n", - " point = JointTrajectoryPoint()\n", - " point.positions = list(current_joint_values)\n", - "\n", - " point.positions[0] = (0 * math.pi) / 180\n", - " point.positions[1] = -(45 * math.pi) / 180\n", - " point.positions[2] = (0 * math.pi) / 180\n", - " point.positions[3] = -(135 * math.pi) / 180\n", - " point.positions[4] = (0 * math.pi) / 180\n", - " point.positions[5] = (90 * math.pi) / 180\n", - " point.positions[6] = (45 * math.pi) / 180\n", - "\n", - " point.time_from_start = rospy.Duration(2.5) \n", - "\n", - " joint_trajectory.points.append(point)\n", - " rospy.sleep(1.0)\n", - " pub.publish(joint_trajectory)\n", - "\n", - " rospy.sleep(2.5)\n", - " ##### YOUR CODE HERE IF YOU CHOOSED MOVEGROUPCOMMANDER #####\n", - "\n", - "else:\n", - " raise NotImplementedError\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "At the end we shutdown the ROS node." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "rospy.signal_shutdown(\"Task completed\")" - ] - } - ], - "metadata": { - "language_info": { - "name": "python" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_1.ipynb deleted file mode 100644 index 078a3d5..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_1.ipynb +++ /dev/null @@ -1,183 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Educational Plattform Panda Robot\n", - "Author: uninh, uqwfa, ultck" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Exercise_2_1\n", - "\n", - "---\n", - "> In this task, you will learn ...\n", - ">\n", - "> - ... how to move the robot using the cartesian values.\n", - "---" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "For this we need the `MoveGroupCommander`." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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": [ - "Initialize the ``MoveIt Commander``, launch a ``ROS node``, and create a ``MoveGroupCommander`` instance." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "roscpp_initialize(sys.argv)\n", - "rospy.init_node('exercise_2_1', anonymous=True)\n", - "group = MoveGroupCommander(\"panda_arm\")\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "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": {}, - "outputs": [], - "source": [ - "##### WRITE YOUR CODE HERE #####\n", - "\n", - "group.set_max_velocity_scaling_factor(1.0) \n", - "group.set_max_acceleration_scaling_factor(1.0)\n", - "\n", - "##### WRITE YOUR CODE HERE #####" - ] - }, - { - "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 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", - "For the orientation, we set all values to ``0.5``. For the position, we want to determine the location along the x-axis, so we set position.x to ``0.5``, position.y to ``0.0``, and position.z to ``0.2``, ensuring the gripper is not on the ground." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### WRITE YOUR CODE HERE #####\n", - "\n", - "target_pose = group.get_current_pose().pose\n", - "\n", - "target_pose.position.x = 0.5\n", - "target_pose.orientation.x = 0.5\n", - "\n", - "\n", - "target_pose.position.y = 0\n", - "target_pose.position.z = 0.2\n", - "\n", - "target_pose.orientation.y = 0.5\n", - "target_pose.orientation.z = 0.5\n", - "target_pose.orientation.w = 0.5\n", - "\n", - "##### WRITE YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now, we just need to set the ``target_pose`` and execute the movement." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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": [ - "And, as always, we shut down the initialized modules." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb deleted file mode 100644 index 9b3ccdc..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_2/exercise_2_2.ipynb +++ /dev/null @@ -1,207 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Educational Plattform Panda Robot\n", - "Author: uninh, uqwfa, ultck" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Exercise_2_2\n", - "\n", - "---\n", - "> In this task, you will learn ...\n", - ">\n", - "> - ... which joint values are needed to move the robot to a specific Cartesian pose.\n", - "---" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "For this we need the `MoveGroupCommander`." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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": [ - "Initialize the ``MoveIt Commander``, launch a ``ROS node``, and create a ``MoveGroupCommander`` instance." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "roscpp_initialize(sys.argv)\n", - "rospy.init_node('exercise_2_2', anonymous=True)\n", - "group = MoveGroupCommander(\"panda_arm\")\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "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": {}, - "outputs": [], - "source": [ - "##### WRITE YOUR CODE HERE #####\n", - "\n", - "group.set_max_velocity_scaling_factor(1.0) \n", - "group.set_max_acceleration_scaling_factor(1.0)\n", - "\n", - "##### WRITE YOUR CODE HERE #####" - ] - }, - { - "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 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", - "For the orientation, we set all values to ``0.5``. For the position, we want to determine the location along the x-axis, so we set position.x to ``0.5``, position.y to ``0.0``, and position.z to ``0.2``, ensuring the gripper is not on the ground." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### WRITE YOUR CODE HERE #####\n", - "\n", - "target_pose = group.get_current_pose().pose\n", - "\n", - "target_pose.position.x = -0.5\n", - "target_pose.orientation.x = 0.0\n", - "\n", - "\n", - "target_pose.position.y = -0.2\n", - "target_pose.position.z = 0.8\n", - "\n", - "target_pose.orientation.y = 0.0\n", - "target_pose.orientation.z = 0.0\n", - "target_pose.orientation.w = 1.0\n", - "\n", - "##### WRITE YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Now, we want to calculate the required joint values to move the robot to this Cartesian pose. For this we retrieve the joint values for the target pose from the final trajectory point of the planned motion. " - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### DO NOT CHANGE #####\n", - "\n", - "plan = group.plan(target_pose)\n", - "\n", - "joint_values = None\n", - "if plan:\n", - " joint_values = plan[1].joint_trajectory.points[-1].positions\n", - "\n", - "##### DO NOT CHANGE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Next we want to execute the movement with the ``joint_values``." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "##### YOUR CODE HERE #####\n", - "\n", - "group.set_joint_value_target(joint_values)\n", - "group.go(wait=True)\n", - "\n", - "##### YOUR CODE HERE #####" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "And, as always, we shut down the initialized modules." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "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 -} diff --git a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_3/exercise_3_1.ipynb b/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_3/exercise_3_1.ipynb deleted file mode 100644 index 3aab6e8..0000000 --- a/catkin_ws/src/learn_environment/task_pool/solution_scripts/beginner/exercise_3/exercise_3_1.ipynb +++ /dev/null @@ -1,78 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "TODO: FORMAT AS NOTEBOOK" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "vscode": { - "languageId": "plaintext" - } - }, - "outputs": [], - "source": [ - "#!/usr/bin/env python\n", - "\n", - "import sys\n", - "import rospy\n", - "import math\n", - "from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown\n", - "\n", - "\n", - "# \n", - "# task: add a sequence of joint values to the MoveGroupCommander and execute it\n", - "#\n", - "\n", - "# intialize the MoveIt! commander from the moveit_command package\n", - "roscpp_initialize(sys.argv)\n", - "\n", - "# initialize the ros node for the communication with the robot\n", - "rospy.init_node('exercise_3_1', anonymous=True)\n", - "\n", - "# create an instance of MoveGroupCommander for controlling the Panda arm\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", - "group.set_max_velocity_scaling_factor(1.0) # Set to 1.0 for maximum speed\n", - "group.set_max_acceleration_scaling_factor(1.0)\n", - "\n", - "joint_sequence = [\n", - " [0.5, -0.5, 0.5, -1.5, 0.5, 1.0, 0.5], # Position 1\n", - " [1.0, -1.0, 1.0, -2.0, 1.0, 0.5, 1.0], # Position 2\n", - " [2.7, -1.6, 2.7, -0.2, 2.7, 0.5, 2.7], # position 3\n", - " [1.0, -1.0, 1.0, -2.0, 1.0, 0.5, 1.0], # Position 2\n", - " [0.5, -0.5, 0.5, -1.5, 0.5, 1.0, 0.5], # Position 1\n", - " [0.0, -0.785, 0.0, -2.356, 0.0, 1.571, 0.785] # Home position\n", - "]\n", - "\n", - "for joint_goal in joint_sequence:\n", - " group.set_joint_value_target(joint_goal)\n", - " group.go(wait=True)\n", - " rospy.loginfo(\"goal reached\")\n", - " rospy.sleep(1)\n", - "\n", - "# delete the ros node\n", - "rospy.signal_shutdown(\"Task completed\")\n", - "roscpp_shutdown()" - ] - } - ], - "metadata": { - "language_info": { - "name": "python" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} 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 bc59994..44dcd5e 100644 --- a/catkin_ws/src/learn_environment/task_pool/task_definitions.json +++ b/catkin_ws/src/learn_environment/task_pool/task_definitions.json @@ -90,73 +90,6 @@ } ] }, - { - "title": "Task 1 (TODO: Rename)", - "description": "TODO: Add Description.", - "topic": "ROS Basics", - "difficulty": "beginner", - "previous_subtasks_required": true, - "folder": "/beginner/exercise_1", - "subtasks": [ - { - "title": "Subtask 1.1 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/exercise_1_1.ipynb", - "evaluation_file": "/exercise_1_1_eval.py", - "timeout_seconds": 60, - "parallelized_evaluation_required": false - }, - { - "title": "Subtask 1.2 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2. TODO: Add Subtask Description Subtask 2.", - "solution_file": "/exercise_1_2.ipynb", - "evaluation_file": "/exercise_1_2_eval.py" - }, - { - "title": "Subtask 1.3 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 3.", - "solution_file": "/exercise_1_3.ipynb", - "evaluation_file": "/exercise_1_3_eval.py" - } - ] - }, - { - "title": "Task 2 (TODO: Rename)", - "description": "TODO: Add Description.", - "topic": "ROS Basics", - "difficulty": "beginner", - "folder": "/beginner/exercise_2", - "subtasks": [ - { - "title": "Subtask 2.1 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/exercise_2_1.ipynb", - "evaluation_file": "/exercise_2_1_eval.py" - }, - { - "title": "Subtask 2.2 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 2.", - "solution_file": "/exercise_2_2.ipynb", - "evaluation_file": "/exercise_2_2_eval.py" - } - ] - }, - { - "title": "Task 3 (TODO: Rename)", - "description": "TODO: Add Description.", - "topic": "ROS Basics", - "difficulty": "strange_difficulty", - "folder": "/beginner/exercise_3", - "subtasks": [ - { - "title": "Subtask 3.1 (TODO: Rename)", - "description": "TODO: Add Subtask Description Subtask 1.", - "solution_file": "/exercise_3_1.ipynb", - "evaluation_file": "/exercise_3_1_eval.py", - "parallelized_evaluation_required": true - } - ] - }, { "title": "Task 4 (TODO: Rename)", "description": "TODO: Add Description.", -- GitLab